|
@@ -6,7 +6,6 @@
|
|
|
对 common 消息的定义和实现应以遵循开源已有通用定义为准则, 以便在和其它支持 mavlink 通用协议的设备对接时不产生歧义.
|
|
|
对于 common 已有定义的消息无法满足的需求, 应在 vkfmu 自定义消息的部分进行定义和实现.
|
|
|
|
|
|
-
|
|
|
## 1 自定义枚举类型
|
|
|
|
|
|
### 1.1 机型布局 VKFLY_AP_TYPE
|
|
@@ -38,6 +37,7 @@ typedef enum VKFLY_AP_TYPE
|
|
|
```
|
|
|
|
|
|
### 1.2 自定义组件ID VKFLY_USER_COMP_ID
|
|
|
+
|
|
|
```c
|
|
|
typedef enum VKFLY_USER_COMP_ID
|
|
|
{
|
|
@@ -87,7 +87,9 @@ typedef enum VKFLY_ARM_DENIED_REASON
|
|
|
VKFLY_ARM_DENIED_LEAN_ANG=18, /* 倾斜角过大 | */
|
|
|
VKFLY_ARM_DENIED_IN_CALIBRATION=19, /* 正在校准中 | */
|
|
|
VKFLY_ARM_DENIED_HYDRO_BMS_CHECK_ERR=20, /* 氢电池自检故障 | */
|
|
|
- VKFLY_ARM_DENIED_REASON_ENUM_END=21, /* | */
|
|
|
+ VKFLY_ARM_DENIED_FUEL_LOW=21, /* 发动机油量低 | */
|
|
|
+ VKFLY_ARM_DENIED_H2P_LOW=22, /* 氢能气压低 | */
|
|
|
+ VKFLY_ARM_DENIED_REASON_ENUM_END=23, /* | */
|
|
|
} VKFLY_ARM_DENIED_REASON;
|
|
|
```
|
|
|
|
|
@@ -136,7 +138,9 @@ typedef enum VKFLY_SYS_ERROR1
|
|
|
VKFLY_SYS_ERROR1_OUT_FENCE=64, /* 超出电子围栏范围 | */
|
|
|
VKFLY_SYS_ERROR1_OBV_LINK_LOST=128, /* 备用链路失联 | */
|
|
|
VKFLY_SYS_ERROR1_BATBMS_LINK_LOST=256, /* 智能电池bms数据失联 | */
|
|
|
- VKFLY_SYS_ERROR1_ENUM_END=257, /* | */
|
|
|
+ VKFLY_SYS_ERROR1_ECU_FUEL_LOW=512, /* 发动及油量低 | */
|
|
|
+ VKFLY_SYS_ERROR1_ECU_LINK_LOST=1024, /* 发动机数据断开 |*/
|
|
|
+ VKFLY_SYS_ERROR1_H2P_LOW=2048, /* 氢气压低 | */
|
|
|
} VKFLY_SYS_ERROR1;
|
|
|
```
|
|
|
|
|
@@ -220,8 +224,10 @@ typedef enum VKFLY_RTL_REASON
|
|
|
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_ENUM_END=14, /* | */
|
|
|
+ VKFLY_RTL_REASON_WP_FINISH=13, /* 航线完成返航 */
|
|
|
+ VKFLY_RTL_REASON_H2P_LOW=14, /* 氢能气压低返航 */
|
|
|
+ VKFLY_RTL_REASON_ECU_FUEL_LOW=15, /* 发动机油量低返航 */
|
|
|
+ VKFLY_RTL_REASON_ENUM_END=16, /* | */
|
|
|
} VKFLY_RTL_REASON;
|
|
|
```
|
|
|
|
|
@@ -245,6 +251,8 @@ typedef enum VKFLY_LOITER_REASON
|
|
|
VLFLY_LOITER_REASON_RC_BAD=13, /* 遥控器数据异常悬停 | */
|
|
|
VLFLY_LOITER_REASON_BAT_CAP_LOW=14, /* 电池电量低悬停 | */
|
|
|
VLFLY_LOITER_REASON_OFFBOARD=15, /* OFFBORAD控制悬停 | */
|
|
|
+ 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;
|
|
@@ -280,13 +288,13 @@ typedef enum VKFLY_YAW_CTRL_MODE
|
|
|
VKFLY_YAW_TO_HOME=4, /* 航向指向 HOME 点 | */
|
|
|
VKFLY_YAW_TO_INTEREST=5, /* 航向指向兴趣点 | */
|
|
|
VKFLY_YAW_TO_OTHER_MAV_SYS=6, /* 航向指向其它 mav system, 比如另一个无人机或车 | */
|
|
|
- VKFLY_YAW_CTRL_MODE_ENUM_END=7, /* | */
|
|
|
+ VKFLY_YAW_TO_SET_VALUE_ONLY_ON_LANDING=7, /* 当完成该航点后结束航线并降落时, 航向指向给定值。否则指向运动前方 */
|
|
|
+ VKFLY_YAW_CTRL_MODE_ENUM_END=8, /* | */
|
|
|
} VKFLY_YAW_CTRL_MODE;
|
|
|
```
|
|
|
|
|
|
### 1.14 自动拍照模式 VKFLY_PHOTO_CTRL_MODE
|
|
|
|
|
|
-
|
|
|
```c
|
|
|
typedef enum VKFLY_PHOTO_CTRL_MODE
|
|
|
{
|
|
@@ -827,12 +835,11 @@ param1-Hold 不为0或者NAN时,将执行自动转弯. 否则按对应时间悬
|
|
|
降落点
|
|
|
param3 作为飞往该点速度使用m/s, NAN表示使用飞控默认巡航速度参数.
|
|
|
|
|
|
-
|
|
|
#### 4.1.3 拍照航点 VKFLY_CMD_NAV_WP
|
|
|
|
|
|
拍照航点.
|
|
|
|
|
|
-param1 分为 byte[4] 进行使用.
|
|
|
+param1 分为 byte[4] 进行使用.
|
|
|
|
|
|
| 字节 | 类型 | 说明 |
|
|
|
| ---- | ----- | ----------------------------------------------------- |
|
|
@@ -856,6 +863,7 @@ param3 分为 byte[4] 进行使用.
|
|
|
| 2 | int16 | 当吊舱动作为设置角度时为吊舱航向角, 范围 -180-180. <br>当吊舱动作为设置缩放时为缩放倍率 * 10, 比如 5 倍为 50 |
|
|
|
|
|
|
其它 param4\5\6如下
|
|
|
+
|
|
|
| 参数 | 说明 |
|
|
|
| ------ | -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- |
|
|
|
| param4 | 该参数按 byte[4] 进行使用. <br>byte[0] u8, 为航向模式参考 VKFLY_YAW_CTRL_MODE. <br>byte[1] u8, 预留. <br>byte[2]-byte[3] s16, 范围-180-180. 当航向模式为 VKFLY_YAW_TO_SETVAL 时表示给定的航向值, 单位deg. 当航向模式为指向 <br>HOME 或 NEXT_WP 或 INTEREST 等给定点点时, 表示叠加的航向偏移. |
|
|
@@ -951,7 +959,7 @@ mavlink common 标准消息集中主要由 COMMAND_INT 和 COMMAND_LONG 两条.
|
|
|
|
|
|
### 5.5 校准指令 [MAV_CMD_PREFLIGHT_CALIBRATION](https://mavlink.io/en/messages/common.html#MAV_CMD_PREFLIGHT_CALIBRATION)
|
|
|
|
|
|
-校准命令, 请用 COMMAND_LONG
|
|
|
+校准命令, 请用 COMMAND_LONG
|
|
|
|
|
|
| 参数 | 说明 |
|
|
|
| ------ | --------------------------------------- |
|
|
@@ -1182,7 +1190,6 @@ param1~param5中,
|
|
|
| ------ | ------------------------------------------------------------------------------ |
|
|
|
| param1 | 参考 PARACHUTE_ACTION<br> 0-禁用自动开伞<br> 1-启用自动开伞<br> 2-立刻停桨开伞 |
|
|
|
|
|
|
-
|
|
|
### 5.31 数字电调配置 VKFLY_CMD_ESC_CONFIG
|
|
|
|
|
|
电调设置
|
|
@@ -1232,23 +1239,23 @@ param1~param5中,
|
|
|
|
|
|
- 直线返航 从指令开始位置直线返回到降落点
|
|
|
- 逆序返航 从指令开始位置逆序返回到降落点
|
|
|
- - 若指定了起始航点, 则从指定起始航点开始执行
|
|
|
- - 若未指定起始航点, 未执行过航线
|
|
|
- - 地面站指令返航, 则从最后一航点开始执行
|
|
|
- - 自动触发返航, 则直线返航
|
|
|
- - 若未指定起始航点, 执行过航线
|
|
|
- - 若前序航线顺序执行, 航线目标航点为第一个航点, 则直线返航
|
|
|
- - 若前序航线顺序执行, 航线目标航点不为第一个航点, 则从航线目标航点-1开始执行
|
|
|
- - 若前序航线逆序执行, 则从航线目标航点开始执行。
|
|
|
+ - 若指定了起始航点, 则从指定起始航点开始执行
|
|
|
+ - 若未指定起始航点, 未执行过航线
|
|
|
+ - 地面站指令返航, 则从最后一航点开始执行
|
|
|
+ - 自动触发返航, 则直线返航
|
|
|
+ - 若未指定起始航点, 执行过航线
|
|
|
+ - 若前序航线顺序执行, 航线目标航点为第一个航点, 则直线返航
|
|
|
+ - 若前序航线顺序执行, 航线目标航点不为第一个航点, 则从航线目标航点-1开始执行
|
|
|
+ - 若前序航线逆序执行, 则从航线目标航点开始执行。
|
|
|
- 顺序返航 从指令开始位置顺序返回到降落点
|
|
|
- - 若指定了起始航点, 则从指定起始航点开始执行。
|
|
|
- - 若未指定起始航点, 未执行过航线,
|
|
|
- - 地面站指令返航, 则从第一个航点开始执行
|
|
|
- - 自主触发返航, 则直线返航
|
|
|
- - 若未指定起始航点, 执行过航线
|
|
|
- - 若前序航线顺序执行, 则从航线目标航点开始执行
|
|
|
- - 若前序航线逆序执行, 航线目标航点为最后一个航点, 则直线返航
|
|
|
- - 若前序航线逆序执行, 航线目标航点不为最后一个航点, 则从航线目标航点+1开始执行
|
|
|
+ - 若指定了起始航点, 则从指定起始航点开始执行。
|
|
|
+ - 若未指定起始航点, 未执行过航线,
|
|
|
+ - 地面站指令返航, 则从第一个航点开始执行
|
|
|
+ - 自主触发返航, 则直线返航
|
|
|
+ - 若未指定起始航点, 执行过航线
|
|
|
+ - 若前序航线顺序执行, 则从航线目标航点开始执行
|
|
|
+ - 若前序航线逆序执行, 航线目标航点为最后一个航点, 则直线返航
|
|
|
+ - 若前序航线逆序执行, 航线目标航点不为最后一个航点, 则从航线目标航点+1开始执行
|
|
|
|
|
|
| 参数 | 说明 |
|
|
|
| ------ | ----------------------------------------------------------------------------------------------------------------- |
|
|
@@ -1262,8 +1269,6 @@ param1~param5中,
|
|
|
| param1 | 重量校准, 填写实际载重单位克. NAN表示忽略 |
|
|
|
| param2 | 1-恢复出厂配置. NAN表示忽略 |
|
|
|
|
|
|
-
|
|
|
-
|
|
|
## 6 飞控 LOG 读取
|
|
|
|
|
|
- LOG_REQUEST_LIST
|
|
@@ -1375,7 +1380,6 @@ VKins 系统的状态数据自定义消息, 主要用于一些自定状态的传
|
|
|
|
|
|
## 9 飞控参数说明
|
|
|
|
|
|
-
|
|
|
飞控参数名作为确认飞控参数用途的唯一识别码, 不可随意修改. 在新增参数时应注意不要与已有参数重名, 保持向前兼容性.
|
|
|
|
|
|
| 参数名 | 参数 | 类型 | 说明 |
|
|
@@ -1562,7 +1566,7 @@ VKins 系统的状态数据自定义消息, 主要用于一些自定状态的传
|
|
|
| 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_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-表示不启用 |
|
|
@@ -1573,8 +1577,6 @@ VKins 系统的状态数据自定义消息, 主要用于一些自定状态的传
|
|
|
| THROW_RCCH8 | 抛投8-遥控器通道映射 | UINT16 | 范围 0~18, 0-表示不启用 |
|
|
|
| THROW_RCCH9 | 抛投9-遥控器通道映射 | UINT16 | 范围 0~18, 0-表示不启用 |
|
|
|
| THROW_RCCH10 | 抛投10-遥控器通道映射 | UINT16 | 范围 0~18, 0-表示不启用 |
|
|
|
-| THROW_RCCH11 | 抛投11-遥控器通道映射 | UINT16 | 范围 0~18, 0-表示不启用 |
|
|
|
-| THROW_RCCH12 | 抛投12-遥控器通道映射 | 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-表示不启用 |
|
|
@@ -1585,8 +1587,6 @@ VKins 系统的状态数据自定义消息, 主要用于一些自定状态的传
|
|
|
| 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_CH11 | 抛投11-PWM输出通道映射 | UINT16 | 范围 0~16, 0-表示不启用 |
|
|
|
-| THROW_CH12 | 抛投12-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 |
|
|
@@ -1597,8 +1597,6 @@ VKins 系统的状态数据自定义消息, 主要用于一些自定状态的传
|
|
|
| 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_CH11_ON | 抛投11-打开PWM值 | UINT16 | 范围 0~2500 |
|
|
|
-| THROW_CH12_ON | 抛投12-打开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 |
|
|
@@ -1609,8 +1607,6 @@ VKins 系统的状态数据自定义消息, 主要用于一些自定状态的传
|
|
|
| THROW_CH8_OFF | 抛投8-关闭PWM值 | UINT16 | 范围 0~2500 |
|
|
|
| THROW_CH9_OFF | 抛投9-关闭PWM值 | UINT16 | 范围 0~2500 |
|
|
|
| THROW_CH10_OFF | 抛投10-关闭PWM值 | UINT16 | 范围 0~2500 |
|
|
|
-| THROW_CH11_OFF | 抛投11-关闭PWM值 | UINT16 | 范围 0~2500 |
|
|
|
-| THROW_CH12_OFF | 抛投12-关闭PWM值 | UINT16 | 范围 0~2500 |
|
|
|
| PARACHUTE_RCCH | 降落伞-遥控器通道映射 | UINT16 | 范围 0~18, 0-表示不启用 |
|
|
|
| PARACHUTE_CH | 降落伞-PWM输出通道映射 | UINT16 | 范围 7~16, 0-表示不启用 |
|
|
|
| PARACHUTE_ON | 降落伞-打开PWM值 | UINT16 | 范围 0~2500 |
|