APM 仿真遥控指南
地面站开发了一段时间了,由于没有硬件,所以一直在 APM 模拟器中验证。我们已经实现了 MAVLink 消息接收和解析,显示无人机状态,给无人机发送消息,实现一键起飞,飞往指定地点,降落,返航等功能,本期我们来看看如何在模拟器中实现对无人机的遥控。
【注意】
- 本期所说的遥控无人机都是指遥控无人机模拟器,不涉及硬件在环。
- 前方有坠机风险,请谨慎驾驶。
遥控的基本知识
遥控分为发送端和接收端,发送端自然是遥控器,接收方自然就是无人机。遥控信号一般是一系列数值,通过无线电传输。每个数值被称为一个通道(channel),所以在无人机中,遥控信号一般也称为 Radio Channel,简称 RC。通道个数以及每个通道的作用取决于软件实现,比如 APM 共有18个通道。
无人机收到 RC 控制信号后,会通过飞控将其转换为 PWM 信号,然后输出给电调来控制电机转速。飞控就是飞行控制模块,是一个集成了多种传感器的嵌入式系统,配有飞控固件,可以通过地面站设置固件参数,简化了无人机的开发流程。
RC 信号可以理解为一个整数数组,其中有些来自摇杆,有些来自按钮,通过遥控器发送给无人机。当然,除了遥控,地面站也能发送这个数组来模拟遥控控制,所以 RC 信号的来源是可以不唯一的。此外,遥控和地面站是不同的东西,虽然在物理上可以把它们封装在一个盒子里。因为我用的是 AMP 模拟器,所以本期所讲的内容也都是基于 APM 飞控平台。
通过mavproxy遥控无人机
由于没有无人机硬件,我首先想到的是能不能通过 mavproxy 来模拟遥控控制。mavproxy 的确提供了 rc
命令来手动控制无人机,但是官网上这部分资料不够详细,对新手不太友好。简单来说就是我们可以通过 rc <channel> <value>
命令来修改某个 RC 通道的值,APM 共有 18 个通道,每个通道的范围都是 0~65535 (2字节无符号整数),有效范围是 1000~2000,对于摇杆,1500 表示中立位置,而 0 和 65536 具有特殊含义。
- 0 表示将该通道的值释放回遥控器。什么意思呢?也就是采用遥控器上对应通道的值,或者说将该通道的控制权交还给遥控器,为什么呢?因为 RC 输入的来源可以不止是遥控器。
- 65535 表示忽略该通道的值,通过地面站模拟遥控时,如果不想修改某些通道的值,就可以将这些通道的值都设置为 65535。
在 mavproxy 的控制台,我们可以通过以下命令来查看各个通道的最小值,最大值和中立值,其中 x
是通道编号,取值为 1,2,3…等。
param fetch RCx_MIN
:最小值。param fetch RCx_MAX
:最大值。param fetch RCx_TRIM
:中立值。
对于我现在的需求,用不到所有的通道,主要用到的是前4个通道,分别控制无人机的姿态和油门。至于为什么俯仰和偏航不是连着的,我也表示很好奇。
通道 | 值 | 含义 |
---|---|---|
RC1 | 1000~2000 | 滚转(roll) |
RC2 | 1000~2000 | 俯仰(pitch) |
RC3 | 1000~2000 | 油门(throttle) |
RC4 | 1000~2000 | 偏航(yaw) |
首先我们还是通过一键起飞的方式让无人机先飞起来,用 mavproxy 命令行或者 QGC 都可以。一键起飞之后,无人机会处于 guided
模式,这个模式下无人机会飞往地图上点击的位置或者指定的某个经纬度。 guided
模式不支持手动控制,手动模式是 manual
,在 APM 中,它等价于 stabilize
模式,也就是模拟器启动时的默认模式。
不过在使用 mode
切换模式之前,我们需要先使用 rc 3 1500
命令将油门置于中立位置。因为 APM 模拟器启动时,油门默认是处于最低位置的,也就是1000。如果此时直接切换到手动模式,无人机就会因失去动力而坠机,再现经典的“黑鹰坠落”。
Mayday, Mayday! Black Hawk is going down!
现在我们可以使用 mode stabilize
切换到手动模式了。然后我们可以通过 rc 3 1600
让无人机上升, rc 3 1400
下降,或者通过 rc 1 1800
转向。RC1 到 RC4 你可以都试试,如果你还开着 QGroundControl 地面站,可以通过姿态仪和指南针查看无人机状态,因为 mavproxy 的地图没有姿态仪和指南针,所以 QGC 上会看得比较直观。唯一需要注意的就是,小心坠机!
mode guided
arm throttle
takeoff 40
rc 3 1500
mode stabilize
rc 3 1600
rc 1 1800
... ...
我们已经学会了手动控制无人机飞行,那么能否直接手动起飞呢?
答案是肯定的。因为 APM 模拟器启动时默认就出于 stabilize
模式,因此我们可以直接解锁,然后轰油门起飞。
arm throttle
rc 3 1600
throttle
就是油门的意思,arm
是武装的意思,arm throttle
就是解锁油门。注意在无人机领域,系统状态不是用”已上锁“和”未上锁“来描述,而是用”武装“和”解除武装“来描述。”锁“表示安全,”武装“表示危险,因此他们对状态的表述是相反的,“武装”的含义是解锁,“解除武装”是上锁。
但是在实操上有个需要注意的点,那就是解锁后需要马上轰油门才能成功起飞,否则无人机会重新上锁,导致起飞失败。这个间隔时间很短,这可能跟我调快了仿真速度有关。这其实是因为无人机的自动锁定机制,当无人机落地,电机停转之后,会自动解除武装,是无人机的一种安全保护机制。
如果来不及输入命令,我们还可以先将油门设置为 1500,然后使用 arm throttle force
强制解锁。
rc 3 1500
arm throttle force
rc 3 1600
如果不强制解锁,而是使用 arm throttle
,模拟器就会报错 Arm: Throttle (RC3) is not neutral
,意思是油门处于不正常位置,这也是出于对无人机的保护,防止弹射起步。如果在连续的操作过程中导致油门没有处于最低位,在一键起飞的时候也会看到这个报错,只需要用 rc 3 1000
将油门置于最低位即可。有时候报的错可能不是 RC3,而是其他通道,也是通过 rc
命令将其设置到中立位置(1500)即可。曾经在网上看到过某些无人机在起飞之前要先将油门挡杆扒到最左,其实也是这个原因。
如果想查看 RC 输入和电机输出,可以点击 mavproxy 图形命令窗口(Console)菜单栏的 Tools 菜单。
然后在弹出菜单中选择 RC Inputs 或 Servo Outputs 就能看到每个 RC 通道的值和电机输出了。
上图左边就是初始时各 RC 通道的值。
通过代码遥控无人机
知道如何手动控制无人机之后,我们还要知道是怎么实现的。我想知道 rc
命令是如何发送给无人机的呢?首先想到的是抓包,如果我们观察 mavproxy 的启动命令,会发现它设置了三个通信地址:
--sitl 127.0.0.1:5501
--master tcp:127.0.0.1:5760
--out 127.0.0.1:14550
14550
我们已经很熟悉了,这是 mavproxy 转发 mavlink 消息的地址,也是其他地面站连接的地址。 5760
是与模拟器通信的地址, 5501
是与仿真环境通信的地址,也是 UDP 协议。
为了弄清 rc
命令背后的原理,我对 5501
和 5760
两个端口进行了抓包,结果显示 rc
命令是通过 5501
端口发送出去的。但问题是发送的数据并不是 mavlink 格式,而是下面这么一串数据。
为了一探究竟,也只好去看看 mavproxy 的源码了。 rc
命令的源码在 MAVProxy/modules/mavproxy_rc.py
文件中,我们找到 cmd_cr
这个函数。
def cmd_rc(self, args):
'''handle RC value override'''
if len(args) > 0 and args[0] == 'set':
self.rc_settings.command(args[1:])
return
if len(args) == 1 and args[0] == 'clear':
channels = self.override
for i in range(self.count):
channels[i] = 0
self.set_override(channels)
return
if len(args) == 1 and args[0] == "status":
self.cmd_rc_status()
return
if len(args) == 1 and args[0] == "guiin":
if not mp_util.has_wxpython:
print("No wxpython detected. Cannot show GUI")
elif sys.version_info >= (3, 10) and sys.modules['wx'].__version__ < '4.2.1':
print("wxpython needs to be >=4.2.1 on Python >=3.10. Cannot show GUI")
elif not self.rcin_gui:
from MAVProxy.modules.lib import wxrc
self.rcin_gui = wxrc.RCStatus(panelType=wxrc.PanelType.RC_IN)
return
if len(args) == 1 and args[0] == "guiout":
if not mp_util.has_wxpython:
print("No wxpython detected. Cannot show GUI")
elif sys.version_info >= (3, 10) and sys.modules['wx'].__version__ < '4.2.1':
print("wxpython needs to be >=4.2.1 on Python >=3.10. Cannot show GUI")
elif not self.servoout_gui:
from MAVProxy.modules.lib import wxrc
self.servoout_gui = wxrc.RCStatus(panelType=wxrc.PanelType.SERVO_OUT)
return
if len(args) != 2:
print("Usage: rc <set|channel|all|clear|status|guiin|guiout> <pwmvalue>")
return
value = int(args[1])
if value > 65535 or value < -1:
raise ValueError("PWM value must be a positive integer between 0 and 65535")
if value == -1:
value = 65535
channels = self.override
if args[0] == 'all':
for i in range(self.count):
channels[i] = value
else:
channel = int(args[0])
if channel < 1 or channel > self.count:
print("Channel must be between 1 and %u or 'all'" % self.count)
return
channels[channel - 1] = value
self.set_override(channels)
从这个函数中,能看到 rc
命令有很多子命令, channel
就是我们上一节提到的用法, all
可以用来设置所有通道的值。 rc status
可以打印出每个通道的值,但是注意它不是打印的真实通道值,而是本地的副本,默认都是0,如果通道没有修改过,那么打印出来就会是0。而 rc guiin
和 rc guiout
对应的其实就是上一节中 Tools 菜单下的 RC Inputs 和 Servo Outputs 两个子菜单,用这两个命令也能弹出对应的窗口。
回到函数的后半段,函数将命令中设置的 value
首先记录到本地 channels
副本,然后调用了 set_override
函数设置通道值,该函数定义如下。
def set_override(self, newchannels):
'''this is a public method for use by drone API or other scripting'''
self.override = newchannels
self.override_counter = 10
self.send_rc()
def send_rc(self):
'''send RC override packet'''
if self.sitl_output:
chan16 = self.override[:16]
buf = struct.pack('<HHHHHHHHHHHHHHHH', *chan16)
self.sitl_output.write(buf)
else:
chan18 = self.override[:18]
self.master.mav.rc_channels_override_send(self.target_system,
self.target_component,
*chan18)
set_override
最终调用了 send_rc
函数,而在 send_rc
函数中,将 channels
发送了出去。因为我们启动 mavproxy 时设置了 sitl
参数,所以这里会进入 if
分支,也就是将 RC 通道的值发送到了 5501
端口。而且这里对数据的序列化方式也是直接使用了 struct.pack
, '<HHHHHHHHHHHHHHHH'
是序列化方式, <
表示采用小端序,每个 H
表示两个字节,也就是 chan16
数组里每个整数用两字节表示,所以我们抓包时抓到 32 字节也就不足为奇了,将它们按每两个字节拆开如下。
dc05 dc05 dd05 dc05 0000 0000 0000 0000 0000 0000 0000 0000 0000 0000 0000 0000
0x05dc
刚好就是十进制的 1500
,第三个 0x05dd
,而我测试用的命令正是 rc 3 1501
。
下一步我们需要在地面站中通过 mavlink 协议发送遥控信号实现手动控制无人机,这里有两个消息比较重要。一是 RC_CHANNELS (65)
,他是 无人机向地面站发送的当前 RC 通道值。二是 RC_CHANNELS_OVERRIDE (70)
,它是地面站发送给无人机的 RC 控制消息。
一是 RC_CHANNELS (65)
,他是 无人机向地面站发送的当前 RC 通道值。
二是 RC_CHANNELS_OVERRIDE (70)
,它是地面站发送给无人机的 RC 控制消息。要实现手动控制无人机,发送这个消息就行了。
这里给出两篇官方参考文章:
- RC Input (aka Pilot Input) — Dev documentation
- https://mavlink.io/zh/messages/common.html#RC_CHANNELS
看吧,一点都不难。