QGC与飞控连接后初始化,初始飞行模式为手动模式
- 模式切换在Vehicle中使用_base_mode和_custom_mode存储模式,初始值均为0。
- 当QGC与飞控连接后,飞控通过心跳包(heartbeat)向下发送base_mode和custom_mode,在心跳包中更新_base_mode和custom_mode的值,具体更细在心跳包数据解析中更新。
- 关于base_mode,是指飞控现在处在哪个基本模式,对于发心跳包的地面站来说没有意义,对于发送心跳包的飞控来说是有意义的。这个参数要看各个飞控自己的定义方式,mavlink介绍网页并不会给出具体的模式。在Pixhawk中基本模式可以分为使用用户模式(custom mode)还是基本模式(这里有点绕,其实是就是是否使用用户模式)。使用基本模式又会分为自动模式(auto),位置控制模式(posctl)和手动模式(manual)。一般情况下都会使用用户模式,普通用户不用关心这个参数。开发者在使用mavlink修改飞行器模式时需要注意基本模式的设置。
- 关于custom_mode,大概说一下Pixhawk的用户模式。以多轴为例。它分为主模式(main mode)和子模式(sub mode),两种模式组合在一起成为最终的模式,主模式分为3种,手动(manual),辅助(assist),自动(auto)。手动模式类似apm的姿态模式。在辅助模式中,又分为高度控制模式(altctl)和位置控制模式(posctl)两个子模式,高度控制模式就类似apm的定高模式,油门对应到飞行器高度控制上。位置模式控制飞行器相对地面的速度,油门和高度控制模式一样,yaw轴控制和手动模式一样。自动模式里又分为3个子模式,任务模式(mission),留待模式(loiter),返航模式(return),任务模式就是执行设定好的航点任务,留待模式就是gps悬停模式,返航模式就是直线返回home点并自动降落。在apm里这个参数貌似是没有用的,注意这个数据占了4个字节,在Pixhawk中,前两个字节(低位)是保留的,没有用,第三个字节是主模式,第四个字节是子模式。普通用户请无视。custom_mode又分为main_mode和sub_mode,三者关系如下:
uint32 custom_mode = (main_mode<<16)|(sub_mode<<24);
- 下边是custom_mode中飞行模式对应的main_mode和sub_mode:
static const struct Modes2Name rgModes2Name[] = {
//main_mode sub_mode canBeSet FW MC
{ PX4_CUSTOM_MAIN_MODE_MANUAL, 0, true, true, true },
{ PX4_CUSTOM_MAIN_MODE_STABILIZED, 0, true, true, true },
{ PX4_CUSTOM_MAIN_MODE_ACRO, 0, true, true, true },
{ PX4_CUSTOM_MAIN_MODE_RATTITUDE, 0, true, true, true },
{ PX4_CUSTOM_MAIN_MODE_ALTCTL, 0, true, true, true },
{ PX4_CUSTOM_MAIN_MODE_OFFBOARD, 0, true, false, true },
{ PX4_CUSTOM_MAIN_MODE_SIMPLE, 0, fa