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

Add processing for all CAN flags #3

Merged
merged 1 commit into from
May 2, 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
5 changes: 5 additions & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -63,8 +63,13 @@ else()
endif()

if(BUILD_TESTING)
find_package(ament_cmake_gtest)
find_package(ament_lint_auto REQUIRED)

ament_lint_auto_find_test_dependencies()

ament_add_gtest(unittests test/unittests.cpp)
target_link_libraries(unittests socketcan_bridge_component)
endif()

ament_export_include_directories(
Expand Down
7 changes: 7 additions & 0 deletions include/ros2_socketcan_bridge/socketcan_bridge.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,8 @@
#include "rclcpp/clock.hpp"
#include "rclcpp/logger.hpp"

// forward declarations
struct can_frame;
namespace rclcpp
{
class Node;
Expand Down Expand Up @@ -49,4 +51,9 @@ class SocketCanBridge
std::jthread receive_thread_;
};

can_frame from_msg(const can_msgs::msg::Frame & msg);

can_msgs::msg::Frame to_msg(const can_frame & frame);
;

} // namespace ros2_socketcan_bridge
44 changes: 30 additions & 14 deletions src/socketcan_bridge.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@

#include <fmt/core.h>
#include <fmt/ostream.h>
#include <linux/can/raw.h>
#include <linux/can.h>
#include <net/if.h>
#include <sys/ioctl.h>
#include <sys/socket.h>
Expand Down Expand Up @@ -65,13 +65,7 @@ SocketCanBridge::SocketCanBridge(

void SocketCanBridge::send(const can_msgs::msg::Frame & msg)
{
can_frame frame;
frame.can_id = msg.id;
frame.len = msg.dlc;
if (msg.is_extended) {
frame.can_id |= CAN_EFF_FLAG;
}
std::copy(msg.data.begin(), msg.data.end(), frame.data);
auto frame = from_msg(msg);
RCLCPP_DEBUG_STREAM(logger_, "Sending " << msg);
auto n = write(socket_, &frame, sizeof(frame));
if (n < 0) {
Expand Down Expand Up @@ -107,18 +101,40 @@ void SocketCanBridge::receive_loop(std::stop_token stoken)
if (nbytes != sizeof(frame)) {
throw std::runtime_error("Partial CAN frame received");
}
const bool ext = ((frame.can_id & CAN_EFF_FLAG) == CAN_EFF_FLAG);
can_msgs::msg::Frame msg;

auto msg = to_msg(frame);
msg.header.stamp = clock_->now();
msg.id = frame.can_id & (ext ? CAN_EFF_MASK : CAN_SFF_MASK);
msg.dlc = frame.len;
msg.is_extended = ext;
std::copy_n(frame.data, sizeof(frame.data), msg.data.begin());

RCLCPP_DEBUG_STREAM(logger_, "Received " << msg);
receive_callback_(msg);
}
RCLCPP_INFO(logger_, "Receive loop stopped");
}

can_frame from_msg(const can_msgs::msg::Frame & msg)
{
canid_t id = msg.id;
if (msg.is_rtr) id |= CAN_RTR_FLAG;
if (msg.is_extended) id |= CAN_EFF_FLAG;
if (msg.is_error) id |= CAN_ERR_FLAG;

can_frame frame;
frame.can_id = id;
frame.len = msg.dlc;
std::copy(msg.data.begin(), msg.data.end(), frame.data);
return frame;
}

can_msgs::msg::Frame to_msg(const can_frame & frame)
{
can_msgs::msg::Frame msg;
msg.is_rtr = (frame.can_id & CAN_RTR_FLAG) == CAN_RTR_FLAG;
msg.is_extended = (frame.can_id & CAN_EFF_FLAG) == CAN_EFF_FLAG;
msg.is_error = (frame.can_id & CAN_ERR_FLAG) == CAN_ERR_FLAG;
msg.id = frame.can_id & (msg.is_extended ? CAN_EFF_MASK : CAN_SFF_MASK);
msg.dlc = frame.len;
std::copy_n(frame.data, sizeof(frame.data), msg.data.begin());
return msg;
}

} // namespace ros2_socketcan_bridge
50 changes: 50 additions & 0 deletions test/unittests.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,50 @@
// Copyright (C) 2024 Nobleo Technology B.V.
//
// SPDX-License-Identifier: Apache-2.0

#include <gtest/gtest.h>
#include <linux/can.h>

#include "ros2_socketcan_bridge/socketcan_bridge.hpp"

using ros2_socketcan_bridge::from_msg;
using ros2_socketcan_bridge::to_msg;

TEST(from_msg, standard)
{
can_msgs::msg::Frame msg;
msg.id = 13;
auto frame = from_msg(msg);
EXPECT_EQ(frame.can_id, 13);
}

TEST(from_msg, extended)
{
can_msgs::msg::Frame msg;
msg.id = 13;
msg.is_extended = true;
auto frame = from_msg(msg);
EXPECT_EQ(frame.can_id, 13 | CAN_EFF_FLAG);
}

TEST(to_msg, standard)
{
struct can_frame frame;
frame.can_id = 13;
auto msg = to_msg(frame);
EXPECT_EQ(msg.id, 13);
EXPECT_FALSE(msg.is_rtr);
EXPECT_FALSE(msg.is_extended);
EXPECT_FALSE(msg.is_error);
}

TEST(to_msg, extended)
{
struct can_frame frame;
frame.can_id = 13 | CAN_EFF_FLAG;
auto msg = to_msg(frame);
EXPECT_EQ(msg.id, 13);
EXPECT_FALSE(msg.is_rtr);
EXPECT_TRUE(msg.is_extended);
EXPECT_FALSE(msg.is_error);
}
Loading