微克 MAVLINK 通信协议以标准 MAVLINK V2.0 协议为基础, 在其 common 包消息的基础上进行自定消息扩充而成.
飞控实现了部分 common 标准消息的支持. 对 common 消息的定义和实现应以遵循开源已有通用定义为准则, 以便在和其它支持 mavlink 通用协议的设备对接时不产生歧义. 对于 common 已有定义的消息无法满足的需求, 应在 vkfmu 自定义消息的部分进行定义和实现.
旋翼飞行器动力布局类型 VKFLY_AP_TYPE
typedef enum VKFLY_AP_TYPE
{
VKFLY_AP_TYPE_I4=41, /* I4 | */
VKFLY_AP_TYPE_X4=42, /* X4 | */
VKFLY_AP_TYPE_X4R=43, /* 反向X4 */
VKFLY_AP_TYPE_I6=61, /* I6 | */
VKFLY_AP_TYPE_X6=62, /* X6 | */
VKFLY_AP_TYPE_YI6D=63, /* YI6D | */
VKFLY_AP_TYPE_Y6D=64, /* Y6D | */
VKFLY_AP_TYPE_H6=65, /* H6 | */
VKFLY_AP_TYPE_I8=81, /* I8 | */
VKFLY_AP_TYPE_X8=82, /* X8 | */
VKFLY_AP_TYPE_4X8M=83, /* 4轴8桨 | */
VKFLY_AP_TYPE_4X8D=84, /* 4轴8桨 */
VKFLY_AP_TYPE_4X8MR=85, /* 4轴8桨 */
VKFLY_AP_TYPE_4X8DR=86, /* 4轴8桨*/
VKFLY_AP_TYPE_6I12=121, /* 6轴12桨, 十字布局 */
VKFLY_AP_TYPE_6X12=122, /* 6轴12桨, X字布局 */
VKFLY_AP_TYPE_6H12=123, /* 6轴12桨, H字布局 */
VKFLY_AP_TYPE_8I16=161, /* 8轴16桨, 十字布局 */
VKFLY_AP_TYPE_8X16=162, /* 8轴16桨, X字布局 */
VKFLY_AP_TYPE_ENUM_END=163, /* | */
} VKFLY_AP_TYPE;
垂起固定翼飞机构型布局 VKFLY_FIXEDWING_AP_TYPE
typedef enum VKFLY_FIXEDWING_AP_TYPE
{
VKFLY_FIXEDWING_AP_TYPE_T_TAIL=0, /* | 平垂尾 */
VKFLY_FIXEDWING_AP_TYPE_V_TAIL=1, /* | V尾巴*/
VKFLY_FIXEDWING_AP_TYPE_TRIANGLE=2, /* | 三角翼 */
VKFLY_FIXEDWING_AP_TYPE_TANDEM=3, /* | 串列翼 */
VKFLY_FIXEDWING_AP_TYPE_V_TAIL_REV=4, /* | 倒V尾 */
VKFLY_FIXEDWING_AP_TYPE_CUSTOM1=5, /* | 备用 */
VKFLY_FIXEDWING_AP_TYPE_CUSTOM2=6, /* | 备用 */
VKFLY_FIXEDWING_AP_TYPE_CUSTOM3=7, /* | 备用 */
VKFLY_FIXEDWING_AP_TYPE_ENUM_END=8, /* | */
} VKFLY_FIXEDWING_AP_TYPE;
typedef enum VKFLY_USER_COMP_ID
{
VKFLY_COMP_ID_VKGPSA=3, /* 普通 GPSA | */
VKFLY_COMP_ID_VKGPSB=4, /* 普通 GPSB | */
VKFLY_COMP_ID_RFD_F=5, /* 前雷达 | */
VKFLY_COMP_ID_RFD_R=6, /* 后雷达 | */
VKFLY_COMP_ID_RFD_D=7, /* 下雷达 | */
VKFLY_COMP_ID_RFD_360=8, /* 360雷达 | */
VKFLY_COMP_ID_BAT0=10, /* 电池0 | */
VKFLY_COMP_ID_BAT1=11, /* 电池1 | */
VKFLY_COMP_ID_BAT2=12, /* 电池2 | */
VKFLY_COMP_ID_BAT3=13, /* 电池3 | */
VKFLY_COMP_ID_BAT4=14, /* 电池4 | */
VKFLY_COMP_ID_BAT5=15, /* 电池5 | */
VKFLY_COMP_ID_ECU0=16, /* 发动机 ECU0 | */
VKFLY_COMP_ID_ECU1=17, /* 发动机 ECU1 | */
VKFLY_COMP_ID_ECU2=18, /* 发动机 ECU2 | */
VKFLY_COMP_ID_ECU3=19, /* 发动机 ECU3 | */
VKFLY_COMP_ID_WEIGHER=20,/* 称重器 | */
VKFLY_USER_COMP_ID_ENUM_END=21, /* | */
}
typedef enum VKFLY_ARM_DENIED_REASON
{
VKFLY_ARM_DENIED_REASON_NONE=0, /* | */
VKFLY_ARM_DENIED_NO_INS=1, /* 航姿数据异常 | */
VKFLY_ARM_DENIED_SPD_OVER_LIM=2, /* 速度过大 | */
VKFLY_ARM_DENIED_ACC_OVER_LIM=3, /* 加速度过大 | */
VKFLY_ARM_DENIED_GYR_OVER_LIM=4, /* 角速度过大 | */
VKFLY_ARM_DENIED_GPS_ERR=5, /* GPS 异常 | */
VKFLY_ARM_DENIED_IMU_ERR=6, /* IMU 异常 | */
VKFLY_ARM_DENIED_POS_NOT_FIXED=7, /* 未定位 | */
VKFLY_ARM_DENIED_RTK_NOT_FIXED=8, /* RTK未锁定 | */
VKFLY_ARM_DENIED_MAG_ERR=9, /* 磁异常 | */
VKFLY_ARM_DENIED_RESERVE=10, /* 预留 | */
VKFLY_ARM_DENIED_TEMP_OVER_LIM=11, /* 温度过热 | */
VKFLY_ARM_DENIED_OUT_FENCE=13, /* 超出电子围栏范围 | */
VKFLY_ARM_DENIED_LOW_BAT_VOLT=14, /* 电池电压低 | */
VKFLY_ARM_DENIED_LOW_BAT_CAP=15, /* 电池电量低 | */
VKFLY_ARM_DENIED_BAT_BMS_FAULT=16, /* 电池BMS故障 | */
VKFLY_ARM_DENIED_SERVO_FAULT=17, /* 动力故障 | */
VKFLY_ARM_DENIED_LEAN_ANG=18, /* 倾斜角过大 | */
VKFLY_ARM_DENIED_IN_CALIBRATION=19, /* 正在校准中 | */
VKFLY_ARM_DENIED_HYDRO_BMS_CHECK_ERR=20, /* 氢电池自检故障 | */
VKFLY_ARM_DENIED_FUEL_LOW=21, /* 发动机油量低 | */
VKFLY_ARM_DENIED_H2P_LOW=22, /* 氢能气压低 | */
VKFLY_ARM_DENIED_REASON_ENUM_END=23, /* | */
} VKFLY_ARM_DENIED_REASON;
失控保护动作类型
typedef enum VKFLY_FS_ACTION
{
FAIL_SAFE_ACT_NONE=0, /* 无动作 | */
FAIL_SAFE_ACT_LOITER=1, /* 悬停 | */
FAIL_SAFE_ACT_RTL=2, /* 返航(回起飞点) | */
FAIL_SAFE_ACT_RTR=3, /* 去往备降点(最近的 rally 点) | */
FAIL_SAFE_ACT_LAND=4, /* 原地降落 | */
FAIL_SAFE_ACT_LOCK=5, /* 停桨上锁 | */
VKFLY_FS_ACTION_ENUM_END=6, /* | */
} VKFLY_FS_ACTION;
typedef enum VKFLY_SYS_STATUS_SENSOR_EXTEND
{
VKFLY_SYS_STATUS_SENSOR_GPS2=4, /* GPS2 | */
VKFLY_SYS_STATUS_SENSOR_RTK_GPS=8, /* RTK GPS | */
VKFLY_SYS_STATUS_SDCARD=16, /* Onboard SD card | */
VKFLY_SYS_STATUS_SENSOR_EXTEND_ENUM_END=17, /* | */
} VKFLY_SYS_STATUS_SENSOR_EXTEND;
用于 SYS_STATUS 消息中对应的字节. 详细参考 VKFLY.xml
typedef enum VKFLY_SYS_ERROR1
{
VKFLY_SYS_ERROR1_GCS_LINK_LOST=1, /* Gcs 失联 | */
VKFLY_SYS_ERROR1_VOLTAGE_LOW=2, /* 电池电压低 | */
VKFLY_SYS_ERROR1_MOTOR_BALANCE=4, /* 电机平衡差 | */
VKFLY_SYS_ERROR1_MOTOR_FAIL=8, /* 动力故障 | */
VKFLY_SYS_ERROR1_OVERHEAT=16, /* 飞控温度高 | */
VKFLY_SYS_ERROR1_INS_INVALID=32, /* 飞控无INS解算定位 | */
VKFLY_SYS_ERROR1_OUT_FENCE=64, /* 超出电子围栏范围 | */
VKFLY_SYS_ERROR1_OBV_LINK_LOST=128, /* 备用链路失联 | */
VKFLY_SYS_ERROR1_BATBMS_LINK_LOST=256, /* 智能电池bms数据失联 | */
VKFLY_SYS_ERROR1_ECU_FUEL_LOW=512, /* 发动及油量低 | */
VKFLY_SYS_ERROR1_ECU_LINK_LOST=1024, /* 发动机数据断开 |*/
VKFLY_SYS_ERROR1_H2P_LOW=2048, /* 氢气压低 | */
} VKFLY_SYS_ERROR1;
用于 SYS_STATUS 消息中对应的字节. 详细参考 VKFLY.xml
typedef enum VKFLY_SYS_ERROR2
{
VKFLY_SYS_ERROR2_ENUM_END=1, /* | */
} VKFLY_SYS_ERROR2;
用于 SYS_STATUS 消息中对应的字节. 详细参考 VKFLY.xml
typedef enum VKFLY_SYS_ERROR3
{
VKFLY_SYS_ERROR3_MAG0_DISTURB=1, /* mag1 磁干扰 | */
VKFLY_SYS_ERROR3_MAG1_DISTURB=2, /* mag2 磁干扰 | */
VKFLY_SYS_ERROR3_IMU0_ERROR=4, /* imu1 数据异常 | */
VKFLY_SYS_ERROR3_IMU1_ERROR=8, /* imu2 数据异常 | */
VKFLY_SYS_ERROR3_BARO0_ERROR=16, /* 气压计数据异常 | */
VKFLY_SYS_ERROR3_GPS0_ERROR=32, /* 普通gps1数据异常 | */
VKFLY_SYS_ERROR3_GPS1_ERROR=64, /* 普通gps2数据异常 | */
VKFLY_SYS_ERROR3_RTK_ERROR=128, /* RTK板卡数据异常 | */
VKFLY_SYS_ERROR3_YAW_DIFF=256, /* RTK和磁偏航角差异过大 | */
VKFLY_SYS_ERROR3_ENUM_END=129, /* | */
} VKFLY_SYS_ERROR3;
用于 SYS_STATUS 消息中对应的字节. 详细参考 VKFLY.xml (待定义)
用于 HEARTBEAT 消息中对应的字节. 详细参考 VKFLY.xml
typedef enum VKFLY_CUSTOM_MODE
{
VKFLY_CUSTOM_MODE_STANDBY=1, /* Standby mode | 待命模式 */
VKFLY_CUSTOM_MODE_ATTITUDE=3, /* Attitude mode 姿态模式 | */
VKFLY_CUSTOM_MODE_POSHOLD=4, /* Poshold mode 定点模式| */
VKFLY_CUSTOM_MODE_TAKEOFF=10, /* Auto takeoff. 自动起飞| */
VKFLY_CUSTOM_MODE_LOITER=11, /* Auto loiter. 自动悬停| */
VKFLY_CUSTOM_MODE_RTL=12, /* Auto return. 自动返航| */
VKFLY_CUSTOM_MODE_CRUISE=15, /* Auto cruise. 自动巡航| */
VKFLY_CUSTOM_MODE_GUIDE=18, /* Guide to point. 指点飞行| */
VKFLY_CUSTOM_MODE_LAND=19, /* Land. 降落| */
VKFLY_CUSTOM_MODE_FSLAND=20, /* Force land. 迫降| */
VKFLY_CUSTOM_MODE_FOLLOW=21, /* Follow. 跟随| */
VKFLY_CUSTOM_MODE_WP_ORBIT=23, /* WP_Orbit 航点环绕| */
VKFLY_CUSTOM_MODE_DYN_TAKEOFF=24, /* Dyn_Takeoff 动平台起飞| */
VKFLY_CUSTOM_MODE_DYN_LAND=25, /* Dyn_Land 动平台降落| */
VKFLY_CUSTOM_MODE_OBAVOID=26, /* Obavoid 自主避障| */
VKFLY_CUSTOM_MODE_OFFBOARD=27, /* Offboard command control. OFFBORAD 控制| */
VKFLY_CUSTOM_MODE_FORMATION=28, /* Formation 队形编队 */
VKFLY_CUSTOM_MODE_FW_MANUL=51, /* Fixedwing Manul 固定翼手动 | */
VKFLY_CUSTOM_MODE_FW_ATTITUDE=52, /* Fixedwing Attitude 固定翼增稳定 | */
VKFLY_CUSTOM_MODE_FW_CRUISE=53, /* Fixedwing Cruise 固定翼巡航 | */
VKFLY_CUSTOM_MODE_FW_CIRCLE=54, /* Fixedwing Circle 固定翼盘旋 | */
VKFLY_CUSTOM_MODE_FW_TAKEOFF=55, /* Fixedwing Takeoff 固定翼起飞 | */
VKFLY_CUSTOM_MODE_FW_GUIDE=56, /* Fixedwing Guide 固定翼指点飞行 | */
VKFLY_CUSTOM_MODE_FW_LAND=57, /* Fixedwing Land 固定翼降落 | */
VKFLY_CUSTOM_MODE_FW_RTL=58, /* Fixedwing Rtl 固定翼返航 | */
VKFLY_CUSTOM_MODE_FW_GPS_FS=59, /* Fixedwing GpsFs 固定翼丢星盘旋 | */
VKFLY_CUSTOM_MODE_ENUM_END=60, /* | */
} VKFLY_CUSTOM_MODE;
返航原因
typedef enum VKFLY_RTL_REASON
{
VKFLY_RTL_REASON_NONE=0, /* 未触发返航给 | */
VKFLY_RTL_REASON_GCSCMD=1, /* 地面站指令返航 | */
VKFLY_RTL_REASON_RCCMD=2, /* 遥控器指令返航 | */
VKFLY_RTL_REASON_GCSLOST=3, /* 地面站失联返航 | */
VKFLY_RTL_REASON_RCFAIL=4, /* 遥控器信号FS返航 | */
VKFLY_RTL_REASON_RCLOST=5, /* 遥控器信号失联返航 | */
VKFLY_RTL_REASON_LOWVOLT=6, /* 电压低保护返航 | */
VKFLY_RTL_REASON_OFFBOARD=7, /* OFFBORAD控制指令返航 | */
VKFLY_RTL_REASON_ALTLIM=8, /* 超出高度限制保护返航 | */
VKFLY_RTL_REASON_OUT_FENCE=9, /* 超出电子围栏范围保护返航 | */
VKFLY_RTL_REASON_BMS_LOWCAP=10, /* 电池BMS电量低保护返航 | */
VKFLY_RTL_REASON_BMS_LINKLOST=11, /* 电池BMS通信失联保护返航 | */
VKFLY_RTL_REASON_SERVO_FAULT=12, /* 伺服动力故障保护返航 | */
VKFLY_RTL_REASON_WP_FINISH=13, /* 航线完成返航 */
VKFLY_RTL_REASON_H2P_LOW=14, /* 氢能气压低返航 */
VKFLY_RTL_REASON_ECU_FUEL_LOW=15, /* 发动机油量低返航 */
VKFLY_RTL_REASON_ATTITUDE_FS=16, /* 姿态失控超限返航 | */
} VKFLY_RTL_REASON;
悬停原因
typedef enum VKFLY_LOITER_REASON
{
VLFLY_LOITER_REASON_DEFAULT=1, /* 默认原因 | */
VLFLY_LOITER_REASON_GCS_CMD=2, /* | 地面站指令悬停 */
VLFLY_LOITER_REASON_MISSION_DONE=3, /* 任务完成悬停 | */
VLFLY_LOITER_REASON_GPS_REABLE=5, /* GPS重定位悬停 | */
VLFLY_LOITER_REASON_RC_CMD=6, /* 遥控器指令悬停 | */
VLFLY_LOITER_REASON_FOLLOW_FAIL=7, /* 跟随目标结束悬停 | */
VLFLY_LOITER_REASON_TAKEOFF_DONE=9, /* 自动起飞结束悬停 | */
VLFLY_LOITER_REASON_BAT_VOLT_LOW=10, /* 电池电压低悬停 | */
VLFLY_LOITER_REASON_RC_FAIL=11, /* 遥控器失控悬停 | */
VLFLY_LOITER_REASON_RC_LOST=12, /* 遥控器失联悬停 | */
VLFLY_LOITER_REASON_RC_BAD=13, /* 遥控器数据异常悬停 | */
VLFLY_LOITER_REASON_BAT_CAP_LOW=14, /* 电池电量低悬停 | */
VLFLY_LOITER_REASON_OFFBOARD=15, /* OFFBORAD控制悬停 | */
VLFLY_LOITER_REASON_QUIT_FORMATION=16, /* 退队编队悬停 | */
VLFLY_LOITER_REASON_H2P_LOW=17, /* 氢能气压低悬停 | */
VLFLY_LOITER_REASON_ECU_FUEL_LOW=18, /* 发动机油量低悬停 | */
VLFLY_LOITER_REASON_WPDATA_ERR=21, /* 航点数据异常悬停 | */
VKFLY_LOITER_REASON_ENUM_END=22, /* | */
} VKFLY_LOITER_REASON;
#endif
vkins 导航状态字 bitmap
typedef enum VKFLY_VKINS_NAV_STATUS
{
VKFLY_VKINS_NAV_INSGPS=1, /* ins解算bit位, 0-无ins解算 1-有ins解算| */
VKFLY_VKINS_NAV_ALT_GPS=2, /* gps高度解算bit位, 0-gps不参与高度解算, 1-gps参与高度解算 | */
VKFLY_VKINS_NAV_HEADING_RTK=4, /* 航向解算标志, 0-磁航向 1-双天线测向 | */
VKFLY_VKINS_NAV_RTK=16, /* RTK标志位, 0-无RTK高精度定位, 1-有RTK高精度定位 | */
VKFLY_VKINS_NAV_STATUS_ENUM_END=17, /* | */
} VKFLY_VKINS_NAV_STATUS;
航向控制模式
typedef enum VKFLY_YAW_CTRL_MODE
{
VKFLY_YAW_KEEP_CURRENT=0, /* 保持航向不改变 | */
VKFLY_YAW_TO_NEXT_WP=1, /* 航向指向下个航点或盘旋中心点 | */
VKFLY_YAW_TO_TRACE_COURSE=2, /* 航向指向水平运动前方 | */
VKFLY_YAW_TO_SETVAL=3, /* 航向指向给定的航向角度 | */
VKFLY_YAW_TO_HOME=4, /* 航向指向 HOME 点 | */
VKFLY_YAW_TO_INTEREST=5, /* 航向指向兴趣点 | */
VKFLY_YAW_TO_OTHER_MAV_SYS=6, /* 航向指向其它 mav system, 比如另一个无人机或车 | */
VKFLY_YAW_TO_SET_VALUE_ONLY_ON_LANDING=7, /* 当完成该航点后结束航线并降落时, 航向指向给定值。否则指向运动前方 */
VKFLY_YAW_CTRL_MODE_ENUM_END=8, /* | */
} VKFLY_YAW_CTRL_MODE;
typedef enum VKFLY_PHOTO_CTRL_MODE
{
VKFLY_AUTO_PHO_KEEP_CURRENT=0, /* 保持之前的自动拍照状态 | */
VKFLY_AUTO_PHO_STOP=1, /* 停止自动拍照 | */
VKFLY_AUTO_PHO_AUTO_BY_TIME=2, /* 定时自动拍照 | */
VKFLY_AUTO_PHO_BY_DIST_XY=3, /* 水平定距离自动拍照 | */
VKFLY_AUTO_PHO_BY_DIST_Z=4, /* 垂直定距离自动拍照 | */
VKFLY_AUTO_PHO_BY_DIST_XYZ=5, /* 三维定距离自动拍照 | */
VKFLY_PHOTO_CTRL_MODE_ENUM_END=6, /* | */
} VKFLY_PHOTO_CTRL_MODE;
相机航点触发动作
typedef enum VKFLY_DIGICAM_WP_ACT
{
VKFLY_DIGICAM_WP_ACT_NONE=0, /* 无动作 | */
VKFLY_DIGICAM_WP_ACT_PHO=1, /* 触发一次拍照 | */
VKFLY_DIGICAM_WP_ACT_VEDIO_ON=2, /* 触发录像开 | */
VKFLY_DIGICAM_WP_ACT_VEDIO_OFF=3, /* 触发录像关 | */
VKFLY_DIGICAM_WP_ACT_ENUM_END=4, /* | */
} VKFLY_DIGICAM_WP_ACT;
云台航点触发动作
typedef enum VKFLY_GIMBAL_WP_ACT
{
VKFLY_GIMBAL_WP_ACT_NONE=0, /* 无动作 | */
VKFLY_GIMBAL_WP_ACT_SET_ANG=1, /* 设置云台角度 | */
VKFLY_GIMBAL_WP_ACT_SET_PITCH_YAW_FOLLOW=2, /* 设置云台俯仰角度+航向跟随机头 | */
VKFLY_GIMBAL_WP_SET_ZOOM=3, /* 设置云台相机画面缩放 | */
VKFLY_GIMBAL_WP_ACT_ENUM_END=4, /* | */
} VKFLY_GIMBAL_WP_ACT;
抛投通道 bitmap
typedef enum VKFLY_THROW_CHAN_TYPE
{
VKFLY_THROW_CHAN_1=1, /* throwing channel1 | */
VKFLY_THROW_CHAN_2=2, /* throwing channel2 | */
VKFLY_THROW_CHAN_3=4, /* throwing channel3 | */
VKFLY_THROW_CHAN_4=8, /* throwing channel4 | */
VKFLY_THROW_CHAN_5=16, /* throwing channel5 | */
VKFLY_THROW_CHAN_6=32, /* throwing channel6 | */
VKFLY_THROW_CHAN_7=64, /* throwing channel7 | */
VKFLY_THROW_CHAN_8=128, /* throwing channel8 | */
VKFLY_THROW_CHAN_9=256, /* throwing channel9 | */
VKFLY_THROW_CHAN_10=512, /* throwing channel10 | */
VKFLY_THROW_CHAN_11=1024, /* throwing channel11 | */
VKFLY_THROW_CHAN_12=2048, /* throwing channel12 | */
VKFLY_THROW_CHAN_13=4096, /* throwing channel12 | */
VKFLY_THROW_CHAN_14=8192, /* throwing channel12 | */
VKFLY_THROW_CHAN_15=16384, /* throwing channel12 | */
VKFLY_THROW_CHAN_16=32768, /* throwing channel12 | */
VKFLY_THROW_CHAN_ALL=65535, /* throwing channel12 | */
VKFLY_THROW_CHAN_TYPE_ENUM_END=65536, /* | */
} VKFLY_THROW_CHAN_TYPE;
航线执行方式
typedef enum VKFLY_MISSION_EXEC_MODE
{
VKFLY_MISSION_EXEC_MODE_NORMAL=0, /* 顺序执行, 正常执行航点动作 | */
VKFLY_MISSION_EXEC_MODE_NO_ACT=1, /* 顺序执行, 略过航点动作 | */
VKFLY_MISSION_EXEC_MODE_REVERSE=2, /* 逆序执行, 正常航点动作 | */
VKFLY_MISSION_EXEC_MODE_REVERSE_NO_ACT=3, /* 逆序执行, 忽略航点动作 | */
VKFLY_MISSION_EXEC_MODE_ENUM_END=4, /* | */
} VKFLY_MISSION_EXEC_MODE;
航线任务完成后动作
typedef enum VKFLY_MISSION_DONE_ACT
{
VKFLY_MISSION_DONE_LOITER=0, /* 悬停 | */
VKFLY_MISSION_DONE_RETURN_TO_LAUNCH=1, /* 返航回 home | */
VKFLY_MISSION_DONE_LAND=2, /* 原地降落 | */
VKFLY_MISSION_DONE_RETURN_TO_RALLY=3, /* 返回回备降点 | */
VKFLY_MISSION_DONE_RETURN_TO_LAUNCH_AB_WP=4, /* 返航回 home, 按顺序航线执行 | */
VKFLY_MISSION_DONE_RETURN_TO_LAUNCH_BA_WP=5, /* 返航回 home, 按逆序航线执行 | */
VKFLY_MISSION_DONE_THEN_REDO=6, /* 重新执行循环航线 | */
VKFLY_MISSION_DONE_ACT_ENUM_END=7, /* | */
} VKFLY_MISSION_DONE_ACT;
返航执行方式
typedef enum VKFLY_RTL_EXEC_MODE
{
VKFLY_RTL_EXEC_MODE_NORMAL=0, /* 直线返航 | */
VKFLY_RTL_EXEC_MODE_BY_MISSION_SEQ=1, /* 沿航线正序返航 | */
VKFLY_RTL_EXEC_MODE_BY_MISSION_SEQ_REVERSE=2, /* 沿航线逆序返航 | */
VKFLY_RTL_EXEC_MODE_ENUM_END=3, /* | */
} VKFLY_RTL_EXEC_MODE;
typedef enum VKFLY_FORMATION_TYPE
{
VKFLY_FORMATION_ROW=0, /* 横一字队形 | */
VKFLY_FORMATION_COLUM=1, /* 纵一字队形 | */
VKFLY_FORMATION_TRIANGLE=2, /* 三角队形 | */
VKFLY_FORMATION_RECTANGLE=3, /* 矩形队形 | */
VKFLY_FORMATION_CUSTOM=4, /* 自定义队形 | */
VKFLY_FORMATION_TYPE_ENUM_END=5, /* | */
} VKFLY_FORMATION_TYPE;
飞控和地面站定周期 1hz 向外发送, 用于判别是否失联. 包含基础的设备信息.
字段 | 说明 |
---|---|
custom_mode | 自定义飞行模式, 参考 VKFLY.xml 中 enum VKFLY_CUSTOM_MODE |
type | 旋翼为 MAV_TYPE_QUADROTOR, 垂起为 MAV_TYPE_VTOL_TAILSITTER_QUADROTOR |
base_mode | 我们主要用 custom_mode, 该字段置位 MAV_MODE_FLAG_CUSTOM_MODE_ENABLED |
system_status | 参考common.xml标准定义 |
mavlink_version | 当前仅支持v2.0, 值为200 |
飞控定周期向外发送, 默认 2hz. 包含传感器\电池\故障码等一些重要状态信息.
字段 | 说明 |
---|---|
onboard_control_sensors_present | 飞控具有的传感器, bit位按common.xml中标准定义 |
onboard_control_sensors_enabled | 飞控启用的传感器, bit位按common.xml中标准定义 |
onboard_control_sensors_health | 传感器健康状态, bit位按common.xml中标准定义 |
load | 系统cpu负载, 0~1000, 按commom.xml标准定义 |
voltage_battery | 电压cV, 传输为飞控供电电压, 注意此单位与通用定义有区别,因为通用定义范围无法满足需求 |
current_battery | 电流cA |
drop_rate_comm | 预留 |
errors_comm | 预留 |
errors_count1 | bit位参考自定义vkfly.xml中 VKFLY_SYS_ERROR1 |
errors_count2 | bit位参考自定义vkfly.xml中 VKFLY_SYS_ERROR2 |
errors_count3 | 预留 |
errors_count4 | 预留 |
battery_remaining | 剩余电量百分比% |
onboard_control_sensors_present_extended | 参考 VKFLY_SYS_STATUS_SENSOR_EXTEND |
onboard_control_sensors_enable_extended | 参考 VKFLY_SYS_STATUS_SENSOR_EXTEND |
onboard_control_sensors_health_extended | 参考 VKFLY_SYS_STATUS_SENSOR_EXTEND |
home点. 飞控起飞时自动设置 home 点并发送本消息. 也可用 MAV_CMD_REQUEST_MESSAGE 进行读取.
字段 | 说明 |
---|---|
latitude | wgs84纬度 degE7 |
longitude | wgs84经度 degE7 |
altitude | 海拔高度 mm |
x | 北向相对坐标(相对解算原点 origin) |
y | 东向相对坐标 |
z | 地向相对坐标 |
q | 地面姿态四元数(暂未使用) |
approach_x | 进近矢量 (暂未使用) |
approach_y | 进近矢量 (暂未使用) |
approach_z | 进近矢量 (暂未使用) |
time_usec | 时间戳us |
飞控定周期向外发送, 默认 1hz. 包含未经融合的原始普通 gps wgs84 坐标定位等信息.
GPS_INPUT 为普通 GPS 无融合原始定位数据. 当普通 GPS 数据接入后开始定期给地面站发送.
字段 | 说明 |
---|---|
time_usec | 数据时间戳 us |
time_week_ms | GPS 时间周内毫秒 |
lat | wgs84 纬度 degE7 |
lon | wgs84 纬度 degE7 |
alt | 海拔高度 mm |
hdop | HDOP (VKGPS 的 PDOP) |
vdop | VDOP |
vn | 北向速度 m/s |
ve | 东向速度 m/s |
vd | 地向速度 m/s |
time_week | GPS 时间周数 |
gps_id | 0-普通GPSA 1-普通GPSB |
fix_type | 参考 GPS_FIX_TYPE |
satellites_visible | 星数 |
GPS2_RAW 为 RTK 无融合的原始数据, 当 RTK 板卡定位数据接入后开始定期发送.
字段 | 说明 |
---|---|
time_usec | 数据时间戳 us |
fix_type | 参考 GPS_FIX_TYPE |
lat | wgs84 纬度 degE7 |
lon | wgs84 纬度 degE7 |
alt | 海拔高度 mm |
eph | HDOP |
epv | VDOP |
vel | 地速 cm/s |
cog | 航迹角 0.01deg, 0~359.99deg |
satellites_visible | 星数 |
dgps_numch | 定向星数 |
yaw | 定向航向, 0.01deg. 0无测向能力, 1-36000有效测向值, UINT16_MAX无效测向值 |
alt_ellipsoid | 椭球高 mm |
h_acc | 水平精度 mm |
v_acc | 垂直精度 mm |
vel_acc | 速度精度 mm |
hdg_acc | 航向精度 degE5 |
融合后的 GLOBAL 定位信息. 飞控定周期向外发送, 默认 5hz. 包含融合后的 wgs84 坐标定位信息.
字段 | 说明 |
---|---|
time_boot_ms | 时间戳ms |
lat | 纬度 degE7 |
lon | 精度 degE7 |
alt | 海拔高度 mm |
relativ_alt | 相对高度 mm |
vx | 北向速度 cm/s, 北为正 |
vy | 东向速度 cm/s, 东为正 |
vz | 地向速度 cm/s, 下为正 |
hdg | 航向角 0.01deg, 0~359.99deg |
飞控定周期向外发送, 默认 5hz. 包含飞行器的姿态\角速度等信息. 欧拉角定义以 FRD-NED(前右下-北东地) 系右手符号. (航向顺时针正, 俯仰抬头正, 横滚右滚正).
字段 | 说明 |
---|---|
time_boot_ms | 时间戳, 从上电开始 |
roll | 横滚角 rad |
pitch | 俯仰角 rad |
yaw | 航向角 rad |
rollspeed | 横滚轴角速度 rad/s |
pitchspeed | 俯仰轴角速度 rad/s |
yawspeed | 航向轴角速度 rad/s |
LOCAL 定位信息 飞控定周期向外发送, 默认 5hz. 包含以解算原点为原点的北东地坐标下的相对位置和速度信息.
电机输出信息 飞控顶周期向外发送, 默认 5hz. 包含各通道电机控制PWM信号的值.
电调数据信息 数字接口电调反馈的状态信息, 包括转速, 电压, 电流. 有电调接入后飞控以默认 2hz 发送给地面站.
仪表HUD信息 飞控定周期向外发送. 包含飞行器的高度\速度\油门等信息.
当前任务点消息 飞控定期下传, 默认 1hz. 包含当前任务航点序号等信息. 注意 seq 字段从 0 开始.
遥控器通道信息 飞控定周期向外发送. 包含飞行器接受到的遥控器输入通道(校准后)的数据. 若遥控器正在进行校准,则发送未校准的原始通道值数据.
系统状态消息 用于打印显示飞控向地面站传输的字符串. 包括 DEBUG\INFO\WARING\ERROR 等用途. 对于 WARING 和更高等级的信息, 地面站应在操作界面给与用户醒目提示. 对于 INFO\DEBUG 等级的信息, 建议地面站在次级界面给与打印记录. (此两等级的消息主要用于调试)
字段 | 说明 |
---|---|
severity | 信息等级 |
text | 消息字符串 |
id | 拼接超过50字符的长消息用, 暂未使用 |
chunk_seq | 拼接超过50字符的长消息用, 暂未使用 |
拍照pos消息 每次拍照都进行下发, 可用 MAV_CMD_REQUEST_MESSAGE 进行读取. 使用 MAV_CMD_REQUEST_MESSAGE 读取时, param2 非负数值表示要读取的第一个照片 index, -1 表示读取所有照片. param3 0表示仅 读取 param2 指定的照片pos, -1 表示读取 param2 及之后所有的照片pos.
字段 | 说明 |
---|---|
time_boot_ms | 本地时间戳ms, 从系统启动开始 |
time_utc | utc 时间戳us, 从1970年1月1日0时开始 |
camera_id | 相机comp_id, 当具有多个相机时使用 |
lat | wgs84 纬度, degE7 |
lat | wgs84 经度, degE7 |
alt | 海拔高度m |
relativ_alt | 相对高度m |
q | 相机姿态四元数 |
image_index | 照片索引,0开始 |
capture_result | 拍照结果 0失败 1成功 |
file_url | 照片数据地址(网址, 飞控没有填0) |
相机目标跟踪信息
字段 | 说明 |
---|---|
tracking_status | 0-未跟踪 1-在跟踪 2-跟踪异常 |
lat | 目标纬度 |
lon | 目标经度 |
alt | 目标海拔高度 |
载荷吊舱设备姿态信息
字段 | 说明 |
---|---|
flags | 参考链接中的说明, 一般用相对航向 |
q | 姿态四元数, 可用 mavlink_quaternion_to_euler 转为欧拉角 |
测距仪距离数据 目前该消息用于传输下向雷达测距. 当有雷达接入后 2hz 发送该消息
字段 | 说明 |
---|---|
orientation | ROTATION_PITCH_270 下向 |
current_distance | 测距距离 cm |
避障距离数据 目前该消息用于传输水平面雷达. 当有雷达接入后 2hz 发送该消息
字段 | 说明 |
---|---|
distances[72] | 水平各向障碍距离 |
increment | 各向角度间隔 |
increment_f | 各向角度间隔, 此项不为0时优先使用此项 |
angle_offset | distances[0] 与正前向的夹角 |
frame | MAV_FRAME_BODY_FRD, 机体坐前右下标系 |
智能电池状态数据 当检测到智能电池数据接入, 飞控自动周期向地面站发送此消息
字段 | 说明 |
---|---|
time_boot_ms | 系统本地时间戳ms |
voltage | 电压 mV |
current | 电流 cA(0.01A), 负数表示充电 |
temperature | 温度 1度 |
cap_percent | 电量 1% |
bat_id | 电池编号, 0-5 |
err_code | 故障码, 0为无故障 |
cell_num | 电芯数 |
cell_volt | 电芯电压 mV |
cyc_cnt | 循环次数 |
heath | 电池健康度 1% |
发动机 ecu 状态信息 当检测到发动机数据接入后, 飞控自动周期向地面站发送此消息
字段 | 说明 |
---|---|
timestamp | 系统本地时间戳ms |
spd_rpm | 转速 rpm |
thr_pos | 节气门位置 1% |
fuel_pos | 油位 1% |
cylinderA_temp | 缸温1 degC |
cylinderB_temp | 缸温2 degC |
coolant_temp | 冷却液温度 degC |
fuel_remain | 剩余油量 0.1L |
alarm | 警告状态, 参考 VK发动机CAN协议 |
total_runtime | 总工作时长, 1min |
runtime | 本次工作时长, 1min |
service_time | 保养剩余时间, 1min |
output_volt | 输出电压 0.1V |
output_curr | 输出电流 0.1A |
fault | 故障字, 参考 VK发动机CAN协议 |
engine_state | 工作状态 0-未启动 1\2-运行 3-锁机 |
index | 发动机编号 0-3 |
编队飞行长机信息, 此数据从编队长机发出, 编队从机接收.
字段 | 说明 |
---|---|
timestamp | 本地时间戳 |
state | 长机状态字 |
lat | 纬度, 1e-7deg |
lon | 经度, 1e-7deg |
msl | 海拔高度, m |
ve | 东向速度, m/s |
vn | 北向速度, m/s |
vu | 天向速度, m/s |
yaw | 机头航向,北偏东正 deg |
x_dist | 机间左右间距 m |
y_dist | 机间前后间距 m |
z_dist | 机间高度间距 m |
rect_col_num | 矩形队形列数 m |
formation_type | 队形类型 参考 VKFLY_FORMATION_TYPE |
设备版本信息, 本消息可以通过 MAV_CMD_REQUEST_MESSAGE 进行读取, param2 是设备的 comp_id. comp_id 为 0 时, 飞控将回复多个消息逐个返回所有可获取设备的版本信息
字段 | 说明 |
---|---|
comp_id | 组件编号 0-全部, 1-飞控, 其它参考 VKFLY_USER_COMP_ID |
hw_ver | 硬件版本号 |
fw_ver | 软件版本号 |
SN | SN号 |
manufactory | 制造商 |
model | 设备型号 |
接入 mosaich gps 后定期发送
字段 | 说明 |
---|---|
time_usec | 微秒时间戳 |
fix_type | GPS 定位类型, 参考 GPS_FIX_TYPE |
psv_num | 定位星数 |
pvt_err | 定位故障码 |
pvt_mode | 定位模式 |
lat | 纬度 degE7 |
lon | 经度 degE7 |
ellipsoid_alt | 椭球高度 m |
ve | 东向速度 m/s |
vn | 北向速度 m/s |
vu | 天向速度 m/s |
h_acc | 水平精度 cm |
v_acc | 垂直精度 cm |
yaw | 天线测向 deg, 0~360 |
pitch | 天线测俯仰角 deg, -90~90 |
hsv_num | 测向星数 |
att_err | 测向故障码 |
att_mode | 测向模式 |
reserved | 保留字段 |
当有降落伞设备数据接入后, 飞控自动周期向地面站发送此消息
字段 | 说明 |
---|---|
timestamp | 毫秒时间戳 |
state | 状态 0-未就绪 1-就绪 2-已开伞 3-故障 |
auto_launch | 伞自主触发 0-不启用 1-启动 |
uav_cmd | 伞给飞控命令 0-无 1-停桨 |
err_code | 降落伞故障码 |
backvolt | 备用供电电压 V |
当有称重器设备数据接入后, 飞控自动周期向地面站发送此消息
字段 | 说明 |
---|---|
timestamp | 毫秒时间戳 |
weight | 称重器重量 g |
weight_d | 称重器重量变化率 g/s |
work_state | 工作状态 |
err_code | 称重器故障码 |
当有数字电调设备数据接入后, 飞控自动周期向地面站发送此消息. 每4个电调作为一组发送一帧, 通过index字段区分.
字段 | 说明 |
---|---|
timestamp | 毫秒时间戳 ms |
index | 本组第一个电调索引序号, 自增4. (第一组为0, 第二组为4, 第三组为8, 依次类推) |
rpm[4] | 转速 1rpm |
voltage[4] | 电压 V |
current[4] | 电流 A |
temperature[4] | 温度 degC |
status[4] | 状态字 (不同品牌型号有不同的状态定义) |
飞控的参数修改、读取方法参考 mavlink services parameter. 使用16字节的 paramid 作为每各参数的唯一表示码.
单个参数读取. 地面站向飞控发送, 读取某个指定参数. 飞控收到后回复 PARAM_VALUE 消息.
字段 | 说明 |
---|---|
target_system | system id, 区分是哪个飞机 |
target_component | 飞控组件id 填1 (MAV_COMP_ID_AUTOPILOT1) |
param_id | 参数名, 按需要读取参数项的名称字符串填写 |
param_index | 参数序号, 填-1 |
所有参数读取. 地面站向飞控发送, 读取所有飞控参数. 飞控收到后将所有参数依次按 PARAM_VALUE 消息回复.
字段 | 说明 |
---|---|
target_system | system id, 区分是哪个飞机 |
target_component | 飞控组件 id 填1 |
参数值消息. 飞控向地面站回复读取对应的参数值信息.
参数设置消息. 地面站向飞控发送参数设置消息.
航线任务装订和回读交互流程详细参考 mavlink services mission.
目前对 common 标准协议的航线支持有限的几种 MAV_CMD 和 MAV_FRAME.
支持的 MAV_FRAME 如下
FRAME | 说明 |
---|---|
MAV_FRAME_GLOBAL_RELATIVE_ALT_INT | xy经纬度, z相对起飞点高度 |
MAV_FRAME_GLOBAL_INT | xy经纬度, z相对平均海平面amsl高度 |
支持的标准 MAV_CMD包括以下两种, 对当前版本来说这两种不是重点, 只是为了兼容标准协议而做的实现. 重点的航点命令类型在自定义部分.
普通巡航航点 param1-Hold 不为0或者NAN时,将执行自动转弯. 否则按对应时间悬停转弯.
降落点 param3 作为飞往该点速度使用m/s, NAN表示使用飞控默认巡航速度参数.
拍照航点.
param1 分为 byte[4] 进行使用.
字节 | 类型 | 说明 |
---|---|---|
2 | int16 | 悬停时间, 单位 s. 0 表示不进行悬停自动转弯 |
2 | int16 | 巡航速度, 单位 dm/s. 0 或负数表示使用默认巡航速度参数 |
param2 分为 byte[4] 进行使用.
字节 | 类型 | 说明 |
---|---|---|
1 | uint8 | 到达航点是否触发拍照或录像动作 参考 VKFLY_DIGICAM_WP_ACT. |
1 | uint8 | 航点触发自动定时或定距拍照控制 参考 VKFLY_PHOTO_CTRL_MODE. |
2 | uint16 | 为拍照模式间隔参数. 当自动拍照模式为定时时单位为s 当自动拍照模式为定距拍照时单位为m |
param3 分为 byte[4] 进行使用.
字节 | 类型 | 说明 |
---|---|---|
1 | uint8 | 航点吊舱云台控制动作 VKFLY_GIMBAL_WP_ACT |
1 | int8 | 当吊舱动作为设置角度时为吊俯仰角, 范围 -90-90 |
2 | int16 | 当吊舱动作为设置角度时为吊舱航向角, 范围 -180-180. 当吊舱动作为设置缩放时为缩放倍率 * 10, 比如 5 倍为 50 |
其它 param4\5\6如下
参数 | 说明 |
---|---|
param4 | 该参数按 byte[4] 进行使用. byte[0] u8, 为航向模式参考 VKFLY_YAW_CTRL_MODE. byte[1] u8, 预留. byte[2]-byte[3] s16, 范围-180-180. 当航向模式为 VKFLY_YAW_TO_SETVAL 时表示给定的航向值, 单位deg. 当航向模式为指向 HOME 或 NEXT_WP 或 INTEREST 等给定点点时, 表示叠加的航向偏移. |
param5 | 纬度 1e-7deg |
param6 | 经度 1e-7deg |
param7 | 高度 m |
抛投航点
参数 | 说明 |
---|---|
param1 | 该参数按 byte[4] 进行使用. byte[0]-byte[1] s16, 悬停时间, 单位 s. 0 表示不进行悬停自动转弯. 悬停到时间后将执行抛投信号触发. byte[2]-byte[3] s16, 巡航速度, 单位 dm/s. 0 或负数表示使用默认巡航速度参数. |
param2 | 该参数按 byte[4] 进行使用. byte[0]-byte[1] s16, 抛投对地高度, 单位 dm. 0或者负数表示在航点当前高度抛投. 若有有效的对地高度信息如雷达测距仪等, 则自动在航点进行下降到设定的对地高度再执行抛投. byte[2]-byte[3] u16, 抛投通道. 每 bit 代表一个抛投执行通道, bitmap 参考 VKFLY_THROW_CHAN_TYPE. |
param3 | 地面海拔高度 m, NAN 表示无效 |
param4 | 该参数作为 byte[4] 类型使用. byte[0] u8, 为航向模式参考 VKFLY_YAW_CTRL_MODE. byte[1]预留. byte[2]-byte[3] s16, 范围-180-180. 当航向模式为 VKFLY_YAW_TO_SETVAL 时表示给定的航向值, 单位deg. 当航向模式为指向 HOME 或 NEXT_WP 或 INTEREST 等给定点点时, 表示叠加的航向偏移. |
param5 | 纬度 1e-7deg |
param6 | 经度 1e-7deg |
param7 | 高度 m |
环绕航点
参数 | 说明 |
---|---|
param1 | 该参数按 byte[4] 进行使用. byte[0]-byte[1] s16, 环绕半径, 单位 dm. 正数表示顺时针方向环绕, 负数表示逆时针方向环绕. byte[2]-byte[3] s16, 巡航速度. 单位 dm/s. 0或负数表示使用默认的巡航速度设置参数. |
param2 | 拍照控制. 该参数按 byte[4] 进行使用. byte[0] u8, 达到该航点时是否单独触发一次相机动作. 参考 VKFLY_DIGICAM_WP_ACT. byte[1] u8, 为启动相机自动拍照控制模式. 参考 VKFLY_PHOTO_CTRL_MODE. byte[2]-byte[3] u16, 为拍照模式参数. 当拍照模式为定时时单位为s, 当拍照模式为定距拍照时单位为m. 范围 1-UINT16_MAX. |
param3 | 该参数按 byte[4] 进行使用. byte[0]-byte[1] u16, 为环绕圈数, 单位 0.1 圈. byte[2]-byte[3] u16, 为环绕速度, 单位 dm/s. |
param4 | 该参数作为 byte[4] 类型使用. byte[0] u8, 为航向模式参考 VKFLY_YAW_CTRL_MODE. byte[1]预留. byte[2]-byte[3] s16, 范围-180-180. 当航向模式为 VKFLY_YAW_TO_SETVAL 时表示给定的航向值, 单位deg. 当航向模式为指向 HOME 或 NEXT_WP 或 INTEREST 等给定点点时, 表示叠加的航向偏移. |
param5 | 纬度 1e-7deg |
param6 | 经度 1e-7deg |
param7 | 高度 m |
飞控一共有200个电子围栏点. 电子围栏功能上包括返回点(return_point)安全区(inclusion)和禁飞区(exlusion)三种. 安全区和禁飞区可有多边形(polygon)和圆形(circle)两种.
支持的 MAV_CMD
电子围栏返回点. 可以无或者有一个返回点.
圆形电子围栏. 注意不同的圆形电子围栏 group 项应不同.
多边形电子围栏. 注意不同的多边形电子围栏 group 项应不同. 同一个多边形的 item 数据 seq 应保持连续.
飞控支持20个备用降落点的设置和读取. 可通过指令直接去 RALLY 点降落, 可通过参数设定系统
mavlink common 标准消息集中主要由 COMMAND_INT 和 COMMAND_LONG 两条.
飞控接受以下几条 MAV_CMD 类型的指令
指点指令
其中 fram 支持 MAV_FRAME_GLOBAL_RELATIVE_ALT MAV_FRAME_GLOBAL_RELATIVE_ALT_INT MAV_FRAME_GLOBAL MAV_FRAME_GLOBAL_INT
设置 HOME 点
设置吊舱经纬度兴趣点聚焦, 请用 COMMAND_INT
参数 | 说明 |
---|---|
param1 | GIMBAL_ID (暂未使用) |
param2 | 0-仅吊舱指向兴趣点 1-仅机头指向兴趣点 2-吊舱和机头都指向兴趣点 |
param5 | 纬度 |
param6 | 经度 |
param7 | 海拔高度, NAN表示无有效海拔信息,飞控按目标在相对高度0位置 |
取消吊舱兴趣点聚焦
校准命令, 请用 COMMAND_LONG
参数 | 说明 |
---|---|
param1 | 1-陀螺校准(暂未支持) |
param2 | 1-磁力计校准 |
param3 | 1-地面气压校准(暂未支持) |
param4 | 1-遥控器校准开始 2-遥控器校准结束 |
param5 | 1-加速度计校准(暂未支持) 2-水平校准 |
param6 | 1-暂未支持 2-空速计校准 |
param7 | 1-ESC电调校准 |
预飞前存储设备控制命令
参数 | 说明 |
---|---|
param1 | 4-重置所有参数,仅未解锁时可执行, 执行后需重启 |
param2 | NAN 暂未适用 |
param3 | NAN 暂未适用 |
param4 | NAN 暂未使用 |
电机\舵机检测
参数 | 说明 |
---|---|
param1 | 电机0-1对应最小到最大油门, 舵机(-1,1)对应(最大负向,正向行程). 特殊约定 NAN 表示电机输出设置怠速 |
param2 | 检测时间 0-3s |
param3 | |
param4 | |
param5 | 检测通道, 参考ACTUATOR_OUTPUT_FUNCTION |
解锁\上锁命令, 该指令执行拒绝后飞控返回的 ack 中, result_param2 表明拒绝原因, 参考 VKFLY_ARM_DENIED_REASON
参数 | 说明 |
---|---|
param1 | 0-上锁 1-解锁 |
param2 | 21196-强制执行(仅支持上锁) |
参数 | 说明 |
---|---|
param1 | |
param4 | |
param5 | |
param6 | |
param7 | 起飞高度, 约定 NAN 表示用默认参数中的起飞高度 |
参数 | 说明 |
---|---|
param1 | 起始序号 (可选择从几号 mission 开始执行), 从0开始 |
param2 | 结束序号 (可选择到几号 mission 停止执行, 暂不支持) |
参数 | 说明 |
---|---|
param1 | 0-暂停 1-继续 |
返航, 返回起飞点. 本指令会按直线返航执行, 需要按航线返航的话, 请参考 VKFLY_CMD_RETURN_TO_LAUCH
降落
切换目标点
参数 | 说明 |
---|---|
param1 | 目标点序号 |
param2 | reset (暂未使用) |
变速指令
变高指令
设置舵机指令, 用于抛投
参数 | 说明 |
---|---|
Actuator1~6 | 舵机位置 -1 表示关闭位置, 1 表示打开位置, 0表示中间位置, NAN 表示不进行动作 |
index | 从0开始, 当index 为1时, Actuator1 表示第七个通道 |
请求消息命令, 请用 COMMAND_LONG
参数 | 说明 |
---|---|
param1 | 请求的 msgid |
param2-7 | 见被请求消息自定义 |
设置消息发送间隔周期 可设置飞控的常发数据消息周期
参数 | 说明 |
---|---|
param1 | 要设置的 msgid |
param2 | 消息周期 us |
param7 | 未使用 |
设置载荷云台俯仰航向角度指令 param5 中, GIMBAL_MANAGER_FLAGS_RETRACT(镜头回缩) GIMBAL_MANAGER_FLAGS_NEUTRAL(回中) . 该两 bit 指令动作优先级最高执行. param1\param2不都为NAN, 表示吊舱按给定角度运动 设置俯仰低头20度, 航向右60度, param1=-20, param2=60 设置俯仰低头20度, 航向不变, param1=-20, param2=NAN, param1\param2都为NAN, param3 或 param4 不为 NAN, 则表示吊舱俯仰或航向以给定速率运动
参数 | 说明 |
---|---|
param1 | 俯仰角, 抬头为正, -180~180deg, NAN 表示不改变当前俯仰 |
param2 | 航向角, 右转为正, -180~180deg, NAN 表示不改变当前航向 |
param3 | 俯仰角速度, 单位deg/s |
param4 | 航向角速度, 单位deg/s |
param5 | 参考GIMBAL_MANAGER_FLAGS |
param6 | |
param7 | gimbal 设备的 comp_id, (暂未使用) |
拍照-定距指令 若进行定距拍照, 则会停止当前正在进行的定时拍照. 单拍一张 param1=NAN, param2=NAN, param3=1 停止连拍 param1=0, param2=NAN, param3=0 停止连拍且当前单拍一张 param1=0, param2=NAN, param3=1 触发定10m拍照 param1 = 10, param2=NAN, param3=0
参数 | 说明 |
---|---|
param1 | 定距触发距离m, 0表示不定距离触发, NAN表示不改变当前触发状态 |
param2 | 快门时间ms, NAN 表示用默认快门时间设置 |
param3 | 是否立刻进行一次拍照, 0不进行, 1进行 |
拍照-定时指令 若进行定时拍照, 则会关闭当前正进行的定距拍照.
参数 | 说明 |
---|---|
param1 | 定时触发周期ms, 0表示不进行定时触发 |
param2 | 快门时间ms, NAN 表示用默认快门时间设置 |
param3 | 是否立刻进行一次拍照, 0不进行, 1进行 |
相机控制 param1~param5中,
参数 | 说明 |
---|---|
param1 | 未用, 给0或NAN |
param2 | 变倍率, 给定绝对倍率, 0或负数或NAN忽略(用MAV_CMD_SET_CAMERA_ZOOM) |
param3 | 变倍率, 给定相对倍率, 0或负数或NAN忽略(用MAV_CMD_SET_CAMERA_ZOOM) |
param4 | 对焦, 1-执行一次对焦, 0或负数或NAN忽略 |
param5 | 拍照, 1-执行一次拍照, 0或负数或NAN忽略 |
param6 | 未用, 给0或NAN |
param7 | 未用, 给0或NAN |
变焦指令
参数 | 说明 |
---|---|
param1 | 1-连续变焦 2-设置变焦值 |
param2 | 连续变焦: -1到1, 0为停止, 负数为缩小, 正数为放大 设置变焦倍数: 0~100, 100为最大倍数 |
指点跟踪
参数 | 说明 |
---|---|
param1 | px, 水平图像位置, 0~1, 0为最左, 1为最右 |
param2 | py, 垂直图像位置, 0~1, 0为最上, 1为最下 |
param3 | 点半径, 0-一个像素点, 1-全图 |
停止跟踪
开始录像
停止录像
发动机控制
参数 | 说明 |
---|---|
param1 | 0-停止发动机 1-启动发动机, NAN忽略 |
param2 | 0-热车开始 1-冷却开始, NAN忽略 |
param3 | 升空后启动发动机高度, 单位m, NAN忽略 |
降落伞指令
参数 | 说明 |
---|---|
param1 | 参考 PARACHUTE_ACTION 0-禁用自动开伞 1-启用自动开伞 2-立刻停桨开伞 |
电调设置
参数 | 说明 |
---|---|
param1 | 设置电调编号, 1-16, NAN表示忽略该指令 |
指点后抛投, 本指令仅支持 COMMAND_INT
参数 | 说明 |
---|---|
param1 | 抛投舵机编号, 0-0xFFFF, 从低到高每bit对应一舵机, 参考VKFLY_THROW_CHAN_TYPE |
param2 | 抛投后动作, NAN或0为悬停, 1为返航 |
x | 纬度, 1e-7deg |
y | 经度, 1e-7deg |
z | 高度, m |
指点后降落, 本指令仅支持 COMMAND_INT
参数 | 说明 |
---|---|
param1 | 地面海拔,单位m, 飞控根据该参数判断何时接近了地面需要减速, 未知则填 NAN |
param3 | 水平速度,单位m/s, 飞到该位置的最大水平速度 |
param4 | 航向,单位deg, 0-359.99deg, 北偏东航向 |
x | 纬度,1e-7deg |
y | 精度,1e-7deg |
z | 高度, m. 飞往该点过程中的相对高度 |
开始航线
参数 | 说明 |
---|---|
param1 | 起始航点序号,0-UINT16_MAX. NAN表示忽略该参数,飞控根据执行方式从0或最后一点开始 |
param2 | 任务执行方式, 参考 VKFLY_MISSION_EXEC_MODE |
param3 | 任务完成后动作, 参考 VKFLY_MISSION_DONE_ACT |
param4 |
返航
参数 | 说明 |
---|---|
param1 | 起始航点序号, -1-UINT16_MAX. 当返航执行方式为正序或逆序航线返航时参数有效. -1表示最后一点开始, NAN 表示忽略该参数 |
param2 | 返航执行, 参考 VKFLY_RTL_EXEC_MODE |
参数 | 说明 |
---|---|
param1 | 重量校准, 填写实际载重单位克. NAN表示忽略 |
param2 | 1-恢复出厂配置. NAN表示忽略 |
编队指令. 编队集结或解散指令发送给队形从机, 设置队形指令发送给队形主机. 队形主机将队形参数通过 VK_FORMATION_LEADER 持续广播给编队从机.
参数 | 说明 |
---|---|
param1 | 1编队集结 2编队解散 3设置队形 |
param2 | 编队队形, VKFLY_FORMATION_TYPE |
param3 | 举行队形列数 |
param4 | 预留 |
param5 | 左右间距 单位m |
param6 | 前后间距 单位m |
param7 | 上下间距 单位m |
固件下载为VKFLY自定义指令, 飞控固件下载交互过程如下.
sequenceDiagram
GCS->>Autopilot: VK_FW_UPDATE_BEGIN
GCS->>GCS: start timeout
Autopilot->>GCS: VK_FW_UPDATE_DATA_REQUEST (package 0)
Autopilot->>Autopilot: start timeout
GCS-->>Autopilot: VK_FW_UPDATE_DATA (package 0)
note over GCS,Autopilot: ...iterate through packages...
Autopilot->>GCS: VK_FW_UPDATE_DATA_REQUEST (the last package)
Autopilot->>Autopilot: start timeout
GCS-->>Autopilot: VK_FW_UPDATE_DATA (the last package)
Autopilot->>GCS: VK_FW_UPDATE_ACK
地面站向飞控发送此消息, 开始传输固件文件.
字段 | 说明 |
---|---|
target_system | 目标sysid, 在多机系统时指定哪个飞控进行升级 |
target_comp | 目标compid, 飞控compid 为1 |
file_size | 文件字节大小字节数 |
飞控向地面站发送此消息, 请求文件数据内容. 注意飞控请求count可能大于一包所能发送数量, 比如一次请求4096字节. 地面站收到该请求后, 依次将数据按 VK_FW_UPDATE_DATA 连续发送, 注意每次发送的 offset 都需按实际赋值.
字段 | 说明 |
---|---|
offset | 字节偏移 |
count | 字节数 |
地面站向飞控发送文件数据包.
字段 | 说明 |
---|---|
offset | 字节偏移 |
count | 本包字节数, 范围0~128 |
data | 数据内容 |
飞控向地面站发送应答消息.
字段 | 说明 |
---|---|
result | 0-成功 其它失败, 参考 MAV_RESULT |
自定义消息帧, 主要自用于数据排故
VKins 系统的状态数据自定义消息, 主要用于一些自定状态的传输和排故.
字段 | 说明 |
---|---|
time_boot_ms | 系统本地时间戳ms |
nav_status | 传感器状态标志, 参考 VKFLY.xml 中 VKFLY_VKINS_NAV_STATUS |
s_flag1 | |
s_flag2 | |
s_flag3 | |
s_flag4 | |
s_flag5 | |
s_flag6 | |
mag_calib_stage | 磁校准状态 0-未在校准 1-水平XY校准 2-竖直XZ校准 3-校准通过 4-校准失败 |
raw_longitude | vkins解算使用的原始经度, 1e-7deg |
raw_latitude | vkins解算使用的原始纬度, 1e-7deg |
baro_alt | vkins解算使用的原始气压高m |
raw_gps_alt | vkins解算使用的原始海拔高度m |
solv_psat_num | 定位星数 |
solv_hsat_num | 定向星数 |
temperature | 飞控温度, degC |
vibe_coe | 振动系数 0-无效 |
字段 | 说明 |
---|---|
time_boot_ms | 系统本地时间戳ms |
rtl_reason | 返航原因, 参考 VKFLY_RTL_REASON |
loiter_reason | 悬停原因, 参考 VKFLY_LOITER_REASON |
s_flag3 | 预留 |
ups_volt | ups电压, 0.1V |
adc_volt | adc电压, 0.1V |
flight_time | 飞行时间,s |
dist_t_tar | 目标距离, cm |
servo_state | 舵机状态, 每位对应一个舵机, 1-开 0-关 |
flight_dist | 飞行距离, m, 本次上电开始飞行的总距离 |
飞控参数名作为确认飞控参数用途的唯一识别码, 不可随意修改. 在新增参数时应注意不要与已有参数重名, 保持向前兼容性.
参数名 | 参数 | 类型 | 说明 |
---|---|---|---|
MAV_SYS_ID | 系统ID | UINT8 | 范围1~255, 作为MAVLINK通信使用的 SYSTEM ID |
MAV_COMP_ID | 组件ID | UINT8 | 范围1~255, 作为MAVLINK通信使用的COMPONENT ID |
MLOG_MODE | 数据记录模式 | UINT32 | 范围0~3 0-不记录 1-解锁到上锁 2-上电到落锁 3-上电到下电 |
BOOT_MODE | 系统启动模式 | UINT8 | 范围0~1, 0-正常启动, 1-U盘模式(用于导入导出数据文件) |
HW_SN_NUM | 硬件SN号 | UINT32 | 范围0~UINT32_MAX |
AIRFRAME | 飞机布局类型 | UINT16 | 范围0~UINT16_MAX, 区分不同的飞机布局类型, 参考 enum AP_TYPE |
GCS_DISCONT_DT | 地面站失联时间 | UINT16 | 范围0~UINT16_MAX, 单位s. 持续未收到地面站心跳的时间, 0-表示不检测地面站失联 |
RCFAIL_LOT_T | RC失控悬停时间 | UINT16 | 范围0~UINT16_MAX, 单位s. 遥控器失控后悬停等待时间 |
RC_ATT_EN | 遥控器姿态模式启用 | UINT16 | 范围0~1, 0不启用, 1启用 |
VOLT1_LOW_VAL | 一级电压低阈值 | FLOAT | 范围0~1000, 单位V |
VOLT2_LOW_VAL | 二级电压低阈值 | FLOAT | 范围0~1000, 单位V |
VCAP1_LOW_VAL | 一级电量低阈值 | UINT8 | 范围0~100, 单位1%, 当具有多个智能电池时, 飞控按他们的平均电量进行触发保护判定 |
VCAP2_LOW_VAL | 二级电量低阈值 | UINT8 | 范围0~100, 单位1% |
H2P_LOW1_VAL | 一级氢气压低阈值 | FLOAT | 范围0~10000, 单位MPa |
H2P_LOW1_VAL | 二级氢气压低阈值 | FLOAT | 范围0~10000, 单位MPa |
FUEL_LOW1_VAL | 一级ecu油量低阈值 | FLOAT | 范围 1~100, 单位% |
FUEL_LOW2_VAL | 二级ecu油量低阈值 | FLOAT | 范围 1~100, 单位% |
VOLT_PROT_CH | 电压保护通道 | UINT16 | 范围0~10, 触发电压保护的通道, 默认0飞控供电 |
OBAVOID_DIST | 障碍悬停距离 | FLOAT | 范围2~8, 单位m |
OBAVOID_ACT | 避障动作 | UINT8 | 范围0~2,0-不开启 1-悬停 2-爬高 |
GCS_DISC_CRUISE | 航线中是否启用地面站失联 | UINT8 | 范围0~1,0-不启用 1-启用 |
FS_CONF_A | 失控保护设置 | UINT32 | 参考enum FS_ACTION. bit0~3:1级低电压保护 bit4~7:2级低电压保护 bit8~11: 1级氢低压保护 bit12~15: 2级氢低压保护 bit16~19: 1级ecu油量低保护 bit20~23: 2级ecu油量低保护 |
CIR_RAD_DFLT | 默认环绕/盘旋半径 | FLOAT | 范围1~10000m |
TOF_ALT_M | 默认起飞高度 | FLOAT | 范围1~5000, 单位m |
RTL_ALT_M | 默认返航高度 | FLOAT | 范围0~5000, 单位m |
RTL_HEAD_MODE | 返航机头对准方式 | UINT16 | 0-对头返航 1-对尾返航 2-保持当前航向 |
WP_FP_ALT_MODE | 去航线起始点爬高方式 | UINT8 | 0-直线爬升 1-斜线爬升 |
RTL_EXEC_MODE | 默认返航执行方式 | UINT8 | 参考VKFLY_RTL_EXEC_MODE |
MC_XY_CRUISE | 默认旋翼巡航速度 | FLOAT | 范围2~25, 单位m/s |
COM_P1_AF | 载荷P1串口复用 | UINT16 | 范围0~UINT16_MAX |
ALT_LIM_UP1 | 1级高度限制 | UINT16 | 范围10~10000, 单位m |
ALT_LIM_UP2 | 2级高度限制 | UINT16 | 范围0~10000, 单位m |
MAX_HOR_DIST | 最远水平距离 | UINT32 | 范围0~UINT32_MAX, 单位m |
PREC_LAND_ERR | 精准降落误差范围 | FLOAT | 范围0.05~1.0, 单位m |
VEFOL_FR | 车辆跟随相对右向位置 | FLOAT | 范围-1000~1000,单位m |
VEFOL_FF | 车辆跟随相对前向位置 | FLOAT | 范围-1000~1000,单位m |
VEFOL_FU | 车辆跟随相对上向位置 | FLOAT | 范围-1000~1000,单位m |
VEFOL_FYD | 车辆跟随相对航向夹角 | FLOAT | 范围-180~180,单位deg |
VEFOL_BASE_YD | 基站航向安装偏角 | FLOAT | 范围-180~180, 单位deg |
VEFOL_BASE_YD | 基站航向安装偏角 | FLOAT | 范围-180~180, 单位deg |
PHO_SIG_TYPE | 拍照信号类型 | UINT8 | 范围0~2 0-低电平 1-高电平 2-PWM |
PHO_PWM_OFF | 拍照PWM信号待命值 | UINT16 | 范围0~10000, 单位us |
PHO_PWM_ON | 拍照PWM信号触发值 | UINT16 | 范围0~10000, 单位us |
PHO_SIG_TIME | 拍照触发信号持续时间 | UINT16 | 范围0~20000, 单位ms |
PHO_SIG_CH | 拍照-信号输出通道映射 | UINT8 | 拍照信号映射到飞控的哪个输出接口,0~16, 0-表示不启用映射输出 |
FOLLOW_DIST | 默认跟随距离 | FLOAT | 范围2~1000,单位m |
MAN_VELH_MAX | 手动模式最大水平速度 | FLOAT | 范围2~20,单位m/s |
MAN_VELU_MAX | 手动模式最大爬升速度 | FLOAT | 范围1~10,单位m/s |
MAN_VELD_MAX | 手动模式最大下降速度 | FLOAT | 范围1~10,单位m/s |
AUTO_VELU_MAX | 自动模式最大爬升速度 | FLOAT | 范围0.5~8, 单位m/s |
AUTO_VELD_MAX | 自动模式最大下降速度 | FLOAT | 范围0.2~5,单位m/s |
AUTO_VELV_LND | 自动模式降落接地速度 | FLAOT | 范围0.2~0.6, 单位m/s |
TILT_ANG_MAX | 最大倾斜角度 | FLOAT | 范围10~45,单位deg |
YAW_SPD_MAX | 最大航向角速度 | FLAOT | 范围10~120,单位deg/s |
MC_RP_ANG_KP | 旋翼横滚俯仰角度比例系数 | UINT16 | 范围200~800 |
MC_YAW_ANG_KP | 旋翼航向角度比例系数 | UINT16 | 范围200~800 |
MC_RSPD_KP | 旋翼横滚角速度比例系数 | UINT16 | 范围30~200 |
MC_RSPD_KI | 旋翼横滚角速度积分系数 | UINT16 | 范围0~20 |
MC_RSPD_KD | 旋翼横滚角速度微分系数 | UINT16 | 范围0~20 |
MC_PSPD_KP | 旋翼俯仰角速度比例系数 | UINT16 | 范围30~200 |
MC_PSPD_KI | 旋翼俯仰角速度积分系数 | UINT16 | 范围0~20 |
MC_PSPD_KD | 旋翼俯仰角速度微分系数 | UINT16 | 范围0~20 |
MC_YSPD_KP | 旋翼航向角速度比例系数 | UINT16 | 范围50~400 |
MC_YSPD_KI | 旋翼航向角速度积分系数 | UINT16 | 范围0~20 |
MC_YSPD_KD | 旋翼航向角速度微分系数 | UINT16 | 范围0~20 |
MC_PXY_KP | 旋翼水平位置比例系数 | UINT16 | 范围20~150 |
MC_VXY_KP | 旋翼水平速度比例系数 | UINT16 | 范围80~200 |
MC_VXY_KI | 旋翼水平速度积分系数 | UINT16 | 范围0~20 |
MC_VXY_KD | 旋翼水平速度微分系数 | UINT16 | 范围0~20 |
MC_PZ_KP | 旋翼高度位置比例系数 | UINT16 | 范围20~150 |
MC_VZ_KP | 旋翼垂直速度比例系数 | UINT16 | 范围300~500 |
MC_AZ_KP | 旋翼垂直加速度比例系数 | UINT16 | 范围5~20 |
MC_AZ_KI | 旋翼垂直加速度积分系数 | UINT16 | 范围5~20 |
MC_JERKXY_MAX | 旋翼水平最大加加速度 | FLOAT | 范围8~20,单位m/s |
MC_HOV_THR | 旋翼悬停油门 | FLOAT | 范围0.3~0.7(暂未使用) |
MC_MIN_THR | 旋翼怠速油门 | FLOAT | 范围0.05~0.25 |
RC0C1_MIN | 遥控器通道1最小 | UINT16 | 范围500~2500 |
RC0C1_MID | 遥控器通道1中位 | UINT16 | 范围500~2500 |
RC0C1_MAX | 遥控器通道1最大 | UINT16 | 范围500~2500 |
RC0C2_MIN | 遥控器通道2最小 | UINT16 | 范围500~2500 |
RC0C2_MID | 遥控器通道2中位 | UINT16 | 范围500~2500 |
RC0C2_MAX | 遥控器通道2最大 | UINT16 | 范围500~2500 |
RC0C3_MIN | 遥控器通道3最小 | UINT16 | 范围500~2500 |
RC0C3_MID | 遥控器通道3中位 | UINT16 | 范围500~2500 |
RC0C3_MAX | 遥控器通道3最大 | UINT16 | 范围500~2500 |
RC0C4_MIN | 遥控器通道4最小 | UINT16 | 范围500~2500 |
RC0C4_MID | 遥控器通道4中位 | UINT16 | 范围500~2500 |
RC0C4_MAX | 遥控器通道4最大 | UINT16 | 范围500~2500 |
RC0C5_MIN | 遥控器通道5最小 | UINT16 | 范围500~2500 |
RC0C5_MID | 遥控器通道5中位 | UINT16 | 范围500~2500 |
RC0C5_MAX | 遥控器通道5最大 | UINT16 | 范围500~2500 |
RC0C6_MIN | 遥控器通道6最小 | UINT16 | 范围500~2500 |
RC0C6_MID | 遥控器通道6中位 | UINT16 | 范围500~2500 |
RC0C6_MAX | 遥控器通道6最大 | UINT16 | 范围500~2500 |
RC0C7_MIN | 遥控器通道7最小 | UINT16 | 范围500~2500 |
RC0C7_MID | 遥控器通道7中位 | UINT16 | 范围500~2500 |
RC0C7_MAX | 遥控器通道7最大 | UINT16 | 范围500~2500 |
RC0C8_MIN | 遥控器通道8最小 | UINT16 | 范围500~2500 |
RC0C8_MID | 遥控器通道8中位 | UINT16 | 范围500~2500 |
RC0C8_MAX | 遥控器通道8最大 | UINT16 | 范围500~2500 |
RC0C9_MIN | 遥控器通道9最小 | UINT16 | 范围500~2500 |
RC0C9_MID | 遥控器通道9中位 | UINT16 | 范围500~2500 |
RC0C9_MAX | 遥控器通道9最大 | UINT16 | 范围500~2500 |
RC0C10_MIN | 遥控器通道10最小 | UINT16 | 范围500~2500 |
RC0C10_MID | 遥控器通道10中位 | UINT16 | 范围500~2500 |
RC0C10_MAX | 遥控器通道10最大 | UINT16 | 范围500~2500 |
RC0C11_MIN | 遥控器通道11最小 | UINT16 | 范围500~2500 |
RC0C11_MID | 遥控器通道11中位 | UINT16 | 范围500~2500 |
RC0C11_MAX | 遥控器通道11最大 | UINT16 | 范围500~2500 |
RC0C12_MIN | 遥控器通道12最小 | UINT16 | 范围500~2500 |
RC0C12_MID | 遥控器通道12中位 | UINT16 | 范围500~2500 |
RC0C12_MAX | 遥控器通道12最大 | UINT16 | 范围500~2500 |
RC0C13_MIN | 遥控器通道13最小 | UINT16 | 范围500~2500 |
RC0C13_MID | 遥控器通道13中位 | UINT16 | 范围500~2500 |
RC0C13_MAX | 遥控器通道13最大 | UINT16 | 范围500~2500 |
RC0C14_MIN | 遥控器通道14最小 | UINT16 | 范围500~2500 |
RC0C14_MID | 遥控器通道14中位 | UINT16 | 范围500~2500 |
RC0C14_MAX | 遥控器通道14最大 | UINT16 | 范围500~2500 |
RC0C15_MIN | 遥控器通道15最小 | UINT16 | 范围500~2500 |
RC0C15_MID | 遥控器通道15中位 | UINT16 | 范围500~2500 |
RC0C16_MAX | 遥控器通道15最大 | UINT16 | 范围500~2500 |
RC0C16_MIN | 遥控器通道16最小 | UINT16 | 范围500~2500 |
RC0C16_MID | 遥控器通道16中位 | UINT16 | 范围500~2500 |
RC0C16_MAX | 遥控器通道16最大 | UINT16 | 范围500~2500 |
GYRO0_XOFF | GYRO0 X轴零位偏移 | FLOAT | 范围-10~10, 单位 rad/s |
GYRO0_YOFF | GYRO0 Y轴零位偏移 | FLOAT | 范围-10~10, 单位 rad/s |
GYRO0_ZOFF | GYRO0 Z轴零位偏移 | FLOAT | 范围-10~10, 单位 rad/s |
ACC0_XOFF | ACC0 X轴零位偏移 | FLOAT | 范围-10~10, 单位m/s^2 |
ACC0_YOFF | ACC0 Y轴零位偏移 | FLOAT | 范围-10~10, 单位m/s^2 |
ACC0_ZOFF | ACC0 Z轴零位偏移 | FLOAT | 范围-10~10, 单位m/s^2 |
ACC0_XXSCALE | ACC0 校准XX系数 | FLOAT | 范围-10~10 |
ACC0_YYSCALE | ACC0 校准YY系数 | FLOAT | 范围-10~10 |
ACC0_ZZSCALE | ACC0 校准ZZ系数 | FLOAT | 范围-10~10 |
MAG0_XOFF | MAG0 X轴零位偏移 | FLOAT | 范围-10~10,单位Gauss |
MAG0_YOFF | MAG0 Y轴零位偏移 | FLOAT | 范围-10~10,单位Gauss |
MAG0_ZOFF | MAG0 Z轴零位偏移 | FLOAT | 范围-10~10,单位Gauss |
MAG0_XXSCALE | MAG0 校准XX系数 | FLOAT | 范围-10~10 |
MAG0_YYSCALE | MAG0 校准YY系数 | FLOAT | 范围-10~10 |
MAG0_ZZSCALE | MAG0 校准ZZ系数 | FLOAT | 范围-10~10 |
GYRO1_XOFF | GYRO1 X轴零位偏移 | FLOAT | 范围-10~10, 单位 rad/s |
GYRO1_YOFF | GYRO1 Y轴零位偏移 | FLOAT | 范围-10~10, 单位 rad/s |
GYRO1_ZOFF | GYRO1 Z轴零位偏移 | FLOAT | 范围-10~10, 单位 rad/s |
ACC1_XOFF | ACC1 X轴零位偏移 | FLOAT | 范围-10~10, 单位m/s^2 |
ACC1_YOFF | ACC1 Y轴零位偏移 | FLOAT | 范围-10~10, 单位m/s^2 |
ACC1_ZOFF | ACC1 Z轴零位偏移 | FLOAT | 范围-10~10, 单位m/s^2 |
ACC1_XXSCALE | ACC1 校准XX系数 | FLOAT | 范围-10~10 |
ACC1_YYSCALE | ACC1 校准YY系数 | FLOAT | 范围-10~10 |
ACC1_ZZSCALE | ACC1 校准ZZ系数 | FLOAT | 范围-10~10 |
MAG1_XOFF | MAG1 X轴零位偏移 | FLOAT | 范围-10~10,单位Gauss |
MAG1_YOFF | MAG1 Y轴零位偏移 | FLOAT | 范围-10~10,单位Gauss |
MAG1_ZOFF | MAG1 Z轴零位偏移 | FLOAT | 范围-10~10,单位Gauss |
MAG1_XXSCALE | MAG1 校准XX系数 | FLOAT | 范围-10~10 |
MAG1_YYSCALE | MAG1 校准YY系数 | FLOAT | 范围-10~10 |
MAG1_ZZSCALE | MAG1 校准ZZ系数 | FLOAT | 范围-10~10 |
IMU_ATT_ROFF0 | IMU水平ROLL偏移 | FLOAT | 范围-180~180, 单位 deg 飞控通过水平校准自动捕获 |
IMU_ATT_POFF0 | IMU水平PITCH偏移 | FLOAT | 范围-180~180, 单位 deg 飞控通过水平校准自动捕获 |
IMU_ATT_YOFF0 | IMU水平YAW偏移 | FLOAT | 范围-180~180, 单位 deg 可用于设置飞控IMU安装朝向 安装方向前0, 右90, 左-90, 后180 |
ASPD_OFFSET0 | 空速计零偏 | FLOAT | 范围 -5000~5000, 单位Pa |
IMU_GFLT_TYPE | 角速度滤波类型 | UINT8 | 范围0~5, 0-VVH 1-VH 2-H 3-M 4-L 5-VL |
IMU_AFLT_TYPE | 加速度滤波类型 | UINT8 | 范围0~5, 0-VVH 1-VH 2-H 3-M 4-L 5-VL |
IMU_PXOFF | 飞控IMU X安装距离偏差 | INT32 | 范围-1000~1000, 单位cm IMU安装离飞机中心X轴向偏差距离 |
IMU_PYOFF | 飞控IMU Y安装距离偏差 | INT32 | 范围-1000~1000, 单位cm IMU安装离飞机中心Y轴向偏差距离 |
IMU_PZOFF | 飞控IMU Z安装距离偏差 | INT32 | 范围-1000~1000, 单位cm IMU安装离飞机中心Z轴向偏差距离 |
GPS_ANT_XOFF | 普通GPS天线X安装距离偏差 | INT32 | 范围-1000~1000, 单位cm 天线安装离飞机中心X轴向偏差距离 |
GPS_ANT_YOFF | 普通GPS天线Y安装距离偏差 | INT32 | 范围-1000~1000, 单位cm 天线安装离飞机中心Y轴向偏差距离 |
GPS_ANT_ZOFF | 普通GPS天线Z安装距离偏差 | INT32 | 范围-1000~1000, 单位cm 天线安装离飞机中心Z轴向偏差距离 |
RTK_ANT_XOFF | RTK定位天线X安装距离偏差 | INT32 | 范围-1000~1000, 单位cm 天线安装离飞机中心X轴向偏差距离 |
RTK_ANT_YOFF | RTK定位天线Y安装距离偏差 | INT32 | 范围-1000~1000, 单位cm 天线安装离飞机中心Y轴向偏差距离 |
RTK_ANT_ZOFF | RTK定位天线Z安装距离偏差 | INT32 | 范围-1000~1000, 单位cm 天线安装离飞机中心Z轴向偏差距离 |
RTK_H_COMP | RTK测向先天安装角度偏差 | FLOAT | 范围-180~180, 单位deg 常用前后安装 0deg, 左右安装 90deg |
BAT_V_DIV0 | 电压通道0校准比例系数 | FLOAT | 范围0~1000, 通道0为飞控供电电压 |
BAT_V_DIV1 | 电压通道1校准比例系数 | FLOAT | 范围0~1000, 通道0为飞控供电电压 |
BAT_V_DIV2 | 电压通道2校准比例系数 | FLOAT | 范围0~1000, 通道0为飞控供电电压 |
BAT_V_DIV3 | 电压通道3校准比例系数 | FLOAT | 范围0~1000, 通道0为飞控供电电压 |
BAT_V_OFF0 | 电压通道0校准偏移 | FLOAT | 范围-100~100, 单位V |
BAT_V_OFF1 | 电压通道1校准偏移 | FLOAT | 范围-100~100, 单位V |
BAT_V_OFF2 | 电压通道2校准偏移 | FLOAT | 范围-100~100, 单位V |
BAT_V_OFF3 | 电压通道3校准偏移 | FLOAT | 范围-100~100, 单位V |
GIMB_RTM_RCCH | 载荷回中-遥控器通道映射 | UINT32 | 范围 0~18, 0-表示不启用 |
GIMB_MROI_RCCH | 载荷ROI-遥控器通道映射 | UINT32 | 范围 0~18, 0-表示不启用 |
GIMB_FOLL_RCCH | 载荷跟随\锁定模式切换-遥控器通道映射 | UINT32 | 范围 0~18, 0-表示不启用 |
GIMB_ZOOM_RCCH | 载荷画面缩放-遥控器通道映射 | UINT32 | 范围 0~18, 0-表示不启用 |
GIMB_PHO_RCCH | 载荷拍照-遥控器通道映射 | UINT32 | 范围 0~18, 0-表示不启用 |
GIMB_REC_RCCH | 载荷录像-遥控器通道映射 | UINT32 | 范围 0~18, 0-表示不启用 |
GIMB_SSW_RCCH | 载荷画面切换-遥控器通道映射 | UINT32 | 范围 0~18, 0-表示不启用 |
THROW_INSUR | 手动抛投保险开关-遥控器通道映射 | UINT16 | 范围 0~18, 0-表示不启用 |
THROW_RCCH1 | 抛投1-遥控器通道映射 | UINT16 | 范围 0~18, 0-表示不启用 |
THROW_RCCH2 | 抛投2-遥控器通道映射 | UINT16 | 范围 0~18, 0-表示不启用 |
THROW_RCCH3 | 抛投3-遥控器通道映射 | UINT16 | 范围 0~18, 0-表示不启用 |
THROW_RCCH4 | 抛投4-遥控器通道映射 | UINT16 | 范围 0~18, 0-表示不启用 |
THROW_RCCH5 | 抛投5-遥控器通道映射 | UINT16 | 范围 0~18, 0-表示不启用 |
THROW_RCCH6 | 抛投6-遥控器通道映射 | UINT16 | 范围 0~18, 0-表示不启用 |
THROW_RCCH7 | 抛投7-遥控器通道映射 | UINT16 | 范围 0~18, 0-表示不启用 |
THROW_RCCH8 | 抛投8-遥控器通道映射 | UINT16 | 范围 0~18, 0-表示不启用 |
THROW_RCCH9 | 抛投9-遥控器通道映射 | UINT16 | 范围 0~18, 0-表示不启用 |
THROW_RCCH10 | 抛投10-遥控器通道映射 | UINT16 | 范围 0~18, 0-表示不启用 |
THROW_CH1 | 抛投1-PWM输出通道映射 | UINT16 | 范围 0~16, 0-表示不启用 |
THROW_CH2 | 抛投2-PWM输出通道映射 | UINT16 | 范围 0~16, 0-表示不启用 |
THROW_CH3 | 抛投3-PWM输出通道映射 | UINT16 | 范围 0~16, 0-表示不启用 |
THROW_CH4 | 抛投4-PWM输出通道映射 | UINT16 | 范围 0~16, 0-表示不启用 |
THROW_CH5 | 抛投5-PWM输出通道映射 | UINT16 | 范围 0~16, 0-表示不启用 |
THROW_CH6 | 抛投6-PWM输出通道映射 | UINT16 | 范围 0~16, 0-表示不启用 |
THROW_CH7 | 抛投7-PWM输出通道映射 | UINT16 | 范围 0~16, 0-表示不启用 |
THROW_CH8 | 抛投8-PWM输出通道映射 | UINT16 | 范围 0~16, 0-表示不启用 |
THROW_CH9 | 抛投9-PWM输出通道映射 | UINT16 | 范围 0~16, 0-表示不启用 |
THROW_CH10 | 抛投10-PWM输出通道映射 | UINT16 | 范围 0~16, 0-表示不启用 |
THROW_CH1_ON | 抛投1-打开PWM值 | UINT16 | 范围 0~2500 |
THROW_CH2_ON | 抛投2-打开PWM值 | UINT16 | 范围 0~2500 |
THROW_CH3_ON | 抛投3-打开PWM值 | UINT16 | 范围 0~2500 |
THROW_CH4_ON | 抛投4-打开PWM值 | UINT16 | 范围 0~2500 |
THROW_CH5_ON | 抛投5-打开PWM值 | UINT16 | 范围 0~2500 |
THROW_CH6_ON | 抛投6-打开PWM值 | UINT16 | 范围 0~2500 |
THROW_CH7_ON | 抛投7-打开PWM值 | UINT16 | 范围 0~2500 |
THROW_CH8_ON | 抛投8-打开PWM值 | UINT16 | 范围 0~2500 |
THROW_CH9_ON | 抛投9-打开PWM值 | UINT16 | 范围 0~2500 |
THROW_CH10_ON | 抛投10-打开PWM值 | UINT16 | 范围 0~2500 |
THROW_CH1_OFF | 抛投1-关闭PWM值 | UINT16 | 范围 0~2500 |
THROW_CH2_OFF | 抛投2-关闭PWM值 | UINT16 | 范围 0~2500 |
THROW_CH3_OFF | 抛投3-关闭PWM值 | UINT16 | 范围 0~2500 |
THROW_CH4_OFF | 抛投4-关闭PWM值 | UINT16 | 范围 0~2500 |
THROW_CH5_OFF | 抛投5-关闭PWM值 | UINT16 | 范围 0~2500 |
THROW_CH6_OFF | 抛投6-关闭PWM值 | UINT16 | 范围 0~2500 |
THROW_CH7_OFF | 抛投7-关闭PWM值 | UINT16 | 范围 0~2500 |
THROW_CH8_OFF | 抛投8-关闭PWM值 | UINT16 | 范围 0~2500 |
THROW_CH9_OFF | 抛投9-关闭PWM值 | UINT16 | 范围 0~2500 |
THROW_CH10_OFF | 抛投10-关闭PWM值 | UINT16 | 范围 0~2500 |
PARACHUTE_RCCH | 降落伞-遥控器通道映射 | UINT16 | 范围 0~18, 0-表示不启用 |
PARACHUTE_CH | 降落伞-PWM输出通道映射 | UINT16 | 范围 7~16, 0-表示不启用 |
PARACHUTE_ON | 降落伞-打开PWM值 | UINT16 | 范围 0~2500 |
PARACHUTE_OFF | 降落伞-关闭PWM值 | UINT16 | 范围 0~2500 |
COM_SBUSO_AF | SBUS.O复用 | UINT8 | 0-透传SBUS.I 1-复用为抛投信号 |
LADRC_EN | LADRC控制开关 | UINT8 | 0-不启用 1-启用, 默认不启用 |
LADRC_R_B0 | LADRC横滚感度 | float | 100~1000, 默认300 |
LADRC_P_B0 | LADRC俯仰感度 | float | 100~1000, 默认300 |
LADRC_Y_B0 | LADRC航向感度 | float | 100~1000, 默认600 |
WIND_COMP_KP | 抗风补偿 | float | 0~1, 默认0 |