Skip to content

Commit

Permalink
Refactor to use ostream for readability
Browse files Browse the repository at this point in the history
  • Loading branch information
Rayman committed Apr 30, 2024
1 parent 12f384c commit 6f2f79b
Show file tree
Hide file tree
Showing 2 changed files with 8 additions and 8 deletions.
2 changes: 1 addition & 1 deletion include/nobleo_socketcan_bridge/socketcan_bridge.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@ class SocketCanBridge
SocketCanBridge & operator=(const SocketCanBridge & other) = delete;
SocketCanBridge & operator=(SocketCanBridge && other) noexcept = delete;

void write(const can_msgs::msg::Frame & msg);
void __attribute__((noinline)) write(const can_msgs::msg::Frame & msg);

void close();

Expand Down
14 changes: 7 additions & 7 deletions src/socketcan_bridge.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@
#include "nobleo_socketcan_bridge/socketcan_bridge.hpp"

#include <fmt/core.h>
#include <fmt/ostream.h>
#include <linux/can/raw.h>
#include <net/if.h>
#include <sys/ioctl.h>
Expand All @@ -16,14 +17,13 @@

namespace nobleo_socketcan_bridge
{

std::string to_string(const can_msgs::msg::Frame & msg)
std::ostream & operator<<(std::ostream & os, const can_msgs::msg::Frame & msg)
{
auto result = fmt::format("{:0>3X} [{}]", msg.id, msg.dlc);
fmt::print(os, "{:0>3X} [{}]", msg.id, msg.dlc);
for (auto i = 0; i < msg.dlc; ++i) {
result += fmt::format(" {:0>2X}", msg.data[i]);
fmt::print(os, " {:0>2X}", msg.data[i]);
}
return result;
return os;
}

SocketCanBridge::SocketCanBridge(
Expand Down Expand Up @@ -69,7 +69,7 @@ void SocketCanBridge::write(const can_msgs::msg::Frame & msg)
frame.can_id = msg.id;
frame.len = msg.dlc;
std::copy(msg.data.begin(), msg.data.end(), frame.data);
RCLCPP_DEBUG(logger_, "Sending %s", to_string(msg).c_str());
RCLCPP_DEBUG_STREAM(logger_, "Sending " << msg);
auto n = ::write(socket_, &frame, sizeof(frame));
if (n < 0) {
throw std::system_error(errno, std::generic_category());
Expand Down Expand Up @@ -111,7 +111,7 @@ void SocketCanBridge::read_loop(std::stop_token stoken)
msg.dlc = frame.len;
std::copy_n(frame.data, sizeof(frame.data), msg.data.begin());

RCLCPP_DEBUG(logger_, "Received %s", to_string(msg).c_str());
RCLCPP_DEBUG_STREAM(logger_, "Received " << msg);
receive_callback_(msg);
}
RCLCPP_INFO(logger_, "Read loop stopped");
Expand Down

0 comments on commit 6f2f79b

Please sign in to comment.