3 Komitmen e3dd4cbc72 ... 3e61f10766

Pembuat SHA1 Pesan Tanggal
  Liu Yang 3e61f10766 生成头文件 5 hari lalu
  Liu Yang 554d4dc5fa 增加 error1 避障锁定报警 5 hari lalu
  Liu Yang 1223df3bd0 增加一些参数说明 5 hari lalu

+ 8 - 5
msg_definitions/VKFly.xml

@@ -247,16 +247,19 @@
         <description>Battery bms link lost.</description>
       </entry>
       <entry value="512" name="VKFLY_SYS_ERROR1_ECU_FUEL_LOW">
-        <description>Battery bms link lost.</description>
+        <description>ECU fuel percentage low.</description>
       </entry>
       <entry value="1024" name="VKFLY_SYS_ERROR1_ECU_LINK_LOST">
-        <description>Battery bms link lost.</description>
+        <description>ECU linklost.</description>
       </entry>
       <entry value="2048" name="VKFLY_SYS_ERROR1_H2P_LOW">
-        <description>Battery bms link lost.</description>
+        <description>H2 pressure low.</description>
       </entry>
       <entry value="4096" name="VKFLY_SYS_ERROR1_OVER_WEIGHT">
-        <description>Battery bms link lost.</description>
+        <description>Over weight.</description>
+      </entry>
+      <entry value="8192" name="VKFLY_SYS_ERROR1_OBSTACLE_AVOID">
+        <description>Obstacle avoid.</description>
       </entry>
     </enum>
 
@@ -1344,4 +1347,4 @@
 
   </messages>
 
-</mavlink>
+</mavlink>

+ 95 - 89
readme.md

@@ -173,6 +173,7 @@ typedef enum VKFLY_SYS_ERROR1
     VKFLY_SYS_ERROR1_ECU_LINK_LOST=1024, /* 发动机数据断开 |*/
     VKFLY_SYS_ERROR1_H2P_LOW=2048, /* 氢气压低 | */
     VKFLY_SYS_ERROR1_OVER_WEIGHT=4096, /* 负载超重 |*/
+    VKFLY_SYS_ERROR1_OBSTACLE_AVOID=8192, /* 避障锁定 | */
 } VKFLY_SYS_ERROR1;
 ```
 
@@ -2058,9 +2059,9 @@ VKins 系统的状态数据自定义消息, 主要用于一些自定状态的传
 | RTK_ANT_XOFF    | RTK定位天线X安装距离偏差             | INT32  | 范围-1000~1000, 单位cm <br>天线安装离飞机中心X轴向偏差距离                                         |
 | RTK_ANT_YOFF    | RTK定位天线Y安装距离偏差             | INT32  | 范围-1000~1000, 单位cm <br>天线安装离飞机中心Y轴向偏差距离                                         |
 | RTK_ANT_ZOFF    | RTK定位天线Z安装距离偏差             | INT32  | 范围-1000~1000, 单位cm <br>天线安装离飞机中心Z轴向偏差距离                                         |
-| RTK_ANT2_XOFF   | RTK2定位天线X安装距离偏差             | INT32  | 范围-1000~1000, 单位cm <br>天线安装离飞机中心X轴向偏差距离                                         |
-| RTK_ANT2_YOFF   | RTK2定位天线Y安装距离偏差             | INT32  | 范围-1000~1000, 单位cm <br>天线安装离飞机中心Y轴向偏差距离                                         |
-| RTK_ANT2_ZOFF   | RTK2定位天线Z安装距离偏差             | INT32  | 范围-1000~1000, 单位cm <br>天线安装离飞机中心Z轴向偏差距离                                         |
+| RTK_ANT2_XOFF   | RTK2定位天线X安装距离偏差            | INT32  | 范围-1000~1000, 单位cm <br>天线安装离飞机中心X轴向偏差距离                                         |
+| RTK_ANT2_YOFF   | RTK2定位天线Y安装距离偏差            | INT32  | 范围-1000~1000, 单位cm <br>天线安装离飞机中心Y轴向偏差距离                                         |
+| RTK_ANT2_ZOFF   | RTK2定位天线Z安装距离偏差            | INT32  | 范围-1000~1000, 单位cm <br>天线安装离飞机中心Z轴向偏差距离                                         |
 | RTK_H_COMP      | RTK测向先天安装角度偏差              | FLOAT  | 范围-180~180, 单位deg <br>常用前后安装 0deg, 左右安装 90deg                                        |
 | BAT_V_DIV0      | 电压通道0校准比例系数                | FLOAT  | 范围0~1000, 通道0为飞控供电电压                                                                    |
 | BAT_V_DIV1      | 电压通道1校准比例系数                | FLOAT  | 范围0~1000, 通道0为飞控供电电压                                                                    |
@@ -2193,92 +2194,97 @@ COM5_PROT_TYPE 的选项如下
 
 ### 9.2 垂起版本参数
 
-| 参数名          | 参数                     | 类型   | 说明                                                                              |
-| --------------- | ------------------------ | ------ | --------------------------------------------------------------------------------- |
-| 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 <br>0-不记录 <br>1-解锁到上锁 <br>2-上电到落锁 3-上电到下电               |
-| BOOT_MODE       | 系统启动模式             | UINT8  | 范围0~1, 0-正常启动, 1-U盘模式(用于导入导出数据文件)                              |
-| HW_SN_NUM       | 硬件SN号                 | UINT32 | 范围0~UINT32_MAX                                                                  |
-| AIRFRAME        | 旋翼机型                 | UINT16 | 参考 VKFLY_AP_TYPE, 垂起仅支持 X4, X4R                                            |
-| FW_AIRFRAME     | 固定翼机型               | UINT16 | 参考 VKFLY_FIXEDWING_AP_TYPE                                                      |
-| GCS_DISCONT_DT  | 地面站失联时间           | UINT16 | 范围0~UINT16_MAX, 单位s. 持续未收到地面站心跳的时间, 0-表示不检测地面站失联       |
-| 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%                                                                 |
-| VOLT_PROT_CH    | 电压保护通道             | UINT16 | 范围0~10, 触发电压保护的通道, 默认0飞控供电                                       |
-| FS_CONF_A       | 失控保护设置             | UINT32 | 参考enum FS_ACTION.                                                               |
-| CIR_RAD_DFLT    | 默认环绕/盘旋半径        | FLOAT  | 单位m, 范围100~10000m , 默认200                                                   |
-| TOF_ALT_M       | 默认起飞高度             | FLOAT  | 范围1~5000, 单位m                                                                 |
-| RTL_ALT_M       | 默认返航高度             | FLOAT  | 范围1~5000, 单位m                                                                 |
-| FUEL_LOW1_VAL   | 一级ecu油量低阈值        | FLOAT  | 范围 1~100, 单位%                                                                 |
-| FUEL_LOW2_VAL   | 二级ecu油量低阈值        | FLOAT  | 范围 1~100, 单位%                                                                 |
-| FW_ROLL_KP      | 固定翼横滚感度           | UINT16 | 范围 500~2000, 默认1000                                                           |
-| FW_ROLL_KI      | 固定翼横滚积分           | UINT16 | 范围 0~1000, 默认100                                                              |
-| FW_ROLL_KD      | 固定翼横滚阻尼           | UINT16 | 范围 0~1000, 默认100                                                              |
-| FW_PITCH_KP     | 固定翼俯仰感度           | UINT16 | 范围 500~2000, 默认1000                                                           |
-| FW_PITCH_KI     | 固定翼俯仰积分           | UINT16 | 范围 0~1000, 默认100                                                              |
-| FW_PITCH_KD     | 固定翼俯仰阻尼           | UINT16 | 范围 0~1000, 默认100                                                              |
-| FW_YAW_KD       | 固定翼航向阻尼           | UINT16 | 范围 0~1000, 默认100                                                              |
-| FW_L1_PERIOD    | 固定翼L1周期             | UINT16 | 范围1500~3000, 默认2500                                                           |
-| FW_L1_DAMPING   | 固定翼L1阻尼             | UINT16 | 范围60~100, 默认80                                                                |
-| FW_L1_KI        | 固定翼L1积分             | UINT16 | 范围0~10, 默认2                                                                   |
-| FW_ALT_KP       | 固定翼高度比例           | UINT16 | 范围10~150, 默认 50                                                               |
-| FW_VU_KP        | 固定翼垂速比例           | UINT16 | 范围200~500, 默认 350                                                             |
-| FW_VU_KI        | 固定翼垂速积分           | UINT16 | 范围0~100, 默认10                                                                 |
-| FW_ASPD_THR_KP  | 固定翼油门比例           | UINT16 | 范围10~300, 默认80                                                                |
-| FW_ASPD_THR_KI  | 固定翼油门积分           | UINT16 | 范围1~100, 默认10                                                                 |
-| FW_ROLL_ELEV_KP | 固定翼横滚拉杆补偿       | UINT16 | 范围0~10, 默认3                                                                   |
-| FW_ROLL_MAX     | 固定翼最大横滚角         | FLOAT  | 单位deg, 范围15~45,  默认30                                                       |
-| FW_PITCH_MAX    | 固定翼最大俯仰角         | FLOAT  | 单位deg, 范围5~30, 默认15                                                         |
-| FW_TOF_PITCH    | 固定翼起飞俯仰角         | FLOAT  | 单位deg, 范围 5~30, 默认12                                                        |
-| FW_TOF_THR_DL   | 固定翼起飞油门启动延迟   | INT32  | 单位ms, 范围 -1~2000. 负值表示先启动油门, 正值表示检测到过载后再延迟启动油门      |
-| FW_VU_MAX       | 固定翼最大爬升率         | FLOAT  | 单位m/s, 范围1~10, 默认5                                                          |
-| FW_VD_MAX       | 固定翼最大下降率         | FLOAT  | 单位m/s, 范围1~10, 默认5                                                          |
-| FW_ASPD_STALL   | 固定翼失速空速           | FLOAT  | 单位m/s, 范围 10~200, 默认16                                                      |
-| FW_ASPD_MIN     | 固定翼最小空速           | FLOAT  | 单位m/s, 范围 10~200, 默认20                                                      |
-| FW_ASPD_CRUISE  | 固定翼巡航空速           | FLOAT  | 单位m/s, 范围 10~200, 默认22                                                      |
-| FW_TOF_THR      | 切换固定翼最大油门       | UINT16 | 单位1%, 范围10~100, 默认90                                                        |
-| TRANS_FW_TMO    | 切换固定翼超时时间       | UINT16 | 单位s, 范围5~100, 默认10                                                          |
-| TRANS_MC_DIST   | 切换旋翼提前距离         | UINT16 | 单位m,  范围50~500, 默认100                                                       |
-| MC_RP_ANG_KP    | 旋翼横滚俯仰角度比例系数 | UINT16 | 范围200~800                                                                       |
-| MC_YAW_ANG_KP   | 旋翼航向角度比例系数     | UINT16 | 范围200~800                                                                       |
-| MC_RSPD_KP      | 旋翼横滚角速度比例系数   | UINT16 | 范围30~200                                                                        |
-| MC_RSPD_KD      | 旋翼横滚角速度微分系数   | UINT16 | 范围0~20                                                                          |
-| MC_PSPD_KP      | 旋翼俯仰角速度比例系数   | UINT16 | 范围30~200                                                                        |
-| MC_PSPD_KD      | 旋翼俯仰角速度微分系数   | UINT16 | 范围0~20                                                                          |
-| MC_YSPD_KP      | 旋翼航向角速度比例系数   | UINT16 | 范围50~400                                                                        |
-| 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, 默认 0.15                                                          |
-| FW_RNG_AILEL_D  | 左副翼或前翼行程下       | UINT16 | 范围500~2500, T尾V尾左副翼下, 串联翼左前翼下, 三角翼左翼下                        |
-| FW_RNG_AILEL_M  | 左副翼或前翼行程中       | UINT16 | 范围500~2500, T尾V尾左副翼中, 串联翼左前翼中, 三角翼左翼中                        |
-| FW_RNG_AILEL_U  | 左副翼或前翼行程上       | UINT16 | 范围500~2500, T尾V尾左副翼上, 串联翼左前翼上, 三角翼左翼上                        |
-| FW_RNG_AILER_D  | 右副翼或前翼行程下       | UINT16 | 范围500~2500, T尾V尾右副翼下, 串联翼右前翼下, 三角翼右翼下                        |
-| FW_RNG_AILER_M  | 右副翼或前翼行程中       | UINT16 | 范围500~2500, T尾V尾右副翼中, 串联翼右前翼中, 三角翼右翼中                        |
-| FW_RNG_AILER_U  | 右副翼或前翼行程上       | UINT16 | 范围500~2500, T尾V尾右副翼上, 串联翼右前翼上, 三角翼右翼上                        |
-| FW_RNG_ELEVL_D  | 左升降或后翼行程下       | UINT16 | 范围500~2500, T尾左升降下, V尾左尾下, 倒V尾左尾下, 串联翼左后翼下, 三角翼左鸭翼下 |
-| FW_RNG_ELEVL_M  | 左升降或后翼行程中       | UINT16 | 范围500~2500, T尾左升降中, V尾左尾中, 倒V尾左尾中, 串联翼左后翼中, 三角翼左鸭翼中 |
-| FW_RNG_ELEVL_U  | 左升降或后翼行程上       | UINT16 | 范围500~2500, T尾左升降上, V尾左尾上, 倒V尾左尾上, 串联翼左后翼上, 三角翼左鸭翼上 |
-| FW_RNG_ELEVL_D  | 右升降或后翼行程下       | UINT16 | 范围500~2500, T尾右升降下, V尾左尾下, 倒V尾左尾下, 串联翼右后翼下, 三角翼右鸭翼下 |
-| FW_RNG_ELEVL_M  | 右升降或后翼行程中       | UINT16 | 范围500~2500, T尾右升降中, V尾左尾中, 倒V尾左尾中, 串联翼右后翼中, 三角翼右鸭翼中 |
-| FW_RNG_ELEVL_U  | 右升降或后翼行程上       | UINT16 | 范围500~2500, T尾右升降上, V尾左尾上, 倒V尾左尾上, 串联翼右后翼上, 三角翼右鸭翼上 |
-| FW_RND_RUD_L    | 方向舵行程左             | UINT16 | 范围500~2500                                                                      |
-| FW_RND_RUD_M    | 方向舵行程中             | UINT16 | 范围500~2500                                                                      |
-| FW_RND_RUD_R    | 方向舵行程右             | UINT16 | 范围500~2500                                                                      |
-| FW_THR_OFF      | 油门行程灭车             | UINT16 | 范围500~2500                                                                      |
-| FW_THR_MIN      | 油门行程怠速             | UINT16 | 范围500~2500                                                                      |
-| FW_THR_MAX      | 油门行程最大             | UINT16 | 范围500~2500                                                                      |
+| 参数名          | 参数                          | 类型   | 说明                                                                              |
+| --------------- | ----------------------------- | ------ | --------------------------------------------------------------------------------- |
+| 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 <br>0-不记录 <br>1-解锁到上锁 <br>2-上电到落锁 3-上电到下电               |
+| BOOT_MODE       | 系统启动模式                  | UINT8  | 范围0~1, 0-正常启动, 1-U盘模式(用于导入导出数据文件)                              |
+| HW_SN_NUM       | 硬件SN号                      | UINT32 | 范围0~UINT32_MAX                                                                  |
+| AIRFRAME        | 旋翼机型                      | UINT16 | 参考 VKFLY_AP_TYPE, 垂起仅支持 X4, X4R                                            |
+| FW_AIRFRAME     | 固定翼机型                    | UINT16 | 参考 VKFLY_FIXEDWING_AP_TYPE                                                      |
+| GCS_DISCONT_DT  | 地面站失联时间                | UINT16 | 范围0~UINT16_MAX, 单位s. 持续未收到地面站心跳的时间, 0-表示不检测地面站失联       |
+| VOLT1_LOW_VAL   | 一级电压低阈值                | FLOAT  | 范围0~1000, 单位V                                                                 |
+| VOLT2_LOW_VAL   | 二级电压低阈值                | FLOAT  | 范围0~1000, 单位V                                                                 |
+| VOLT1_1_LOW_VAL | 第二路电压 一级电压低阈值     | FLOAT  | 范围0~1000, 单位V                                                                 |
+| VOLT2_1_LOW_VAL | 第二路电压 二级电压低阈值     | FLOAT  | 范围0~1000, 单位V                                                                 |
+| VOLT1_1_LOW_ACT | 第二路电压 一级电压低保护动作 | UINT8  | 参考 VKFLY_FS_ACTION                                                              |
+| VOLT2_1_LOW_ACT | 第二路电压 二级电压低保护动作 | UINT8  | 参考 VKFLY_FS_ACTION                                                              |
+| VCAP1_LOW_VAL   | 一级电量低阈值                | UINT8  | 范围0~100, 单位1%, 当具有多个智能电池时, 飞控按他们的平均电量进行触发保护判定     |
+| VCAP2_LOW_VAL   | 二级电量低阈值                | UINT8  | 范围0~100, 单位1%                                                                 |
+| VOLT_PROT_CH    | 电压保护通道                  | UINT16 | 范围0~10, 触发电压保护的通道, 默认0飞控供电                                       |
+| FS_CONF_A       | 失控保护设置                  | UINT32 | 参考enum FS_ACTION.                                                               |
+| CIR_RAD_DFLT    | 默认环绕/盘旋半径             | FLOAT  | 单位m, 范围100~10000m , 默认200                                                   |
+| TOF_ALT_M       | 默认起飞高度                  | FLOAT  | 范围1~5000, 单位m                                                                 |
+| RTL_ALT_M       | 默认返航高度                  | FLOAT  | 范围1~5000, 单位m                                                                 |
+| FUEL_LOW1_VAL   | 一级ecu油量低阈值             | FLOAT  | 范围 1~100, 单位%                                                                 |
+| FUEL_LOW2_VAL   | 二级ecu油量低阈值             | FLOAT  | 范围 1~100, 单位%                                                                 |
+| FW_ROLL_KP      | 固定翼横滚感度                | UINT16 | 范围 500~2000, 默认1000                                                           |
+| FW_ROLL_KI      | 固定翼横滚积分                | UINT16 | 范围 0~1000, 默认100                                                              |
+| FW_ROLL_KD      | 固定翼横滚阻尼                | UINT16 | 范围 0~1000, 默认100                                                              |
+| FW_PITCH_KP     | 固定翼俯仰感度                | UINT16 | 范围 500~2000, 默认1000                                                           |
+| FW_PITCH_KI     | 固定翼俯仰积分                | UINT16 | 范围 0~1000, 默认100                                                              |
+| FW_PITCH_KD     | 固定翼俯仰阻尼                | UINT16 | 范围 0~1000, 默认100                                                              |
+| FW_YAW_KD       | 固定翼航向阻尼                | UINT16 | 范围 0~1000, 默认100                                                              |
+| FW_L1_PERIOD    | 固定翼L1周期                  | UINT16 | 范围1500~3000, 默认2500                                                           |
+| FW_L1_DAMPING   | 固定翼L1阻尼                  | UINT16 | 范围60~100, 默认80                                                                |
+| FW_L1_KI        | 固定翼L1积分                  | UINT16 | 范围0~10, 默认2                                                                   |
+| FW_ALT_KP       | 固定翼高度比例                | UINT16 | 范围10~150, 默认 50                                                               |
+| FW_VU_KP        | 固定翼垂速比例                | UINT16 | 范围200~500, 默认 350                                                             |
+| FW_VU_KI        | 固定翼垂速积分                | UINT16 | 范围0~100, 默认10                                                                 |
+| FW_ASPD_THR_KP  | 固定翼油门比例                | UINT16 | 范围10~300, 默认80                                                                |
+| FW_ASPD_THR_KI  | 固定翼油门积分                | UINT16 | 范围1~100, 默认10                                                                 |
+| FW_ROLL_ELEV_KP | 固定翼横滚拉杆补偿            | UINT16 | 范围0~10, 默认3                                                                   |
+| FW_ROLL_MAX     | 固定翼最大横滚角              | FLOAT  | 单位deg, 范围15~45,  默认30                                                       |
+| FW_PITCH_MAX    | 固定翼最大俯仰角              | FLOAT  | 单位deg, 范围5~30, 默认15                                                         |
+| FW_TOF_PITCH    | 固定翼起飞俯仰角              | FLOAT  | 单位deg, 范围 5~30, 默认12                                                        |
+| FW_TOF_THR_DL   | 固定翼起飞油门启动延迟        | INT32  | 单位ms, 范围 -1~2000. 负值表示先启动油门, 正值表示检测到过载后再延迟启动油门      |
+| FW_VU_MAX       | 固定翼最大爬升率              | FLOAT  | 单位m/s, 范围1~10, 默认5                                                          |
+| FW_VD_MAX       | 固定翼最大下降率              | FLOAT  | 单位m/s, 范围1~10, 默认5                                                          |
+| FW_ASPD_STALL   | 固定翼失速空速                | FLOAT  | 单位m/s, 范围 10~200, 默认16                                                      |
+| FW_ASPD_MIN     | 固定翼最小空速                | FLOAT  | 单位m/s, 范围 10~200, 默认20                                                      |
+| FW_ASPD_CRUISE  | 固定翼巡航空速                | FLOAT  | 单位m/s, 范围 10~200, 默认22                                                      |
+| FW_TOF_THR      | 切换固定翼最大油门            | UINT16 | 单位1%, 范围10~100, 默认90                                                        |
+| TRANS_FW_TMO    | 切换固定翼超时时间            | UINT16 | 单位s, 范围5~100, 默认10                                                          |
+| TRANS_MC_DIST   | 切换旋翼提前距离              | UINT16 | 单位m,  范围50~500, 默认100                                                       |
+| MC_RP_ANG_KP    | 旋翼横滚俯仰角度比例系数      | UINT16 | 范围200~800                                                                       |
+| MC_YAW_ANG_KP   | 旋翼航向角度比例系数          | UINT16 | 范围200~800                                                                       |
+| MC_RSPD_KP      | 旋翼横滚角速度比例系数        | UINT16 | 范围30~200                                                                        |
+| MC_RSPD_KD      | 旋翼横滚角速度微分系数        | UINT16 | 范围0~20                                                                          |
+| MC_PSPD_KP      | 旋翼俯仰角速度比例系数        | UINT16 | 范围30~200                                                                        |
+| MC_PSPD_KD      | 旋翼俯仰角速度微分系数        | UINT16 | 范围0~20                                                                          |
+| MC_YSPD_KP      | 旋翼航向角速度比例系数        | UINT16 | 范围50~400                                                                        |
+| 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, 默认 0.15                                                          |
+| FW_RNG_AILEL_D  | 左副翼或前翼行程下            | UINT16 | 范围500~2500, T尾V尾左副翼下, 串联翼左前翼下, 三角翼左翼下                        |
+| FW_RNG_AILEL_M  | 左副翼或前翼行程中            | UINT16 | 范围500~2500, T尾V尾左副翼中, 串联翼左前翼中, 三角翼左翼中                        |
+| FW_RNG_AILEL_U  | 左副翼或前翼行程上            | UINT16 | 范围500~2500, T尾V尾左副翼上, 串联翼左前翼上, 三角翼左翼上                        |
+| FW_RNG_AILER_D  | 右副翼或前翼行程下            | UINT16 | 范围500~2500, T尾V尾右副翼下, 串联翼右前翼下, 三角翼右翼下                        |
+| FW_RNG_AILER_M  | 右副翼或前翼行程中            | UINT16 | 范围500~2500, T尾V尾右副翼中, 串联翼右前翼中, 三角翼右翼中                        |
+| FW_RNG_AILER_U  | 右副翼或前翼行程上            | UINT16 | 范围500~2500, T尾V尾右副翼上, 串联翼右前翼上, 三角翼右翼上                        |
+| FW_RNG_ELEVL_D  | 左升降或后翼行程下            | UINT16 | 范围500~2500, T尾左升降下, V尾左尾下, 倒V尾左尾下, 串联翼左后翼下, 三角翼左鸭翼下 |
+| FW_RNG_ELEVL_M  | 左升降或后翼行程中            | UINT16 | 范围500~2500, T尾左升降中, V尾左尾中, 倒V尾左尾中, 串联翼左后翼中, 三角翼左鸭翼中 |
+| FW_RNG_ELEVL_U  | 左升降或后翼行程上            | UINT16 | 范围500~2500, T尾左升降上, V尾左尾上, 倒V尾左尾上, 串联翼左后翼上, 三角翼左鸭翼上 |
+| FW_RNG_ELEVL_D  | 右升降或后翼行程下            | UINT16 | 范围500~2500, T尾右升降下, V尾左尾下, 倒V尾左尾下, 串联翼右后翼下, 三角翼右鸭翼下 |
+| FW_RNG_ELEVL_M  | 右升降或后翼行程中            | UINT16 | 范围500~2500, T尾右升降中, V尾左尾中, 倒V尾左尾中, 串联翼右后翼中, 三角翼右鸭翼中 |
+| FW_RNG_ELEVL_U  | 右升降或后翼行程上            | UINT16 | 范围500~2500, T尾右升降上, V尾左尾上, 倒V尾左尾上, 串联翼右后翼上, 三角翼右鸭翼上 |
+| FW_RND_RUD_L    | 方向舵行程左                  | UINT16 | 范围500~2500                                                                      |
+| FW_RND_RUD_M    | 方向舵行程中                  | UINT16 | 范围500~2500                                                                      |
+| FW_RND_RUD_R    | 方向舵行程右                  | UINT16 | 范围500~2500                                                                      |
+| FW_THR_OFF      | 油门行程灭车                  | UINT16 | 范围500~2500                                                                      |
+| FW_THR_MIN      | 油门行程怠速                  | UINT16 | 范围500~2500                                                                      |
+| FW_THR_MAX      | 油门行程最大                  | UINT16 | 范围500~2500                                                                      |
+| HOLL0_PRESC     | 霍尔转速分频数                | UINT16 | 范围1~10, 将采集的霍尔转速按此系数进行分频, 值由采集头个数决定                    |
 
 #### 9.2.1 FS_CONF_A 参数说明
 

+ 8 - 7
v2.0/VKFly/VKFly.h

@@ -10,7 +10,7 @@
     #error Wrong include order: MAVLINK_VKFLY.H MUST NOT BE DIRECTLY USED. Include mavlink.h from the same directory instead or set ALL AND EVERY defines from MAVLINK.H manually accordingly, including the #define MAVLINK_H call.
 #endif
 
-#define MAVLINK_VKFLY_XML_HASH -992509777465783844
+#define MAVLINK_VKFLY_XML_HASH -5628547367346913573
 
 #ifdef __cplusplus
 extern "C" {
@@ -216,11 +216,12 @@ typedef enum VKFLY_SYS_ERROR1
    VKFLY_SYS_ERROR1_OUT_FENCE=64, /* Position out of fence range. | */
    VKFLY_SYS_ERROR1_OBV_LINK_LOST=128, /* Obv mavlink com link lost. | */
    VKFLY_SYS_ERROR1_BATBMS_LINK_LOST=256, /* Battery bms link lost. | */
-   VKFLY_SYS_ERROR1_ECU_FUEL_LOW=512, /* Battery bms link lost. | */
-   VKFLY_SYS_ERROR1_ECU_LINK_LOST=1024, /* Battery bms link lost. | */
-   VKFLY_SYS_ERROR1_H2P_LOW=2048, /* Battery bms link lost. | */
-   VKFLY_SYS_ERROR1_OVER_WEIGHT=4096, /* Battery bms link lost. | */
-   VKFLY_SYS_ERROR1_ENUM_END=4097, /*  | */
+   VKFLY_SYS_ERROR1_ECU_FUEL_LOW=512, /* ECU fuel percentage low. | */
+   VKFLY_SYS_ERROR1_ECU_LINK_LOST=1024, /* ECU linklost. | */
+   VKFLY_SYS_ERROR1_H2P_LOW=2048, /* H2 pressure low. | */
+   VKFLY_SYS_ERROR1_OVER_WEIGHT=4096, /* Over weight. | */
+   VKFLY_SYS_ERROR1_OBSTACLE_AVOID=8192, /* Obstacle avoid. | */
+   VKFLY_SYS_ERROR1_ENUM_END=8193, /*  | */
 } VKFLY_SYS_ERROR1;
 #endif
 
@@ -739,7 +740,7 @@ typedef enum MAV_CMD
    VKFLY_CMD_NAV_EDU_TRAINING=44013, /* VLFLY Custom orbit waypoint  | |  |  |  | Latitude| Longitude| Altitude|  */
    VKFLY_CMD_MOUNT_CTRL=44030, /* VLFLY Custom orbit waypoint  | |  |  |  | Latitude| Longitude| Altitude|  */
    VKFLY_CMD_FORMATION_FLY=44031, /* Formation fly assemble, disband or change formation |1 means assemble, 2 means quit, 3 means change formation| | | | | | |  */
-   VKFLY_CMD_ESC_CONFIG=44050, /* can esc id configuration | Set Esc id, min=1, max=16 |  |  |  |  |  |  |  */
+   VKFLY_CMD_ESC_CONFIG=44050, /* can esc id configuration | Set Esc id, minValue=1, maxValue=16 |  |  |  |  |  |  |  */
    VKFLY_CMD_RFD_CONFIG=44051, /* can esc id configuration | target component id |  set blind zone, NAN means ignore |  set max range, NAN means ignore |  |  |  |  |  */
    VKFLY_CMD_DO_REPOSITION_THAN_THROW=44060, /* Do reposition and throwing | Throw servo id bitmap |  |  |  |  |  |  |  */
    VKFLY_CMD_DO_REPOSITION_THAN_LAND=44061, /* Do reposition and throwing | Ground msl altitude|  |  |  |  |  |  |  */

+ 1 - 1
v2.0/VKFly/mavlink.h

@@ -6,7 +6,7 @@
 #ifndef MAVLINK_H
 #define MAVLINK_H
 
-#define MAVLINK_PRIMARY_XML_HASH -992509777465783844
+#define MAVLINK_PRIMARY_XML_HASH -5628547367346913573
 
 #ifndef MAVLINK_STX
 #define MAVLINK_STX 253

+ 24 - 12
v2.0/VKFly/mavlink_msg_fmub_status.h

@@ -23,9 +23,11 @@ typedef struct __mavlink_fmub_status_t {
  float amsl; /*< [m] altitude above mean sea level.*/
  int32_t ins_status; /*<  */
  int32_t ins_flag; /*<  */
- uint16_t throttle; /*<  throttle output.*/
+ uint16_t throttle; /*<  throttle
+        output.*/
  uint8_t flight_mode; /*<  flight mode.*/
- uint8_t btake_status; /*<  backup takeover
+ uint8_t btake_status; /*<  backup
+        takeover
         status.*/
 } mavlink_fmub_status_t;
 
@@ -120,9 +122,11 @@ typedef struct __mavlink_fmub_status_t {
  * @param amsl [m] altitude above mean sea level.
  * @param ins_status  
  * @param ins_flag  
- * @param throttle  throttle output.
+ * @param throttle  throttle
+        output.
  * @param flight_mode  flight mode.
- * @param btake_status  backup takeover
+ * @param btake_status  backup
+        takeover
         status.
  * @return length of the message in bytes (excluding serial stream start sign)
  */
@@ -210,9 +214,11 @@ static inline uint16_t mavlink_msg_fmub_status_pack(uint8_t system_id, uint8_t c
  * @param amsl [m] altitude above mean sea level.
  * @param ins_status  
  * @param ins_flag  
- * @param throttle  throttle output.
+ * @param throttle  throttle
+        output.
  * @param flight_mode  flight mode.
- * @param btake_status  backup takeover
+ * @param btake_status  backup
+        takeover
         status.
  * @return length of the message in bytes (excluding serial stream start sign)
  */
@@ -303,9 +309,11 @@ static inline uint16_t mavlink_msg_fmub_status_pack_status(uint8_t system_id, ui
  * @param amsl [m] altitude above mean sea level.
  * @param ins_status  
  * @param ins_flag  
- * @param throttle  throttle output.
+ * @param throttle  throttle
+        output.
  * @param flight_mode  flight mode.
- * @param btake_status  backup takeover
+ * @param btake_status  backup
+        takeover
         status.
  * @return length of the message in bytes (excluding serial stream start sign)
  */
@@ -432,9 +440,11 @@ static inline uint16_t mavlink_msg_fmub_status_encode_status(uint8_t system_id,
  * @param amsl [m] altitude above mean sea level.
  * @param ins_status  
  * @param ins_flag  
- * @param throttle  throttle output.
+ * @param throttle  throttle
+        output.
  * @param flight_mode  flight mode.
- * @param btake_status  backup takeover
+ * @param btake_status  backup
+        takeover
         status.
  */
 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
@@ -760,7 +770,8 @@ static inline int32_t mavlink_msg_fmub_status_get_ins_flag(const mavlink_message
 /**
  * @brief Get field throttle from fmub_status message
  *
- * @return  throttle output.
+ * @return  throttle
+        output.
  */
 static inline uint16_t mavlink_msg_fmub_status_get_throttle(const mavlink_message_t* msg)
 {
@@ -780,7 +791,8 @@ static inline uint8_t mavlink_msg_fmub_status_get_flight_mode(const mavlink_mess
 /**
  * @brief Get field btake_status from fmub_status message
  *
- * @return  backup takeover
+ * @return  backup
+        takeover
         status.
  */
 static inline uint8_t mavlink_msg_fmub_status_get_btake_status(const mavlink_message_t* msg)

+ 1 - 1
v2.0/VKFly/version.h

@@ -7,7 +7,7 @@
 #ifndef MAVLINK_VERSION_H
 #define MAVLINK_VERSION_H
 
-#define MAVLINK_BUILD_DATE "Thu Feb 26 2026"
+#define MAVLINK_BUILD_DATE "Tue Mar 31 2026"
 #define MAVLINK_WIRE_PROTOCOL_VERSION "2.0"
 #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255
  

+ 1 - 1
v2.0/common/common.h

@@ -10,7 +10,7 @@
     #error Wrong include order: MAVLINK_COMMON.H MUST NOT BE DIRECTLY USED. Include mavlink.h from the same directory instead or set ALL AND EVERY defines from MAVLINK.H manually accordingly, including the #define MAVLINK_H call.
 #endif
 
-#define MAVLINK_COMMON_XML_HASH -6447195062229904136
+#define MAVLINK_COMMON_XML_HASH 7069897735541995260
 
 #ifdef __cplusplus
 extern "C" {

+ 1 - 1
v2.0/common/mavlink.h

@@ -6,7 +6,7 @@
 #ifndef MAVLINK_H
 #define MAVLINK_H
 
-#define MAVLINK_PRIMARY_XML_HASH -6447195062229904136
+#define MAVLINK_PRIMARY_XML_HASH 7069897735541995260
 
 #ifndef MAVLINK_STX
 #define MAVLINK_STX 253

+ 1 - 1
v2.0/common/version.h

@@ -7,7 +7,7 @@
 #ifndef MAVLINK_VERSION_H
 #define MAVLINK_VERSION_H
 
-#define MAVLINK_BUILD_DATE "Thu Feb 26 2026"
+#define MAVLINK_BUILD_DATE "Tue Mar 31 2026"
 #define MAVLINK_WIRE_PROTOCOL_VERSION "2.0"
 #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255
  

+ 1 - 1
v2.0/minimal/mavlink.h

@@ -6,7 +6,7 @@
 #ifndef MAVLINK_H
 #define MAVLINK_H
 
-#define MAVLINK_PRIMARY_XML_HASH 8869005500997421512
+#define MAVLINK_PRIMARY_XML_HASH -8425130030743674314
 
 #ifndef MAVLINK_STX
 #define MAVLINK_STX 253

+ 1 - 1
v2.0/minimal/minimal.h

@@ -10,7 +10,7 @@
     #error Wrong include order: MAVLINK_MINIMAL.H MUST NOT BE DIRECTLY USED. Include mavlink.h from the same directory instead or set ALL AND EVERY defines from MAVLINK.H manually accordingly, including the #define MAVLINK_H call.
 #endif
 
-#define MAVLINK_MINIMAL_XML_HASH 8869005500997421512
+#define MAVLINK_MINIMAL_XML_HASH -8425130030743674314
 
 #ifdef __cplusplus
 extern "C" {

+ 1 - 1
v2.0/minimal/version.h

@@ -7,7 +7,7 @@
 #ifndef MAVLINK_VERSION_H
 #define MAVLINK_VERSION_H
 
-#define MAVLINK_BUILD_DATE "Thu Feb 26 2026"
+#define MAVLINK_BUILD_DATE "Tue Mar 31 2026"
 #define MAVLINK_WIRE_PROTOCOL_VERSION "2.0"
 #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 22
  

+ 1 - 1
v2.0/standard/mavlink.h

@@ -6,7 +6,7 @@
 #ifndef MAVLINK_H
 #define MAVLINK_H
 
-#define MAVLINK_PRIMARY_XML_HASH -7535397402208776511
+#define MAVLINK_PRIMARY_XML_HASH -7463754958872367563
 
 #ifndef MAVLINK_STX
 #define MAVLINK_STX 253

+ 1 - 1
v2.0/standard/standard.h

@@ -10,7 +10,7 @@
     #error Wrong include order: MAVLINK_STANDARD.H MUST NOT BE DIRECTLY USED. Include mavlink.h from the same directory instead or set ALL AND EVERY defines from MAVLINK.H manually accordingly, including the #define MAVLINK_H call.
 #endif
 
-#define MAVLINK_STANDARD_XML_HASH -7535397402208776511
+#define MAVLINK_STANDARD_XML_HASH -7463754958872367563
 
 #ifdef __cplusplus
 extern "C" {

+ 1 - 1
v2.0/standard/version.h

@@ -7,7 +7,7 @@
 #ifndef MAVLINK_VERSION_H
 #define MAVLINK_VERSION_H
 
-#define MAVLINK_BUILD_DATE "Thu Feb 26 2026"
+#define MAVLINK_BUILD_DATE "Tue Mar 31 2026"
 #define MAVLINK_WIRE_PROTOCOL_VERSION "2.0"
 #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 22