简介
CAN电调电机是一类通过CAN协议控制转速的电调电机,和传统的PWM电调电机不同在于,CAN协议有网络性和抗干扰性,因此其性能比PWM更好,占用的端口数也会更少。在apm或者px4等基于dronecan的飞控来说,想要控制第三方的CAN电调电机其实比较困难,因为其CAN协议不同。所以在这种情况下,想要通信有两种方法:
- 第一种是在飞控上替换掉dronecan协议,添加第三方的can协议。这种方式添加的硬件最少,但是用替换原来的dronecan协议,先不说二次开发的工作量,单说这种方式就会破坏原由的架构,并且如果想要添加其他dronecan设备的时候就无法添加了。
- 第二种也是本文的方式,就是用一个转换器模块,也是我们使用的CAN-Convertor,把dronecan协议按照一定的规则转换成can电调需要的协议。这种方式的好处就是并不会破坏原来的软件架构,并且开发量最少,扩展性和维护性也比第一种方式好太多。
实现方法
简单介绍之后,我们以大疆的CAN电调电机为例来说明。我这里有大疆C610无刷电机电调,这一款是通过can总线控制转速的电调电机,并且带有转速反馈。
其can通信协议如下图所示:
其协议本身并不是很复杂,下面看看我们怎么用CAN-Convertor进行转换。我在某宝上买的can-convertor模块,价格在一众can模块中还不算贵:
先上LUA代码:
local can_num = 1
candrv.set_BitRate(can_num, 1000)
candrv.set_Protocol(can_num, 0)
candrv.enable(can_num)
candrv.set_Len(can_num, 8)
candrv.set_StdID(can_num, 0x200)
local rpm = 0
local rpm_h, rpm_l
local i = 200
local id
local len
while true do
i = i + 100
if i > 500 then
i = 200
end
candrv.set_Data(can_num, 0, uint8_t(i >> 8))
candrv.set_Data(can_num, 1, uint8_t(i))
candrv.send(can_num)
candrv.recv(can_num)
id = candrv.get_ID(can_num)
len = candrv.get_Len(can_num)
if (id == 513) then
rpm_h = candrv.get_Data(can_num, 2)
rpm_l = candrv.get_Data(can_num, 3)
rpm = rpm_h << 8|rpm_l
print("rpm=", rpm)
end
delay(10)
end
代码本身并不复杂,主要就是使能can,然后按大疆can协议发送数据,最后将代码放入CAN-Convertor的U盘中,电机也能正常运行起来,用串口调试助手看到反馈的电机转速如下图:
Dronecan实现方法
上面仅是用lua脚本控制了电机,并没有用到飞控dronecan通信,下面用飞控通过dronecan控制大疆电调。先将电调和飞控分别接在CAN-Convertor的can1和can2接口上。然后写入下面的代码:
local can_num = 1
local droencan_num = 0
candrv.set_BitRate(can_num, 1000)
candrv.set_Protocol(can_num, 0)
candrv.enable(can_num)
candrv.set_BitRate(droencan_num, 1000)
candrv.set_Protocol(droencan_num, 1)
candrv.enable(droencan_num)
dronecan.init(80);
candrv.set_Len(can_num, 8)
candrv.set_StdID(can_num, 0x200)
local esc_raw
local esc_min = 819
local esc_max = 7371
local pwm = 1000
local current_value = 0
while true do
esc_raw = dronecan.get_ESC_RAW(10, 0)
if esc_raw ~= -1 then
pwm = (esc_raw - esc_min) / (esc_max - esc_min) * 1000 + 1000
current_value = pwm - 1000
end
candrv.set_Data(can_num, 0, uint8_t(current_value >> 8))
candrv.set_Data(can_num, 1, uint8_t(current_value))
candrv.send(can_num)
delay(10)
end
代码也是很简单的,esc_raw = dronecan.get_ESC_RAW(10, 0)
是获取飞控的电机控制指令,这里10是飞控id的意思,0代表第一个电机数据。然后我们改变飞控第一个电机输入源为Servon_TRIM
,Servon_TRIM
代表是PWM的中值,也就是1500,pwm = (esc_raw - esc_min) / (esc_max - esc_min) * 1000 + 1000
是将dronecan发出去的esc原始数据转换成PWM值(1000-2000)范围。
上面最后的代码:
candrv.set_Data(can_num, 0, uint8_t(current_value >> 8))
candrv.set_Data(can_num, 1, uint8_t(current_value))
candrv.send(can_num)
便是将droneccan的电机数据转换成大疆电调期望的格式。
实际效果如下图所示:
是不是感觉极大简化了软件开发,也不需要去理解dronecan内部的机制,这都是因为can-convertor嵌入了lua脚本,所以可以用lua快速的实现用户功能开发。can-convertor的功能远不止于此,还有其他的更高级的功能,后续还会继续介绍。
欢迎感兴趣的朋友添加公众号进行交流: