PS:本文需要的先行知识请自行补充

本文提供了两种方法实现CAN通讯:

  1. 自行使用linux的socket,完成CAN通讯的封装,并部署于ROS中;

  2. 使用ROS提供的CANopen功能包,完成CAN通讯,并提供使用案例;

Socket

Socket(套接字)是一种用于实现网络通信的编程接口(API),它提供了一种标准化的方式,使得不同操作系统和编程语言之间的应用程序能够相互通信。

环境部署

工程环境:RK3588 + Ubuntu 20.04.2 LTS + ROS-noetic

默认工作空间已建立,环境变量已导入脚本;

创建功能包:catkin_create_pkg mysocketcan_pkg roscpp rospy std_msgs

1.linux-socket

部分源码

代码需包含的头文件:

1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
#include <cstdio>
#include <cstdlib>
#include <cstring>
#include <iostream>
#include <stdexcept>
#include <sstream>

#include <unistd.h>
#include <sys/ioctl.h>
#include <sys/socket.h>
#include <linux/can.h>
#include <linux/can/raw.h>
#include <net/if.h>

#include <termios.h>

部分宏定义:

在本次应用中,linux中CAN的接口需要通过shell系统指令打开,并进行设置,因此对部分指令进行了宏定义

1
2
3
4
5
6
#define CAN_DEV  "can0"
#define up "ifconfig can0 up"
#define down "ifconfig can0 down"
#define command "/sbin/ip link set can0 type can bitrate 1000000"
#define CAN_Loop "/sbin/ip link set can0 type can loopback on"
#define CAN_Loop_OFF "/sbin/ip link set can0 type can loopback off"

类:

1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21

class Socket_Can
{
public:
Socket_Can();
~Socket_Can();

void Init();
void send_can_frame(const struct can_frame& xframe);
void receive_can_frame(struct can_frame& xframe);
void close_socket();

private:
struct ifreq ifr = {0};
// struct can_bittiming btr = {0};
struct sockaddr_can can_addr = {0};
struct can_frame frame = {0};
int socket_fd = -1;
int ret;
struct can_filter rfilter[2];
};

对应封装:

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
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100

Socket_Can::Socket_Can()
{
/*打开套接字*/
socket_fd = socket(PF_CAN,SOCK_RAW, CAN_RAW);
if(0 > socket_fd)
{
throw std::runtime_error("socket error!");//std::system_error

}

}

Socket_Can::~Socket_Can()
{
close_socket();
}

void Socket_Can::close_socket()
{
::close(socket_fd);// 关闭套接字
}


void Socket_Can::Init()
{

system(down); //这里用到了上方提到的宏定义/*
system(command);
// system(CAN_Loop);
system(up);


/*指定CAN设备*/
strcpy(ifr.ifr_name,CAN_DEV);
ret = ioctl(socket_fd,SIOCGIFINDEX, &ifr);
can_addr.can_family = AF_CAN; /*填充数据*/
can_addr.can_ifindex = ifr.ifr_ifindex;
if(ret < 0)
{
std::stringstream ss;
ss << "Failed to get index for " << CAN_DEV << " device";
throw std::runtime_error(ss.str());
}
/* 将can0与套接字进行绑定 */
ret = bind(socket_fd, (struct sockaddr *)&can_addr, sizeof(can_addr));
if(ret < 0)
{
throw std::runtime_error("bind error!");
}



// ifr.ifr_flags &= ~IFF_UP; //
// ret = ioctl(socket_fd, SIOCSIFFLAGS, &ifr);



// ifr.ifr_flags |= IFF_UP; // 开启接口
// ret = ioctl(socket_fd, SIOCSIFFLAGS, &ifr);
// if(ret < 0)
// {
// throw std::runtime_error("Error bringing up CAN interface");
// }

/* 设置过滤规则:不接受任何报文、仅发送数据 */
setsockopt(socket_fd, SOL_CAN_RAW, CAN_RAW_FILTER, NULL, 0);


// rfilter[0].can_id = 0x60A;
// rfilter[0].can_mask = 0x7FF;
// rfilter[1].can_id = 0x60B;
// rfilter[1].can_mask = 0x7FF;
// // 调用 setsockopt 设置过滤规则
// setsockopt(sockfd, SOL_CAN_RAW, CAN_RAW_FILTER, &rfilter, sizeof(rfilter));


}


void Socket_Can::send_can_frame(const struct can_frame& xframe)
{
ret = write(socket_fd,&xframe,sizeof(xframe));
if(ret != sizeof(xframe))
{
throw std::runtime_error("CAN_Send error!");
}

}


void Socket_Can::receive_can_frame( struct can_frame& xframe)
{
ret = read(socket_fd,&xframe,sizeof(xframe));
// if(ret != sizeof(xframe))
// {
// throw std::runtime_error("CAN_Read error!");
// }

}

节点测试:

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
51
int main(int argc,char **argv)
{

Socket_Can socket_can;

ros::init(argc,argv,"socket_can_publisher");
ros::NodeHandle seuNB;
ros::Rate loop_rate(1);

try{
socket_can.Init();
}
catch(const std::runtime_error& e)
{
socket_can.close_socket();
}

// ros::Publisher tree = seuNB.advertise<sensor_msgs::Imu>("MPU9250_Topic",10);

struct can_frame my_frame;
struct can_frame rec_frame;
/*TEST*/
my_frame.can_id = 0x123;
my_frame.can_dlc = 8;
my_frame.data[0]= 0x10;
my_frame.data[1]= 0x20;
my_frame.data[2]= 0x30;
my_frame.data[3]= 0x40;

my_frame.data[4]= 0x50;
my_frame.data[5]= 0x60;
my_frame.data[6]= 0x70;
my_frame.data[7]= 0x80;

while(ros::ok())
{
printf("Test_Run\r\n");
try{
socket_can.send_can_frame(my_frame);
socket_can.receive_can_frame(rec_frame);

printf("data:%x\r\n",rec_frame.data[1]);
}
catch(const std::runtime_error& e)
{
socket_can.close_socket();
}
// tree.publish(imu_msg);
loop_rate.sleep();
}
}

工程概述

本例程中使用 “can0”

CAN波特率设置为10000000(1M)

功能:
通过调用以socket的API封装的函数,完成对CAN接口的调用,并在ROS的节点中完成了对应的CAN通讯;

2.ROS-canopen

canopen功能包组成:
{

socketcan_interface //底层包/*

socketcan_bridge //基于socketcan,内含了socketcan_interface/*

ros_canopen //基于canopen/*

}

ROS官方wiki:
https://wiki.ros.org/ros_canopen

ROS_canopen GitHub:
https://github.com/ros-industrial/ros_canopen

使用其中的socketcan_bridge 实现can通信

默认工作空间已建立,环境变量已导入脚本;

直接使用Git指令拉取代码到工作空间/src下:

git clone https://github.com/ros-industrial/ros_canopen.git

也可以在github中下载zip文件,同样放到工作空间/src下:

执行解压即可:
unzip ros_canopen-melodic-devel.zip

建议提前安装一个缺少的驱动 (避免报错):
sudo apt-get install libmuparser-dev

回到工作空间编译:catkin_make

开启can,源码中默认使用的是can0:

1
2
3
ifconfig can0 down
ip link set can0 type can bitrate 1000000 //设置对应波特率/*
ifconfig can0 up

编译完成后开启ros:roscore

开启节点:rosrun socketcan_bridge socketcan_to_topic_node

订阅节点信息:rostopic echo /received_messages,就可以正常接收和显示can报文

订阅的话题名称:sent_messages(can_msgs/Frame),此处收到的消息将被发送到 SocketCAN 设备

发布的话题名称:received_messages (can_msgs/Frame),在 SocketCAN 设备上接收到的帧在本主题中发布

ROS节点参数:~can_device (string, default: can0),SocketCAN 设备的名称,默认情况下这些设备被命名为can0及以上。

1
2
3
4
5
6
7
8
<launch>
<node pkg="socketcan_bridge" type="socketcan_bridge_node" name="socketcan_bridge_node" output="screen">
<param name="can_device" value="can0"/>
<remap from="sent_messages" to="your_topic_name"/>
<remap from="received_messages" to="your_topic_name"/>

</node>
<launch>

设置多路CAN口:

socketcan_bridge_node.cpp

中设置为 nh_param.getParam(“can_device” ,can_device);

配置launch文件中的各个CAN口;注意命名空间