diff --git a/ros2_socketcan/launch/socket_can_bridge.launch.xml b/ros2_socketcan/launch/socket_can_bridge.launch.xml
index 1992c52..cbfd729 100644
--- a/ros2_socketcan/launch/socket_can_bridge.launch.xml
+++ b/ros2_socketcan/launch/socket_can_bridge.launch.xml
@@ -6,12 +6,14 @@
+
+
diff --git a/ros2_socketcan/src/socket_can_receiver.cpp b/ros2_socketcan/src/socket_can_receiver.cpp
index f60d2df..96aa2b2 100644
--- a/ros2_socketcan/src/socket_can_receiver.cpp
+++ b/ros2_socketcan/src/socket_can_receiver.cpp
@@ -171,18 +171,28 @@ 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));
+
// Checks
if (nbytes < 0) {
throw std::runtime_error{strerror(errno)};
}
- if (static_cast(nbytes) < sizeof(frame)) {
- throw std::runtime_error{"read: incomplete CAN FD frame"};
+
+ if (static_cast(nbytes) < sizeof(frame.can_id) + sizeof(frame.len)) {
+ throw std::runtime_error{"read: corrupted CAN frame"};
}
- if (static_cast(nbytes) != sizeof(frame)) {
- throw std::logic_error{"Message was wrong size"};
+
+ if (frame.len > CANFD_MAX_DLEN) {
+ throw std::runtime_error{"read: frame length is larger than max allowed CAN FD payload length"};
}
- // Write
+
const auto data_length = static_cast(frame.len);
+ // some CAN FD frames are shorter than 64 bytes
+ const auto expected_length = sizeof(frame) - sizeof(frame.data) + data_length;
+
+ if (static_cast(nbytes) < expected_length) {
+ throw std::runtime_error{"read: incomplete CAN FD frame"};
+ }
+ // Write
(void)std::memcpy(data, static_cast(&frame.data[0U]), data_length);
// get bus timestamp