基于 cantools 的 DBC 文件自动生成 C/C++ 代码与 ROS 集成

DBC: Database Can
ROS: Robot Operating System
Message - 报文,Signal - 信号
Encode - 编码,Decode - 解码,Pack - 打包,Unpack - 解包

文章目录

  • 代码生成丨cantools
    • 生成的四种函数
    • 函数示例
  • ROS 集成丨socketcan_bridge
    • ROS 话题与 CAN 报文的相互转换
    • CAN 发送:编码 + 打包
    • CAN 接收:解包 + 解码

代码生成丨cantools

DBC 文件以纯文本(txt)形式对 CAN 报文中的数据进行了定义,在使用 DBC 文件进行代码生成之前,建议先用 CANdb++ 软件尝试打开该文件以确定其格式没有问题。这里以开源工具 cantools 提供的 motohawk.dbc (Github 文件链接 link)为例:

基于 cantools 的 DBC 文件自动生成 C/C++ 代码与 ROS 集成_第1张图片

确认 DBC 文件格式正确后,安装 cantools:python3 -m pip install cantools(建议在虚拟环境中安装)。随后即可针对指定 DBC 文件生成 C/C++ 代码:

python3 -m cantools generate_c_source tests/files/dbc/motohawk.dbc

以上指令都是在命令行输入的,无需 Python 编程知识。执行上述指令后,会生成和 DBC 文件同名的 .c.h 代码文件,代码文件中的函数名会以 DBC 文件名开头。

生成的四种函数

CAN 通讯中,信号是报文的下一级,一条 CAN 报文中可以包含多个信号。所以:
【发送报文时】先编码信号,然后打包报文
【接收报文时】先解包报文,然后解码信号

这就对应了代码文件中的四种函数:encode,pack,unpack,decode。

  • encode:将具有实际意义的信号数值转换为 int 或 unsigned int 类型的信号数值
  • decode:将 int 或 unsigned int 类型的信号数值转换为具有实际意义的信号数值
  • pack:将多个 int 或 unsigned int 类型的信号数值合并成一条报文
  • unpack:将一条报文分解成多个 int 或 unsigned int 类型的信号数值

pack & unpack 时考虑了信号的布置(layout,包括各个信号的起始位 Startbit 与长度 length)以及格式(Byte Oder,Intel 或 Motorola);encode & decode 时考虑了信号数值的缩放系数(Factor)和偏移量(Offset)。当然,这些考虑都能由生成出的代码文件自动完成,我们调用函数即可。

函数示例

自动生成的 pack 函数:

int motohawk_example_message_pack(
    uint8_t *dst_p,
    const struct motohawk_example_message_t *src_p,
    size_t size)
{
    uint16_t temperature;

    if (size < 8u) {
        return (-EINVAL);
    }

    memset(&dst_p[0], 0, 8);

    dst_p[0] |= pack_left_shift_u8(src_p->enable, 7u, 0x80u);
    dst_p[0] |= pack_left_shift_u8(src_p->average_radius, 1u, 0x7eu);
    temperature = (uint16_t)src_p->temperature;
    dst_p[0] |= pack_right_shift_u16(temperature, 11u, 0x01u);
    dst_p[1] |= pack_right_shift_u16(temperature, 3u, 0xffu);
    dst_p[2] |= pack_left_shift_u16(temperature, 5u, 0xe0u);

    return (8);
}

自动生成的 unpack 函数:

int motohawk_example_message_unpack(
    struct motohawk_example_message_t *dst_p,
    const uint8_t *src_p,
    size_t size)
{
    uint16_t temperature;

    if (size < 8u) {
        return (-EINVAL);
    }

    dst_p->enable = unpack_right_shift_u8(src_p[0], 7u, 0x80u);
    dst_p->average_radius = unpack_right_shift_u8(src_p[0], 1u, 0x7eu);
    temperature = unpack_left_shift_u16(src_p[0], 11u, 0x01u);
    temperature |= unpack_left_shift_u16(src_p[1], 3u, 0xffu);
    temperature |= unpack_right_shift_u16(src_p[2], 5u, 0xe0u);

    if ((temperature & (1u << 11)) != 0u) {
        temperature |= 0xf000u;
    }

    dst_p->temperature = (int16_t)temperature;

    return (0);
}

自动生成的 encode 函数:

uint8_t motohawk_example_message_enable_encode(double value)
{
    return (uint8_t)(value);
}

uint8_t motohawk_example_message_average_radius_encode(double value)
{
    return (uint8_t)(value / 0.1);
}

int16_t motohawk_example_message_temperature_encode(double value)
{
    return (int16_t)((value - 250.0) / 0.01);
}

自动生成的 decode 函数:

double motohawk_example_message_enable_decode(uint8_t value)
{
    return ((double)value);
}

double motohawk_example_message_average_radius_decode(uint8_t value)
{
    return ((double)value * 0.1);
}

double motohawk_example_message_temperature_decode(int16_t value)
{
    return (((double)value * 0.01) + 250.0);
}

ROS 集成丨socketcan_bridge

ROS 话题与 CAN 报文的相互转换

使用 socketcan_bridge 实现ROS 话题与 CAN 报文的相互转换,即工控机收到的 CAN 报文会由 socketcan_bridge 以 can_msgs/Frame 类型的消息发布到 received_messages 话题上,socketcan_bridge 同时订阅 sent_messages 话题并将收到的 can_msgs/Frame 类型的消息发送到 CAN 总线上。

可以通过 rosrun socketcan_bridge socketcan_bridge_node 来测试功能包是否存在。若 ROS 中没有预装该功能包,其开源地址为 link ,下载 socketcan_bridge 文件夹到工作空间后编译即可。除了双向转换,socketcan_bridge 还提供单向转换的功能,详见 Github 文件 link。

launch 文件用法示例如下。该示例启动了一个 socketcan_bridge 节点,其发布 can0/received_messages 话题、订阅 can0/sent_messages (多了前缀是由于 ns="can0"),并在工控机的 can0 设备上接收和发送 CAN 报文。工控机 can 设备的启动建议咨询供应商,可能涉及 busybox devmemip link set 等命令行指令。

<node ns="can0" pkg="socketcan_bridge" type="socketcan_bridge_node" name="socketcan_bridge_node" output="screen">
    <param name="can_device" value="can0" />
node>

CAN 发送:编码 + 打包

需实现的功能为 ROS 节点编码并打包发送出 can_msgs/Frame 类型的消息到 sent_messages 话题,剩下的工作由 socketcan_bridge 完成。以下代码依旧以 motohawk.dbc 为例,所用到的函数已列举在上文函数示例中。

// 声明结构体变量与具有实际意义的信号数值变量
struct motohawk_example_message_t s;
uint8_t enable = 1;
double average_radius = 2.5;
double temperature = 260.3;

// 编码
s.enable = enable;  // enable 本身就是整型,且没有缩放或偏移,故无需 encode
s.average_radius = motohawk_example_message_average_radius_encode(average_radius);
s.temperature = motohawk_example_message_temperature_decode(temperature);

// 打包
can_msgs::Frame = frame;
size_t dlc = 8;  // 数据长度,可以固定为 8
motohawk_example_message_pack(&frame.data[0], &s, dlc);
frame.id = 0x1F0u;
frame.dlc = dlc;
frame.header.stamp = ros::Time::now();

// 最后 publish

CAN 接收:解包 + 解码

需实现的功能为 ROS 节点解包并解码从 received_messages 话题上接收到的 can_msgs/Frame 类型的消息。以下代码依旧以 motohawk.dbc 为例,所用到的函数已列举在上文函数示例中。

// subscriber callback 输入了 const can_msgs::FrameConstPtr &_msg

// 判断 CAN ID
if (_msg->id == 0x1F0u) {
    // 声明结构体变量与具有实际意义的信号数值变量
    struct motohawk_example_message_t s;
    uint8_t enable;
    double average_radius;
    double temperature;
    
    // 解包
	motohawk_example_message_unpack(&s, &_msg->data[0], _msg->dlc);
	
	// 解码
	enable = s.enable;  // enable 本身就是整型,且没有缩放或偏移,故无需 decode
	average_radius = motohawk_example_message_average_radius_decode(s.average_radius);
	temperature = motohawk_example_message_temperature_decode(s.temperature);
}

你可能感兴趣的:(汽车电子,c语言,c++,机器人,汽车)