CAN Communication

1. Virtual CAN

1.1 Setup virtual CAN

在Linux主机上通过以下命令可以设置虚拟CAN端口,“pcan0”作为端口名称,任意设置。
并且可以设置多个虚拟CAN端口,满足不同的测试需求。

1
2
3
4
5
6
sudo ip link add dev pcan0 type vcan
sudo ip link set up pcan0
sudo ip link add dev pcan1 type vcan
sudo ip link set up pcan1
sudo ip link add dev can0 type vcan
sudo ip link set up can0

1.2 Send CAN frame

向pcan0端口,发送CAN ID为0x123的数据帧一次。

1
cansend pcan0 123#0011223344556677

每间隔0.1秒,向pcan0端口,发送CAN ID为0x123的数据帧一次。

watch命令最小支持0.1秒。

1
watch -n 0.1 cansend pcan0 123#0011223344556677

1.3 Send CAN frame with heartbeat infomation

很多CAN数据都有heartbeat信息,用来确认CAN通信是否正常。

这是我自己在开发中经常用的一个脚本,可以模拟CAN数据的heartbeat信息。

1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
#!/bin/bash

while true
do
for i in {1..255}
do

# var=$(echo "obase=16; ibase=10; $i" | bc)
var=$(printf %02X $i)
# echo $var
`cansend pcan0 300#00000000000000${var}`

# Duplicate test
# `cansend pcan0 300#0000000000000022`

/bin/sleep 0.001
done
done

2. Socket CAN with ROS

在ROS中,要经常涉及到CAN端口的通信。这次主要记录一个ROS节点如何与多个CAN端口进行通信。
没有任何难度,都是干货。

1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
<launch>
<!-- 定义CAN端口名称 -->
<arg name="main_can_device" default="pcan0"/>
<arg name="sub_can_device" default="pcan1"/>

<!-- 设置该节点的参数文件 -->
<arg name="vehicle_can_interface_param_path" default="$(find-pkg-share vehicle_can_interface)/config/vehicle_can_interface.param.yaml"/>

<!-- 根据需要可以设置是否读取sub can端口信息 -->
<arg name="launch_sub_can" default="true" description="launch sub can device"/>

<!-- 设置main can device参数 -->
<group>
<!-- 对main can device的topic名加上命名空间 -->
<push-ros-namespace namespace="$(var main_can_device)"/>
<include file="$(find-pkg-share ros2_socketcan)/launch/socket_can_bridge.launch.xml">
<!-- 设置main can device参数 -->
<arg name="interface" value="$(var main_can_device)"/>
<arg name="receiver_interval_sec" value="1.0"/>
<arg name="sender_timeout_sec" value="0.02"/>
</include>
</group>

<!-- 如果读取sub can端口参数为true,则执行以下group -->
<group if="$(var launch_sub_can)">
<!-- 对main can device的topic名加上命名空间 -->
<push-ros-namespace namespace="$(var sub_can_device)"/>
<include file="$(find-pkg-share ros2_socketcan)/launch/socket_can_bridge.launch.xml">
<!-- 设置sub can device参数 -->
<arg name="interface" value="$(var sub_can_device)"/>
<arg name="receiver_interval_sec" value="1.0"/>
<arg name="sender_timeout_sec" value="0.02"/>
</include>
</group>

<!-- 节点的详细设定 -->
<node pkg="vehicle_can_interface" name="vehicle_can_interface" exec="vehicle_can_interface" output="screen">
<!-- 读取参数 -->
<param from="$(var vehicle_can_interface_param_path)"/>
<!-- REMAP -->
<remap from="input/from_can_bus" to="$(var main_can_device)/from_can_bus"/>
<remap from="input/from_brake_can_bus" to="$(var sub_can_device)/from_can_bus"/>
<remap from="input/b0_command" to="can/command/b0_command"/>
...
<remap from="output/to_can_bus" to="$(var main_can_device)/to_can_bus"/>
<remap from="output/to_brake_can_bus" to="$(var sub_can_device)/to_can_bus"/>
<remap from="output/b0_status" to="can/status/b0_status"/>
...
</node>
</launch>