libcanard简介
libcanard 是用于嵌入式实时系统的 UAVCAN 协议的缩减版实现库。
在 PX4 中,在 src/drivers/uacvan_v1 目录中,与 0.9 版本的相比,名称更改了(v0.9版本为 libuavcan):
此库有几个点需要注意:
1)支持 29 位 ID 的 扩展帧 CAN,不支持 11 位 ID 的标准帧 CAN,并且该库只支持 CAN 协议
2)UAVCAN 需要确定性的固定时间的有界碎片的动态内存分配,因此在 PX4 中引入了 o1heap(文件夹也在 uavcan_v1 中)
3)主要包含四个文件:canard.c,canard.h,canard_dsdl.c,canard_dsdl.h,其中 canard.c,canard.h 用于协议的实现,后两个用于 DSDL 数据格式的序列化与反序列化(这两个文件可以直接解析DSDL文件,但官方提供了另一个工具,可以将 DSDL文件转化为 C 文件,因此 canard_dsdl.c,canard_dsdl.h 这两个文件作为扩展库,作用并不大,一般直接使用 C 文件)
UAVCAN作为一个协议栈,由两层组成:TRANSPORT(传输层) 和 PRESENTATION(表示层)。
传输层 ---可跨不同的传输协议进行移植,不过 libcanard 相当于是 uavcan 的精简实现,libcanard 只支持 CAN 协议。
表示层 ---指 DSDL 数据格式的支持扩展库,在 canad_dsdl.h/c 文件中实现,不过官方提供了一个工具 nunavut,可以将 dsdl 文件转换成 c 文件,因此这个扩展库的两个文件,只是一个扩展功能,作用并不大,此工具 nunavut 在安装 PX4 环境时,也会一起安装
需要注意的是:libcanard 并不是一个完整库,是一个微缩版的uavcan库,只能用于 can 通信,并且只实现了平台层,也就是说,底层如何发送,是没有写的,需要用户自行实现
由于 libcanard 没有实现底层,因此在 PX4 中另外写了文件来实现了发送与接收的方法:
一般使用的是 CanardNuttXCDev,SocketCAN用于px4与linux设备通信
传输层
传输层包含两个通道,TX 通道与 RX 通道,两个通道相互独立,不过使用同一个内存管理工具,TX 通道将准备向外输出的CAN帧存储在队列中,RX 通道存储收到的数据。
除了初始化函数 canardInit,TX 与 RX 通道分别有其他的主要函数来完成功能。
TX通道
TX通道主要通过 3 个函数来管理(因为 CAN 单帧只能发送 8 个字节,因此需要分解 CAN 帧):
1)当需要启动传输的时候,使用 canardTxPush() 函数会把要传输的数据分解成 CAN 帧,并按优先级存储到发送队列;
2)之后,在一个专门的发送任务中,canardTxPeek() 会被用来逐个地获取 CAN 帧,并调用硬件底层 CAN 发送函数进行数据包发送;
3)最后,调用 canardTxPop() 将已经发送的CAN帧从队列中移除,移除后需要释放改 CAN 帧的空间。
RX通道
RX管道也是主要通过 3 个函数进行管理。
1)主函数 canardRxAccept() 获取接收到的CAN帧并更新相应的传输重组状态机。
2)函数 canardRxSubscribe() 用来创建一个主题数据的订阅,如果订阅成功,则返回 1,如果此主题已经被订阅过,则会先取消订阅,再重新订阅,之后会返回 0
3)函数 canardRxUnsubscribe() 用于取消订阅某主题的数据
发送结构体
在 libcanard 库中,发送结构体的成员比较多,概念比较杂,因此单独拿出来分析:
typedef struct
{/*接收时是时间戳,发送时是发送时刻*/CanardMicrosecond timestamp_usec;/*优先级*/CanardPriority priority;/*发送类型*/CanardTransferKind transfer_kind;/*消息主题ID*/CanardPortID port_id;/* 对于传出广播消息,值应为CANARD_NODE_ID_UNSET(否则状态无效)。对于传出响应消息,这是目标地址(服务端ID)(如果未设置,则无效)。对于传入的非匿名传输,这是源节点的节点ID。对于传入的匿名传输,值报告为CANARD_NODE_ID_UNSET。*/CanardNodeID remote_node_id;/*响应服务请求时,响应传输应具有与请求相同的传输ID值,因为客户端将基于此将响应与请求匹配。发送请求消息时,该值比之前的ID大1(ID自加)发送广播时,该值应比相同主题ID下的先前传输大1(与发送请求消息相同),初始值为0 */CanardTransferID transfer_id;/*有效载荷大小*/size_t payload_size;const void* payload;
} CanardTransfer;
remote_node_id 是用于 请求/响应消息的,因此当发送服务消息时,其是服务端 ID,当是广播消息是,其就设置为 CANARD_NODE_ID_UNSET。可以参照其广播消息与请求/响应消息:
广播消息:
请求/响应消息:
transfer_id 是用于尾字节的,因为有可能一个客户端发送了多个请求,每个请求消息的尾字节会有一个消息 ID,代表的是哪一条请求,因此服务端:
1)在回复客户端响应消息时,会与请求消息中的 ID 一致,代表回复哪一条请求;
2)当主动发送请求消息时(不是回复消息),会相比上一个值,自加1;
3)发送广播消息与发送请求消息相同,也是自加 1。
例如,一个心跳包的发送结构体定义:
CanardTransfer transfer = {.timestamp_usec = now + PUBLISHER_DEFAULT_TIMEOUT_USEC,.priority = CanardPriorityNominal,.transfer_kind = CanardTransferKindMessage,.port_id = uavcan_node_Heartbeat_1_0_FIXED_PORT_ID_,.remote_node_id = CANARD_NODE_ID_UNSET,.transfer_id = _uavcan_node_heartbeat_transfer_id++,.payload_size = uavcan_node_Heartbeat_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_,.payload = &_uavcan_node_heartbeat_buffer,
};
由于发送的是广播消息,结合 libcanard 中对于发送结构体 CanardTransfer 的定义,广播消息的 remote_node_id 设置为 CANARD_NODE_ID_UNSET,而 transfer_id 与上次相比,自加即可。
payload_size 有效载荷大小,其实就是消息定义的大小,例如心跳包,结构体是 7 个字节,因此有效载荷大小就是 7 字节。因为除了有效载荷,一个消息包中还包含其他数据。
解析过程
在上层中,调用 canardRxAccept 来接收数据,在底层,调用 rxTryParseFrame 来解析数据,在分析此函数之前,可以将请求/响应的 ID 分布图贴出来看一下,根据分布图,再对照其解析程序:
广播消息:
请求/响应消息:
数据解析分为三步:
1)解析 ID
2)解析负载数据(去除尾字节)
3)解析尾字节
之所以是这三步,与 UAVCAN 协议的特点有关:
UAVCAN 将 CAN ID 进行了重定义,使用 ID 来进行总线仲裁过滤以及主题消息的接收,因此首先是解析 ID ,除此,CAN 单帧是 8 字节,UAVCAN 对其进行了拆分,将尾部字节单独拉出,8位数据用于表示其他信息。可以参考之前的笔记《UAVCAN_V1特点与仲裁原理》
解析 ID
广播消息与请求服务消息的 ID 中,优先级与源ID是相同的,因此首先解析:
out->priority = (CanardPriority)((can_id >> OFFSET_PRIORITY) & CANARD_PRIORITY_MAX);
out->source_node_id = (CanardNodeID)(can_id & CANARD_NODE_ID_MAX);
广播消息与请求服务消息的 ID 解析是稍有不同的,因此之后解析是否是请求/服务消息,之后再分情况区分
广播消息与请求/回复消息的区别是第 25 位 ID:
广播消息的第 25 位 ID 为 0,请求服务消息的第 25 位为 1。
if (0 == (can_id & FLAG_SERVICE_NOT_MESSAGE)) //判断是否是请求/服务消息
广播消息
判断是广播消息之后,将传输类型置位,之后提取目标 ID
out->transfer_kind = CanardTransferKindMessage;
out->port_id = (CanardPortID)((can_id >> OFFSET_SUBJECT_ID) & CANARD_SUBJECT_ID_MAX);
在 uavcan 中,将传输类型分为三种:
typedef enum
{CanardTransferKindMessage = 0, //广播消息,所有节点可接收CanardTransferKindResponse = 1, //点对点,从服务端到客户端CanardTransferKindRequest = 2, //点对点,从客户端到服务端
} CanardTransferKind;
请求/回复消息
如果是请求/回复消息,根据上面的传输类型,首先就要判断,此消息是由服务端到客户端,还是从客户端到服务端。
请求/回复消息的类型由第24位ID决定:
为1表示此消息是从客户端到服务端的请求消息,为0表示此消息是从服务端到客户端的回复消息
之后,就可以解析目标 ID 以及主题消息 ID:
out->transfer_kind =((can_id & FLAG_REQUEST_NOT_RESPONSE) != 0) ? CanardTransferKindRequest : CanardTransferKindResponse;
out->port_id = (CanardPortID)((can_id >> OFFSET_SERVICE_ID) & CANARD_SERVICE_ID_MAX);
out->destination_node_id = (CanardNodeID)((can_id >> OFFSET_DST_NODE_ID) & CANARD_NODE_ID_MAX);
解析负载数据
由于 uavcan 的单帧负载数据只有7位,最后一位用于表示其他信息,因此负载解析,需要减去 1 个字节
// Payload parsing.
out->payload_size = frame->payload_size - 1U; // Cut off the tail byte.
out->payload = frame->payload;
解析尾字节
尾字节的官方说明为:
Start of transfer --- 如果此主题消息单帧发送不完(超过7个字节),则必然会发送多帧数据,如果此帧是第一帧,则此位为1,否则为0;如果是单帧消息,则该为一直为1
End of transfer --- 如果此主题消息单帧发送不完(超过7个字节),则必然会发送多帧数据,如果此帧是最后一帧,则此位为1,否则为0;如果是单帧消息,则该为一直为1
Toggle --- 如果是单帧消息,则该为一直为0,如果是多帧消息,则翻转该位(若第一帧为0,则第二帧为1,如此翻转)
Transfer ID --- 标识此次传输的ID
// Tail byte parsing.
// Intentional violation of MISRA: pointer arithmetics is required to locate the tail byte. Unavoidable.
const uint8_t tail = *(((const uint8_t*) out->payload) + out->payload_size); // NOSONAR
out->transfer_id = tail & CANARD_TRANSFER_ID_MAX;
out->start_of_transfer = ((tail & TAIL_START_OF_TRANSFER) != 0);
out->end_of_transfer = ((tail & TAIL_END_OF_TRANSFER) != 0);
out->toggle = ((tail & TAIL_TOGGLE) != 0);
DSDL
类似于 C++ 格式的数据结构,用于定义 uavcan 中的各种类型的消息。
文件命名
DSDL 的文件命名包含 端口ID,短名,版本号,以及后缀名,其中最重要的是短名与版本号,官方对于 DSDL 文件命名的示意如下:
最前面的端口 ID 号是可选的,可以不写,后缀一般都是 ".uavcan",uavcan 的 v1.0 版本规定,每个 DSDL 文件都要有一个版本号,但不能从 0.0 开始,主次版本号的范围都是0-255
不过在其他文件来搜索此文件的时候,还包含命名空间的概念,相当于是 C++ 的命名空间,不过在 DSDL 中,命名空间代表的是目录。目录可以包含子目录,目录的深度没有限制,在官方的示意如下:
在前面的命名空间表示目录,在后面的 GetInfo,刚好是接 DSDL 文件名的。
例如,在 PX4 中的一个 DSDL 文件中调用了其他的文件:
uavcan.time.TAIInfo.0.1 info
那么表示,在 uavcan/time 目录下的 TAIInfo.0.1.uavcan 文件的数据:
数据结构
一些常见的数据类型,在 DSDL 中有定义,例如:
bool
uint8
uint16
uint32
uint64
float16
...
不定长数组
除了常见的数据类型,DSDL 还有一个重要的功能:支持不定长数组。例如:
uint8[<=64] payload
表示 uint8 类型的小于等于 64 个元素的不定长数组 payload,但在不定长数组的数据中,默认第一个元素是数组长度。
void 类型
DSDL 同样支持 void 类型。
void 类型是用于数据对齐目的的特殊字段类型。规范定义了64种不同的空隙类型,如下所示:
void1---1填充位;单位:bit 不是字节
void2---2个填充位;
…
void63---63填充位;
void64---64填充位。
注意 void 填充的是 bit 位,而不是字节。
void 类型的字段没有名称,无法指定其转换模式。在消息序列化期间,所有空字段必须填充零位;在反序列化期间,需要忽略void字段的内容。
服务响应标记
服务响应标记将服务数据类型定义的请求和响应部分分开。标记由专用线上一行中的三个减号(-)组成,上面是请求,下面是响应:
---
辅助关键词(uavcan_v1有,DroneCAN没有)
除数据类型外,还有一些辅助关键词来协助定义消息,常见的有:@sealed,@extent,@union
@sealed:表示封版,后续数据不再更改
float16 geometric # GDOP
float16 position # PDOP
float16 horizontal # HDOP
float16 vertical # VDOP
float16 time # TDOP
float16 northing # NDOP
float16 easting # EDOP
@sealed
@extent:表示后续可继续向后扩展,可以声明一个总空间,方便后续再增加数据
bool fix
bool rtk_fix
@extent 8 * 124
@extent 后续会跟一个 size,单位是 bit 位,以上 8*124 表示总共申请 124 字节。后续所有数据大小加起来不能超过这个 size 大小
@sealed 与 @extent 的使用约束:
1)每个文件只能使用一次
2)必须放在最后一个数据元素后面
3)@extent 后面的大小必须是 8 的倍数
4)@sealed 与 @extent 不能共存
@union:用于定义联合体结构,需要在第一个元素之前,不是很常用
官方示例DSDL数据以及转换C代码(只用于测试,与PX4无关)
可以在另外建立一个文件夹,用于存放官方标准的DSDL数据(只是用于实验观察):
之后需要安装一个 linux 工具 nunavut ,安装方法可以自行搜索,不过 PX4 的安装环境列表中本来就有 nunavut ,因此正常应该是本来就有这个工具的。
官方定义的 DSDL 标准数据类型,包括心跳包等,使用 git 下载到目录中:
git clone https://github.com/OpenCyphal/public_regulated_data_types
拉取下来可以得到如下文件夹:
到此时,就可以看出跟 PX4 有一些联系了,因为 PX4 中的 uavcan_v1 模块中也有这样一个文件夹:
这是由于要使用 uavcan 协议的话,需要调用官方的标准数据才行,有一些自定义消息需要调用官方的标准消息。
接下来再看目录中的内容:
主要有两个部分:uavcan 目录下存放的是官方的标准消息类型,包括心跳包等;reg 目录下存放的是自定义消息类型,如果添加自己的自定义消息,就是添加在 reg 文件夹中。
编译标准消息
由于一些自定义消息会依赖标准消息,因此一般会先编译标准消息,先生成标准消息的程序文件,即生成 uavcan 文件夹下的标准消息,调用此命令(在 DSDL目录下运行下面命令):
nnvg --target-language c --target-endianness=little --enable-serialization-asserts public_regulated_data_types/uavcan --outdir dsdl_compile
--outdir 后跟编译后的程序文件存放目录
进入目录,可以看到生成的标准消息程序文件
编译自定义消息
在 reg 目录的自定义消息中,有一些是对标准消息有依赖关系的,即自定义消息可能会调用标准消息,因此在编译时,需要添加一个:
--lookup-dir public_regulated_data_types/uavcan
表示查找指定路径下的依赖数据。
完整命令如下:
nnvg --target-language c --target-endianness=little --enable-serialization-asserts public_regulated_data_types/reg --lookup-dir public_regulated_data_types/uavcan --outdir dsdl_compile
之后在生成的编译目录下,就会多生成一个 reg 目录,存放自定义消息:
PX4中的DSDL程序文件生成
此部分可以归结为两个问题的解答:
1)PX4 的 DSDL 文件存放位置
2)PX4 如何将 DSDL 文件转为 C 文件
1.PX4 的 DSDL 文件存放位置
在 PX4 中的目录中,有两个文件夹都存放了相应的 DSDL 文件,一个是新的消息定义,另一个是旧版本的消息定义(可能是为了保持兼容):
如同官方例子一样,可以找到 public_regulated_data_types 目录下的 reg 目录与 uavcan 目录,分别存放自定义消息与标准消息。
在 reg 自定义消息中可以根据其文件夹查看到当前 uavcan_v1 支持的模块:
2.PX4 如何将 DSDL 文件转为 C 文件
从官方的例子中,可以知道将 DSDL 格式文件转成 C 调用的是 nunavut ,命令是 nnvg 。
在 uavcan_v1 的 CMakeLists 文件中,可以看出 PX4 编译 uavcan_v1 模块执行的过程:
1)设置 DSDL 文件目录宏
set(LIBCANARD_DIR ${CMAKE_CURRENT_SOURCE_DIR}/libcanard)
set(DSDL_DIR ${CMAKE_CURRENT_SOURCE_DIR}/public_regulated_data_types)
set(LEGACY_DSDL_DIR ${CMAKE_CURRENT_SOURCE_DIR}/legacy_data_types)
2)寻找 nunavut 脚本的路径
find_program(NNVG_PATH nnvg)
3)如果脚本存在,调用 nnvg 命令生成程序文件
if(NNVG_PATH)message("Generating UAVCANv1 DSDL headers using Nunavut")execute_process(COMMAND ${NNVG_PATH} --outdir ${CMAKE_CURRENT_BINARY_DIR}/dsdlc_generated --target-language c -I ${DSDL_DIR}/uavcan ${DSDL_DIR}/reg)execute_process(COMMAND ${NNVG_PATH} --outdir ${CMAKE_CURRENT_BINARY_DIR}/dsdlc_generated --target-language c -I ${LEGACY_DSDL_DIR}/uavcan ${LEGACY_DSDL_DIR}/legacy)execute_process(COMMAND ${NNVG_PATH} --outdir ${CMAKE_CURRENT_BINARY_DIR}/dsdlc_generated --target-language c ${DSDL_DIR}/uavcan)
else()message(FATAL_ERROR "UAVCAN Nunavut nnvg not found")
endif()
4)根据配置选择编译底层配置程序文件
if(${PX4_PLATFORM} MATCHES "nuttx")if(CONFIG_NET_CAN)list(APPEND SRCSCanardSocketCAN.cppCanardSocketCAN.hpp)elseif(CONFIG_CAN_EXTID)list(APPEND SRCSCanardNuttXCDev.cppCanardNuttXCDev.hpp)endif()
endif()
总体如下图:
当其他的配置设置好之后(相关配置在其他笔记文档中说明),在终端调用编译命令 make px4_fmu-v5_default 时,可以看到如下提示:
说明已经调用脚本生成了相关的程序文件。
由于 uavcan_v1 的模块路径在 src/drivers/uavcan_v1 ,因此其生成的程序文件也在编译目录 build/px4_fmu-v5_default 中的 src/drivers/uavcan_v1 目录下:
生成的程序文件内容
nunavut 目录
生成的程序文件中,除了 uavcan 与 reg 目录,还有一个目录---nunavut 目录。此目录中存放的主要是序列化与反序列化的工具函数,也可以理解为 nunavut 的工具函数库。
序列化与反序列化可以理解为协议的包装与解析,因为 uavcan 协议中会对一些位进行二次封装,而且设计到数据类型的转换存储,因此,将要发送的数据进行包装就是序列化的过程,序列化后发送给其他节点。当接收到数据之后,进行反序列化,解包读取数据。
其中文件的内容,例如将整形数据进行序列化的工具函数 :
static inline int8_t nunavutSetUxx(uint8_t* const buf,const size_t buf_size_bytes,const size_t off_bits,const uint64_t value,const uint8_t len_bits)
将一个 float 类型数据进行反序列化解析的函数:
static inline float nunavutGetF32(const uint8_t* const buf,const size_t buf_size_bytes,const size_t off_bits)
其他函数都是类似的工具函数。
DSDL数据文件生成的程序文件
以心跳包为例,打开 uavcan/node 目录下的心跳包程序文件:
里面的主要内容是:
1)消息字节数以及推荐的缓冲区字节大小
//扩展字节(定义缓冲区时要比实际字节大一点)
#define uavcan_node_Heartbeat_1_0_EXTENT_BYTES_ 12UL
//实际字节
#define uavcan_node_Heartbeat_1_0_SERIALIZATION_BUFFER_SIZE_BYTES_ 7UL
心跳包的字节总数是 7 字节,但又定义了一个宏,扩展字节,用于定义缓存区数组大小,都会比实际字节大一些
2)心跳包的结构体
typedef struct
{/// saturated uint32 uptimeuint32_t uptime;/// uavcan.node.Health.1.0 healthuavcan_node_Health_1_0 health;/// uavcan.node.Mode.1.0 modeuavcan_node_Mode_1_0 mode;/// saturated uint8 vendor_specific_status_codeuint8_t vendor_specific_status_code;
} uavcan_node_Heartbeat_1_0;
其中会调用其他文件的结构体数据
3)序列化与反序列化函数
序列化函数:
/*序列化函数 (将要发送的数据序列化)obj ---要序列化的数据(目标数据)buffer ---存放生成的序列化数据的缓冲区(存放目标数据转换成序列化的数据)*/
/*inout_buffer_size_bytes 在调用时,表示传入的缓冲区的大小;
返回时返回生成的序列化数据的大小*/
static inline int8_t uavcan_node_Heartbeat_1_0_serialize_(const uavcan_node_Heartbeat_1_0* const obj, uint8_t* const buffer, size_t* const inout_buffer_size_bytes)
反序列化函数:
/*反序列化 (将接收到的序列化数据解析为正常数据)out_obj ---序列化数据buffer ---包含序列化数据的源缓冲区inout_buffer_size_bytes ---调用时,表示要反序列化的数据的大小;返回时,返回已经反序列化过的数据大小
*/
static inline int8_t uavcan_node_Heartbeat_1_0_deserialize_(uavcan_node_Heartbeat_1_0* const out_obj, const uint8_t* buffer, size_t* const inout_buffer_size_bytes)
调用时,例如心跳包的发送:在 uavcan.hpp 文件中,定义了一个类的私有变量,用于作为心跳包的缓冲区:
// uavcan::node::Heartbeat_1_0
uint8_t _uavcan_node_heartbeat_buffer[uavcan_node_Heartbeat_1_0_EXTENT_BYTES_];
在 uavcan.cpp 文件中,声明相应的结构体,在给结构体变量赋值之后,调用序列化函数进行序列化:
序列化后的数据存放在 payload 中,作为消息的负载,之后调用 libcanard 中的发送函数:
int32_t result = canardTxPush(&_canard_instance, &transfer);
将整个消息包 transfer 发送出去
由于发送的是广播消息,结合 libcanard 中对于发送结构体 CanardTransfer 的定义,广播消息的 remote_node_id 设置为 CANARD_NODE_ID_UNSET,而 transfer_id 与上次相比,自加即可。