介绍
上一篇主要是介绍libcanard的基础知识和函数,比较偏理论一点,这一篇呢主要注重于实践。主要解决以下问题:
(1)如何把uavcan v1编译到default标签
(2)如何直接调用uavcan的传输层,这样可以使用uavcan与普通的can设备(非uavcan)可以直接通信。
主要过程
如何让default标签支持uavcan v1
我们知道px4的编译有很多lable,比如default,optimized,test等,可以通过设置不同标签实现不同的编译配置。我们最常用的还是default标签,而default标签默认支持的是uavcan v0而不是uavcan v1,因此需要修改一些地方使得编译通过:
- 修改
boards/px4/fmu-v5
下的default.cmake
文件,注释掉原来的uavcan加入uavcan_v1。
px4_add_board(
PLATFORM nuttx
VENDOR px4
MODEL fmu-v5
LABEL default
TOOLCHAIN arm-none-eabi
ARCHITECTURE cortex-m7
ROMFSROOT px4fmu_common
IO px4_io-v2_default
UAVCAN_INTERFACES 2
#UAVCAN_TIMER_OVERRIDE 6
SERIAL_PORTS
...
DRIVERS
...
tone_alarm
# uavcan
uavcan_v1
-
添加can相关的配置,最简单的办法就是在boards/px4/fmu-v5/nuttx-config
下新建default
文件夹,并把boards/px4/fmu-v5/nuttx-config/uavcanv1
下的文件复制到新建的文件夹下。
-
使用编译指令开始编译
make px4_fmu-v5
出现任何奇怪的错误请用 make distclean
指令清理后重新编译
编译成功的话可以下一步。
添加需要的功能到can发送队列
uavcan是新建了一个任务队列,然后在这个任务队列里处理其他任务发来的消息,并发送到can,这个任务有两个子队列是定周期的,有两个级别,一个是给传感器用的,10ms,一个是给执行器用的,1ms。
由于这里为了提供最简单的例子,所以就不管其他任务在,就在子队列里循环发送自定义的消息。
- 新建
/src/drivers/uavcan_v1/Actuators/test.hpp
并添加以下内容:
#pragma once
#include <lib/perf/perf_counter.h>
#include <uORB/PublicationMulti.hpp>
#include <drivers/drv_hrt.h>
class SendTest : public UavcanPublisher
{
public:
SendTest(CanardInstance &ins, UavcanParamManager &pmgr) :
UavcanPublisher(ins, pmgr, "test") { };
~SendTest() {};
void update() override
{
static int i = 0;
if(i++ > 100)
{
i = 0;
CanardPortID arming_pid = static_cast<CanardPortID>(static_cast<uint32_t>(_port_id) + 1);
uint8_t arming_payload_buffer[8] = {0x01,0x02,0x03,0x04,0x05,0x06,0x07};
CanardTransfer transfer = {
.timestamp_usec = hrt_absolute_time() + PUBLISHER_DEFAULT_TIMEOUT_USEC,
.priority = CanardPriorityNominal,
.transfer_kind = CanardTransferKindMessage,
.port_id = arming_pid,
.remote_node_id = CANARD_NODE_ID_UNSET,
.transfer_id = 0xa5,
.payload_size = 8,
.payload = &arming_payload_buffer,
};
canardTxPush(&_canard_instance, &transfer);
}
};
private:
};
- 在
/src/drivers/uavcan_v1/Uavcan.hpp
中include上述新建的文件,并在/src/drivers/uavcan_v1/Uavcan.hpp
的最下方将新增的类添加到下面的节点信息中:
···
NodeManager _node_manager {_canard_instance, _param_manager};
SubscriptionManager _sub_manager {_canard_instance, _param_manager};
UavcanGnssPublisher _gps_pub {_canard_instance, _param_manager};
UavcanEscController _esc_controller {_canard_instance, _param_manager};
SendTest _SendTest {_canard_instance, _param_manager};
UavcanPublisher *_publishers[3] {&_gps_pub, &_esc_controller, &_SendTest};
UavcanMixingInterface _mixing_output {_node_mutex, _esc_controller};
- 然后就可以编译下载了:
make px4_fmu-v5 upload
- uavcanv1默认是没有启动的,所以,需要上电后。连上nsh,然后敲入以下指令,启动uavcanv1:
uavcan_v1 start
也可以在配置文件中使能uavcanv1,这样会开机自动启动
- 如果你有usb-can调试助手,或者其他任何可以查看can总线上发送数据的手段,上电后可以看到以下现象:
本文内容由网友自发贡献,版权归原作者所有,本站不承担相应法律责任。如您发现有涉嫌抄袭侵权的内容,请联系:hwhale#tublm.com(使用前将#替换为@)