ros2_socketcan
ros2_socketcan copied to clipboard
previously received data remains
Description
If the DLC(Data Length Code) is less than 8, the previously received data remains in the "data" field of the topic sent by ros2_socketcan.
When supporting multiple types of HW with the same CAN-ID but different DLCs, unintended behavior may occur if garbage is included in the reception result of can_receiver.
I checked with the following steps.
Preparation
- Install can-utils
sudo apt install can-utils
- Enable vcan
sudo modprobe vcan
sudo ip link add dev vcan0 type vcan
sudo ip link set up vcan0
- Invoke ros2_socketcan
ros2 launch ros2_socketcan socket_can_bridge.launch.xml interface:=vcan0
- Invoke candump
candump vcan0
- Topic monitoring
ros2 topic echo /from_can_bus
Procedure
Send the following CAN data with cansend.
cansend vcan0 200#1122334455667788
cansend vcan0 123#aa
Output
- candump output
vcan0 200 [8] 11 22 33 44 55 66 77 88
vcan0 123 [1] AA
- Topic output
header:
stamp:
sec: 1661924425
nanosec: 956480272
frame_id: can
id: 512
is_rtr: false
is_extended: false
is_error: false
dlc: 8
data:
- 17
- 34
- 51
- 68
- 85
- 102
- 119
- 136
---
header:
stamp:
sec: 1661924437
nanosec: 538097128
frame_id: can
id: 291
is_rtr: false
is_extended: false
is_error: false
dlc: 1
data:
- 170
- 34
- 51
- 68
- 85
- 102
- 119
- 136
---
Closed by #18.