Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Fix sonarcloud issues #5

Merged
merged 1 commit into from
May 24, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
6 changes: 3 additions & 3 deletions include/ros2_socketcan_bridge/socketcan_bridge.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,19 +30,19 @@ class SocketCanBridge
const rclcpp::Logger & logger, rclcpp::Clock::SharedPtr clock, const std::string & interface,
double read_timeout, const CanCallback & receive_callback);

~SocketCanBridge() { close(); }
~SocketCanBridge();

SocketCanBridge(const SocketCanBridge &) = delete;
SocketCanBridge(SocketCanBridge &&) noexcept = delete;
SocketCanBridge & operator=(const SocketCanBridge & other) = delete;
SocketCanBridge & operator=(SocketCanBridge && other) noexcept = delete;

void send(const can_msgs::msg::Frame & msg);
void send(const can_msgs::msg::Frame & msg) const;

void close();

private:
void receive_loop(std::stop_token stoken);
void receive_loop(std::stop_token stoken) const;

rclcpp::Logger logger_;
rclcpp::Clock::SharedPtr clock_;
Expand Down
17 changes: 14 additions & 3 deletions src/socketcan_bridge.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -63,7 +63,17 @@ SocketCanBridge::SocketCanBridge(
receive_thread_ = std::jthread{std::bind(&SocketCanBridge::receive_loop, this, _1)};
}

void SocketCanBridge::send(const can_msgs::msg::Frame & msg)
SocketCanBridge::~SocketCanBridge()
{
try {
close();
} catch (const std::system_error & e) {
// closing the socket could fail, but we should not propagate exceptions out of the destructor
RCLCPP_ERROR(logger_, "%s", e.what());
}
}
Copy link
Collaborator Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I'm not sure if this try catch will make sonarcloud happy, but lets try


void SocketCanBridge::send(const can_msgs::msg::Frame & msg) const
{
auto frame = from_msg(msg);
RCLCPP_DEBUG_STREAM(logger_, "Sending " << msg);
Expand All @@ -88,7 +98,7 @@ void SocketCanBridge::close()
}
}

void SocketCanBridge::receive_loop(std::stop_token stoken)
void SocketCanBridge::receive_loop(std::stop_token stoken) const
{
RCLCPP_INFO(logger_, "Receive loop started");
while (!stoken.stop_requested()) {
Expand All @@ -99,7 +109,8 @@ void SocketCanBridge::receive_loop(std::stop_token stoken)
throw std::system_error(errno, std::generic_category());
}
if (nbytes != sizeof(frame)) {
throw std::runtime_error("Partial CAN frame received");
RCLCPP_ERROR(logger_, "Incomplete CAN frame received, skipping");
continue;
}

auto msg = to_msg(frame);
Expand Down
Loading