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(socket_can_receiver): support variable-length CAN FD frames #50

Merged
merged 5 commits into from
Sep 25, 2024
Merged
Show file tree
Hide file tree
Changes from 1 commit
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
2 changes: 2 additions & 0 deletions ros2_socketcan/launch/socket_can_bridge.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -6,12 +6,14 @@
<arg name="enable_can_fd" default="false" />
<arg name="from_can_bus_topic" default="from_can_bus" />
<arg name="to_can_bus_topic" default="to_can_bus" />
<arg name="use_bus_time" default="false" />

<include file="$(find-pkg-share ros2_socketcan)/launch/socket_can_receiver.launch.py">
<arg name="interface" value="$(var interface)" />
<arg name="interval_sec" value="$(var receiver_interval_sec)" />
<arg name="enable_can_fd" value="$(var enable_can_fd)" />
<arg name="from_can_bus_topic" value="$(var from_can_bus_topic)" />
<arg name="use_bus_time" value="$(var use_bus_time)" />
</include>

<include file="$(find-pkg-share ros2_socketcan)/launch/socket_can_sender.launch.py">
Expand Down
9 changes: 4 additions & 5 deletions ros2_socketcan/src/socket_can_receiver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -171,18 +171,17 @@ CanId SocketCanReceiver::receive_fd(void * const data, const std::chrono::nanose
// Read
struct canfd_frame frame;
const auto nbytes = read(m_file_descriptor, &frame, sizeof(frame));
const auto data_length = static_cast<CanId::LengthT>(frame.len);
const auto expected_length = sizeof(frame) - sizeof(frame.data) + data_length;

// Checks
if (nbytes < 0) {
throw std::runtime_error{strerror(errno)};
}
knzo25 marked this conversation as resolved.
Show resolved Hide resolved
if (static_cast<std::size_t>(nbytes) < sizeof(frame)) {
if (static_cast<std::size_t>(nbytes) < expected_length) {
xmfcx marked this conversation as resolved.
Show resolved Hide resolved
throw std::runtime_error{"read: incomplete CAN FD frame"};
}
if (static_cast<std::size_t>(nbytes) != sizeof(frame)) {
throw std::logic_error{"Message was wrong size"};
}
// Write
const auto data_length = static_cast<CanId::LengthT>(frame.len);
(void)std::memcpy(data, static_cast<void *>(&frame.data[0U]), data_length);

// get bus timestamp
Expand Down
Loading