c_
uart_interface_
example是mavlink团队提供的一个演示如何用
c
语言调用
mavlink API
对飞机做
offboard
控制的例子程序,这个程序写的挺漂亮的,但是,新的固件,比如:1.13.0d在进入offboard的方法上已经变化了,参见官网对这个问题的讨论。所以,现在的c_uart_interface_example并不能让飞机起飞,本文对这个程序做了修改,仿真环境下运行正常了。
c_uart_interface_example这个程序可从mavlink主页下载:
https://github.com/mavlink/c_uart_interface_example
在下载后的README.md中有详细的安装和运行说明。
c_uart_interface_example的可执行程序是mavlink_control,它的使用方式如下:
常用的运行mavlink_control的两种形式:
1. 在本机运行mavlink_control, 仿真环境也在本机
mavlink_control -u 127.0.0.1 -a
其中:-u选项是指定PX4在127.0.0.1(本机地址)机器上运行;udp的port没有指定,缺省是14540;-a的意思是autotakeoff(自动起飞)。
2. 在offboard计算机中运行mavlink_control,将offboard计算机与安装有PX4固件的自驾仪Pixhawk做串口连接(注意,如果Pixhawk是在真实飞机上,需要卸下浆叶)
mavlink_control -d /dev/ttyUSB0 -b 57600 -a
其中:-d选项是指定串口名字,我的树梅派与Pixhawk连接采用的是USB转串口电缆,所以用的设备名为ttyUSB0;-b选项是指定这个串口的通讯波特率,这个波特率需要与地面站(比如:QGroundControl)为PX4的串口(通常为TELE2)设置的波特率一致,需要核实一下,否则连不通; -a的意思是autotakeoff(自动起飞)。
主要是三部分:
1。主程序,mavlink_control(.h和.cpp)
通过调用与PX4的接口,控制飞机进入offboard状态,并让飞机起飞、降落。
2。 PX4接口的实现,autopilot_interface(.h和.cpp)
用mavlink API实现从PX4接收以及向PX4发送mavlink消息。
3。 通讯接口的实现,generic.cpp、serial_port(.h和.cpp)、udp_port(.h和.cpp)
4。 mavlink代码,在mavlink目录中。
分析
c_
uart_interface_example
在打开串口
(
port.start())
后
,就
启动了
2
个线程,一个是读线程,一个是写线程,顾名思义,写线程是将
PX4
能接收的
mavlink
消息从串口送给
pixhawk
中的
PX4,
读线程等待
pixhawk
中的
PX4
从串口发送给外部计算机
mavlink
消息
。
读线程先启动
,以
10HZ
的频率,也就是
100ms
从连接在
PX
4
上的串口
读取一条消息,
每一条消息都是由
port→read_message()
函数完成的,每一次都是读
1
个字符:
int result = _read_port(cp)
然后对这个字符解码:
msgReceived = mavlink_parse_char(MAVLINK_COMM_1, cp, &message, &status);
解码过程是
一个字节一个字节处理的。
msgRecevied
标志表示是否一个完整的消息被收到了
,如果是
0
则说明需要读下一个字节,如果是
1
表示一个完整的
mavlink
消息解码完成并组装好了。
一个完整的
message
保存在这样一个的结构中
(定义在
mavlink/include/mavlink/v2.0/mavlink_types.h)
:
MAVPACKED(
typedef struct __mavlink_message {
uint16_t checksum; ///< sent at end of packet
uint8_t magic; ///< protocol magic marker
uint8_t len; ///< Length of payload
uint8_t incompat_flags; ///< flags that must be understood
uint8_t compat_flags; ///< flags that can be ignored if not understood
uint8_t seq; ///< Sequence of packet
uint8_t sysid; ///<
表示飞行器或系统
ID
送来了消息
uint8_t compid; ///<
表示组件
(飞行器上的)
ID
送来了消息
uint32_t msgid:24; ///<
消息内容
(
payload)
的
ID
uint64_t payload64[(MAVLINK_MAX_PAYLOAD_LEN+MAVLINK_NUM_CHECKSUM_BYTES+7)/8];
编码后的消息内容
。
uint8_t ck[2]; ///< incoming checksum bytes
(用于校验)
uint8_t signature[MAVLINK_SIGNATURE_BLOCK_LEN];
(用于签名算法)
}) mavlink_message_t;
读到一条完整的消息后
,
判断这个消息是什么
。
根据
mavlink
对消息的定义
,每一条消息都有它的唯一标识
msgid
。初始时,
msgid
是
MAVLINK_MSG_ID_HEARTBEAT
,则需要对这个
心跳信息再解码
。
mavlink_msg_heartbeat_decode(&message, &(current_messages.heartbeat));
解码后就得到了
sysid
,这个常量表示是谁在发送心跳消息。
解码程序定义在文件
:
mavlink/
include/
mavlink/v2.0/common/
mavlink_msg_
heartbeat.h
。
这个
.
h
文件一方面定义了
heartbeat
心跳信息的数据结构,另外还定义并实现了上述对
heartbeat
消息的解码过程。
然后
,做一个循环等待,这个循环确定如果接收到
heartbeat
消息,就必须再接收
sys_
status
消息,就是说
heartbeat
后面应该紧随
sys_
status
消息
,必须成对出现
。其他消息都是单独的。
读线程进入一个循环,循环的每一次都从
PX
4
读一条消息,
PX4
那一端相关
server
会按一定频率
public
各种
mavlink
消息,
PX
4
端的
mavlink
(
src/module/mavlink
)程序会将这些消息发送给这个外部计算机。
在读线程得到以下
位置和姿态两条
mavlink
消息后
:消息
ID
分别是:
针对消息
MAVLINK_MSG_ID_LOCAL_POSITION_NED
对
payload
域再解码:
mavlink_msg_local_position_ned_decode(&message, &(current_messages.local_position_ned));
针对消息
MAVLINK_MSG_ID_ATTITUDE
对
payload
域在解码:
mavlink_msg_attitude_decode(&message, &(current_messages.attitude));
飞机的初始位置就有了。然后启动写线程
。
写线程先做初始化工作,就是把当前得到的位置消息发送给
px
4
。当前的
位置
x
,
y
,
z
就是启动读线程时得到的初始位置(比如:飞机在地面的某个位置),而它的速度分量是
0
。执行
write_
set
point()
。
先把当前要写的数据
current_
setpoint.data
放到
sp
中,这里要加锁,防止其它线程更改
current_
setpoint.data
。
mavlink_set_position_target_local_ned_t sp;
{
std::lock_guard
sp = current_setpoint.data;
}
此时,
current_
setpoint.data是个全局变量,
存有当前飞机的位置信息,而且
vx,vy,vy
都是
0,
把这个信息发给
px4
之前,需要通过
current_setpoint.data
变成
message
消息。
在变成
mavlink
的
message
之前,先对位置点变量
sp
进行设置:
sp.type_mask = MAVLINK_MSG_SET_POSITION_TARGET_LOCAL_NED_VELOCITY &
MAVLINK_MSG_SET_POSITION_TARGET_LOCAL_NED_YAW_RATE;
sp.coordinate_frame = MAV_FRAME_LOCAL_NED;
这个
.
type_mask
是说后面在为
mavlink
消息编码时是针对
VELOCITY
和
YAW_RATE
这两组数据的
,
而
.coordinate
是说后面的位置设置都采用
FRAME_LOCAL_NED
坐标体系。
然后把位置信息编码,生成
mavlink
消息:
mavlink_msg_set_position_target_local_ned_encode(system_id, companion_id, &message, &sp);
其中,
system_
id
标识一架
px4
所在的
pixhawk
飞机,已经在读线程从
heartbeat
消息中得到了,而
companion_id
标识一台外部计算机,是
0
,就一部
。
然后
write_message(message);
写线程进入一个循环,每
250ms
用
setpoint
()对
px4
发送一次当前设定点(setpoint)。
PX
4
规定,
如果有一个外部计算机想让
px4
进入
offboard
状态,在进入
offboard
状态后,要每至少
500ms
(
2hz
)
向
px4
发送一次当前“设定点”(setpoint)的消息,这样
px
4
可以保持
offboard
状态,否则将退出
offboard
状态。
换一种通俗一些的说法,你(比如:树梅派)要想从外部(offboard)控制我(PX4飞控),你就必须持续(至少500ms-2Hz)告诉我,下一步让我干什么(setpoint),否则,超过一定时间,我就失控了。
这个例子程序是
250ms
发一次,够条件。
set_
point()
函数总是用
current_setpoint
这个全局变量发送作为当前设定点数据的消息。初始时,
current_setpoint.data
中的
x
,
y
,
z
是飞机还没有动的位置,
vx
,
vy
,
vz
是
0,
后面就开始动起来了。
这样,两个线程就启动起来了。
在
commands
函数中:
发送让
px
4
进入
offboard
的命令,发送让
px4 arm
的命令。
///
set_
position
(
),
设置新的位置
更新设定点
写线程中的
setpoint
()函数定期
将新的设定点消息送给
px4
,飞机移动。
///
由于读线程的
read_
message()
会定期
从
PX
4
拿到
local_
position_ned
消息,所以做一个每
8
秒一次的循环,就可以打印出当前飞机的位置信息。
///
set_
velocity
,设置向新的位置移动的速度
set_yaw
,设置向新的位置移动的偏航角度
更新位置
同样,写线程的
setpoint
()
函数将新的设定点发送给
PX4,
飞机移动。
///
set_velocity,
设置向下的位置移动速度(着陆),每秒下降
1m
。
设置消息为降落消息
sp.type_mask |= MAVLINK_MSG_SET_POSITION_TARGET_LOCAL_NED_LAND;
更新位置
///
同样,由于读线程的
read_
message()
会定期
从
PX
4
拿到
local_
position_ned
消息,做一个每
4
秒一次的循环,可以打印出当前飞机的位置信息。
///
发送
disarm
命令
飞机解锁。
停止两个线程:
autopilot_interface.stop()
关闭
uart
接口:
port->stop()
进入offboard飞行模式并保持这个模式的方法
注意:以下方法是2021年3月以前的PX4固件版本,这之后,比如我的固件是1.13.0d,已经不支持MAV_CMD_NAV_GUIDED_ENABLE这个命令。这意味着下载的c_uart_interface_example例子程序不能进入offboard模式,也就是这个程序不能让飞机移动。新的做法是用mavlink送命令MAV_CMD_DO_MODE_SET。
以下我先列出老的方法,然后列出新的方法:
老的方法,基于MAV_CMD_NAV_GUIDED_ENABLE,已被弃用。
首先
要组装一个mavlink消息,发给PX4,让PX4进入offboard飞行模式,其中:设置浮点参数flag>0.5f为启动offboard飞行模式。
toggle_offboard_control( bool flag )
{
// Prepare command for off-board mode
mavlink_command_long_t com = { 0 };
com.target_system = system_id;
com.target_component = autopilot_id;
com.command = MAV_CMD_NAV_GUIDED_ENABLE;
com.confirmation = true;
com.param1 = (float) flag; // flag >0.5 => 启动, <0.5 => 停止
// 编码成mavlink消息
mavlink_message_t message;
mavlink_msg_command_long_encode(system_id, companion_id, &message, &com);
// 向PX4发送消息
int len = port->write_message(message);
// Done!
return len;
}
这是一条PX4的命令,先编码,然后发给PX4。退出offboard飞行模式,需要发送上述命令,其中:flag < 0.5f。进入和退出offboard飞行模式的命令只需要发送一次。
新的方法,基于命令MAV_CMD_DO_SET_MODE,注意,我没有在新的方法中对参数flag进行处理,停止发送setpoint就自然退出offboard模式了。
toggle_offboard_control( bool flag )
{
// Prepare command for off-board mode
mavlink_command_long_t com = { 0 };
com.target_system = system_id;
com.target_component = autopilot_id;
com.command = MAV_CMD_DO_SET_MODE;
com.confirmation = true;
// base_mode = MAV_MODE_FLAG_CUSTOM_MODE_ENABLED,
// 参见src/modules/commander/Commander.cpp对这个常量的定义
com.param1 = 1;
// custom_mode = PX4_CUSTOM_MAIN_MODE_OFFBOARD,
// 惨见src/modules/commander/px4_custom_mode.h对这个常量的定义
com.param2 = 6;
// custom_sub_mode
com.param3 = 0;
// 编码成mavlink消息
mavlink_message_t message;
mavlink_msg_command_long_encode(system_id, companion_id, &message, &com);
// 向PX4发送消息
int len = port->write_message(message);
// Done!
return len;
}
为了让PX4保持offboard飞行模式,需要以不小于2HZ的频率(每500毫秒)向PX4发送当前飞机“设定点”(setpoint)的mavlink消息,这个动作本例由写线程按4Hz的频率(每250毫秒)完成。
在PX4中,“设定点”(setpoint)分成三类,他们是
本例采用的是第一类,即:SET_POSITION_TARGET_LOCAL_NED。
这一类又可采用三种方法发送设定点。
Position setpoint (only x
, y
, z
),发送飞机当前的位置
Velocity setpoint (only vx
, yy
, vz
),发送飞机当前各方向的速度
Acceleration setpoint (only afx
, afy
, afz
),发送飞机当前各方向的加速度,程序有,但本例没有用到
本例用到了前两种,即发送当前位置以及发送当前速度。当PX4有了当前的位置又有了当前的速度之后,这个速度设定点将作为一个正反馈累加到位置控制器的输出上,其结果又被用作速度控制器的输入。
当PX4有了当前的位置,速度以及加速度设定点之后,速度和加速度将作为一个正反馈累加到位置控制器的输出上,其结果又被用作速度控制器的输入。加速度设定点将被累加到速度控制器的输出上,其结果用来计算推力矢量。
在发送了上述位置或速度或加速度设定点之后,可以发送偏航设定点,让飞机机头转向(set_yaw函数)或者偏航速率(set_yaw_rate函数,函数有,但本例没有用到)。就是说在set_yaw函数执行之前,必须先执行set_position函数和/或set_velocity函数。
如果PX4在500ms之内没能接到当前位置的消息,则会退出offboard飞行模式。PX4系统中已经定义了若干种当退出offboard飞行模式后该干什么参数设置,可参考官网说明:Offboard Mode | PX4 User Guide。