Browse Source

增加舵面检查, 设置返航盘旋点等

Liu Yang 3 months ago
parent
commit
5c1d74a048
2 changed files with 199 additions and 88 deletions
  1. 57 1
      msg_definitions/VKFly.xml
  2. 142 87
      readme.md

+ 57 - 1
msg_definitions/VKFly.xml

@@ -263,6 +263,9 @@
       <entry value="256" name="VKFLY_SYS_ERROR3_YAW_DIFF">
         <description></description>
       </entry>
+      <entry value="256" name="VKFLY_SYS_ERROR3_ASPD_LINK_LOST">
+        <description></description>
+      </entry>
     </enum>
 
     <enum name="VKFLY_CUSTOM_MODE">
@@ -472,6 +475,9 @@
       <entry value="17" name="VKFLY_RTL_REASON_TRANS_TMO">
         <description>Trigger rtl mode by transform time out.</description>
       </entry>
+      <entry value="18" name="VKFLY_RTL_REASON_ASPD_LOW">
+        <description>Trigger rtl mode by transform time out.</description>
+      </entry>
     </enum>
 
     <enum name="VKFLY_LOITER_REASON">
@@ -744,6 +750,37 @@
         <param index="7" label=""> </param>
       </entry>
 
+      <entry value="44065" name="VKFLY_CMD_DO_FIXEDWING_ACTUATOR_CHECK" hasLocation="false"
+        isDestination="false">
+        <description>Check fixedwing servos.</description>
+        <param index="1" label="actuator check" minValue="0" maxValue="9">NAN means ignore.0 do all
+          mid, 1 do roll mid, 2 do roll right, 3 do roll left, 4 do pitch mid, 5 do pitch up, 6 do
+          pitch down, 7 do yaw mid, 8 do yaw right, 9 do yaw down.</param>
+        <param index="2" label="throttle check" minValue="-1" maxValue="100"> NAN means ignore. -1
+          throttle off, 0 throttle idle, 100 throttle full </param>
+        <param index="3" label=""> </param>
+        <param index="4" label=""> </param>
+        <param index="5" label=""> </param>
+        <param index="6" label=""> </param>
+        <param index="7" label=""> </param>
+      </entry>
+
+      <entry value="44066" name="VKFLY_CMD_SET_RTL_CIRCLE_POS" hasLocation="true"
+        isDestination="false">
+        <description>Set return circle point.</description>
+        <param index="1" label="Radius">NAN means use default circle radius. Positive value means
+          circle
+          in clockwise.</param>
+        <param index="2" label="DoNow"> NAN means ignore. 1 means do goto rtl circle point right
+          now.
+        </param>
+        <param index="3" label=""> </param>
+        <param index="4" label=""> </param>
+        <param index="5" label="Latitude"> </param>
+        <param index="6" label="Longitude"> </param>
+        <param index="7" label="Alt"> </param>
+      </entry>
+
     </enum>
   </enums>
 
@@ -906,6 +943,25 @@
       <field type="uint32_t[4]" name="status">Status data from each ESC.</field>
     </message>
 
+    <message id="53009" name="VK_FIXEDWING_CONTROL_VALUE">
+      <description>Mosaic_h gps raw data</description>
+      <field type="uint32_t" name="timestamp" units="ms">Timestamp from system boot.</field>
+      <field type="float" name="roll_value" minValue="-1.0" maxValue="1.0">Roll control value,
+        negative value means roll left.</field>
+      <field type="float" name="pitch_value" minValue="-1.0" maxValue="1.0">Pitch control value,
+        negative value means pitch down.</field>
+      <field type="float" name="throttle_value" minValue="-1.0" maxValue="1.0">Throttle control
+        value, negative value means throttle off</field>
+      <field type="float" name="yaw_value" minValue="-1.0" maxValue="1.0">Throttle control
+        value, negative value means throttle off</field>
+    </message>
+
+    <message id="53010" name="VK_FIXEDWING_SERVO_SIGNAL">
+      <description>Mosaic_h gps raw data</description>
+      <field type="uint32_t" name="timestamp" units="ms">Timestamp from system boot.</field>
+      <field type="uint16_t[16]" name="servo_signal">Servo signal</field>
+    </message>
+
     <message id="53020" name="VK_PARACHUTE_STATUS">
       <description>parachute status</description>
       <field type="uint32_t" name="timestamp" units="ms">timestamp from system boot</field>
@@ -974,4 +1030,4 @@
 
   </messages>
 
-</mavlink>
+</mavlink>

+ 142 - 87
readme.md

@@ -8,7 +8,7 @@
 
 ## 1 自定义枚举类型
 
-### 1.1 机型布局 
+### 1.1 机型布局
   
 旋翼飞行器动力布局类型 VKFLY_AP_TYPE
 
@@ -39,6 +39,7 @@ typedef enum VKFLY_AP_TYPE
 ```
 
 垂起固定翼飞机构型布局 VKFLY_FIXEDWING_AP_TYPE
+
 ```c
 typedef enum VKFLY_FIXEDWING_AP_TYPE
 {
@@ -258,6 +259,8 @@ typedef enum VKFLY_RTL_REASON
     VKFLY_RTL_REASON_H2P_LOW=14, /* 氢能气压低返航 */
     VKFLY_RTL_REASON_ECU_FUEL_LOW=15, /* 发动机油量低返航 */
     VKFLY_RTL_REASON_ATTITUDE_FS=16, /* 姿态失控超限返航 | */
+    VKFLY_RTL_REASON_TRANS_TMO=17, /* 转换固定翼超时返航 | */
+    VKFLY_RTL_REASON_ASPD_LOW=18, /* 空速低返航 | */
 } VKFLY_RTL_REASON;
 ```
 
@@ -841,6 +844,40 @@ LOCAL 定位信息
 | temperature[4] | 温度 degC                                                                  |
 | status[4]      | 状态字 (不同品牌型号有不同的状态定义)                                      |
 
+### 2.26 固定翼控制量 VK_FIXEDWING_CONTROL_VALUE
+
+固定翼各通道控制量
+
+| 字段           | 说明                                                |
+| -------------- | --------------------------------------------------- |
+| timestamp      | 毫秒时间戳                                          |
+| roll_value     | 滚动控制值, -1.0~1.0, 负值左滚, 正值右滚            |
+| pitch_value    | 俯仰控制值, -1.0~1.0, 负值低头, 正值抬头            |
+| throttle_value | 油门控制值, -1.0~1.0, 负值灭车, 0~1对应 0~100% 油门 |
+| yaw_value      | 偏航控制值, -1.0~1.0, 负值左转, 正值右转            |
+
+### 2.27 固定翼舵面输出信号 VK_FIXEDWING_SERVO_SIGNAL
+
+最终输出到各舵面舵机的 pwm 信号脉宽, 单位 us
+
+| 字段             | 说明        |
+| ---------------- | ----------- |
+| timestamp        | 毫秒时间戳  |
+| servo_signal[16] | pwm信号脉宽 |
+
+舵面的序号如下:
+
+| 序号 | 说明                                            |
+| ---- | ----------------------------------------------- |
+| 0    | T尾V尾右副翼, 串联翼右前翼, 三角翼右翼          |
+| 1    | T尾V尾左副翼, 串联翼左前翼, 三角翼左翼          |
+| 2    | T尾右升降, V尾右尾, 串联翼右后翼, 三角翼右鸭翼  |
+| 3    | T尾左升降, V尾左尾, 串联翼左后翼 , 三角翼左鸭翼 |
+| 4    | T尾方向舵, 串联翼方向                           |
+| 5    | 油门舵机                                        |
+| 6    | 左襟翼                                          |
+| 7    | 右襟翼                                          |
+
 ## 3 参数设置
 
 飞控的参数修改、读取方法参考 [mavlink services parameter](https://mavlink.io/en/services/parameter.html). 使用16字节的 paramid 作为每各参数的唯一表示码.
@@ -1350,6 +1387,25 @@ param1~param5中,
 | param6 | 前后间距 单位m                 |
 | param7 | 上下间距 单位m                 |
 
+### 5.38 固定翼舵面检查 VKFLY_CMD_DO_FIXEDWING_ACTUATOR_CHECK
+
+| 参数   | 说明                                                                                             |
+| ------ | ------------------------------------------------------------------------------------------------ |
+| param1 | 舵面检查, NAN表示忽略. 0全回中. 1横滚回中, 2右滚, 3左滚. 4俯仰回中, 5抬头, 6低头. 7方向回中, 8左转,9右转. |
+| param2 | 油门检查, NAN表示忽略. -1表示灭车, 0~100 表示给定油门百分比, 0为怠速, 100为满油门                |
+
+### 5.39 固定翼返航盘旋点 VKFLY_CMD_SET_RTL_CIRCLE_POS
+
+设置固定翼返航盘旋点。返航时先执行飞往盘旋点, 到达后在盘旋点盘旋降高到返航高度, 再飞往起飞降落点降落.
+
+| 参数 | 说明|
+|-|-|
+| param1| 盘旋半径, NAN表示用飞控参数中的默认盘旋半径. 正数顺时针, 负数逆时针 |
+| param2| 上传后是否立刻执行返航, 0否, 1是|
+| param5| 纬度|
+| param6| 经度|
+| param7|高度(暂未使用)|
+
 ## 6 飞控 LOG 读取
 
 - LOG_REQUEST_LIST
@@ -1576,7 +1632,7 @@ VKins 系统的状态数据自定义消息, 主要用于一些自定状态的传
 | IMU_ATT_ROFF0   | IMU水平ROLL偏移                      | FLOAT  | 范围-180~180, 单位 deg <br>飞控通过水平校准自动捕获                                                                                                                                        |
 | IMU_ATT_POFF0   | IMU水平PITCH偏移                     | FLOAT  | 范围-180~180, 单位 deg <br>飞控通过水平校准自动捕获                                                                                                                                        |
 | IMU_ATT_YOFF0   | IMU水平YAW偏移                       | FLOAT  | 范围-180~180, 单位 deg <br>可用于设置飞控IMU安装朝向 <br>安装方向前0, 右90, 左-90, 后180                                                                                                   |
-| ASPD_OFFSET0    | 空速计零偏                           | FLOAT  | 范围 -5000~5000, 单位Pa                                                                                                                                                                    |
+| ASPD0_OFFSET1   | 空速计零偏                           | 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 <br>IMU安装离飞机中心X轴向偏差距离                                                                                                                                  |
@@ -1658,88 +1714,87 @@ VKins 系统的状态数据自定义消息, 主要用于一些自定状态的传
 
 ### 垂起版本参数
 
-| 参数名          | 参数                   | 类型   | 说明                                                                                                                                                                                       |
-| --------------- | ---------------------- | ------ | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------ |
-| 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. <br>bit0~3:1级低电压保护 <br>bit4~7:2级低电压保护 <br>bit8~11: 1级氢低压保护 <br>bit12~15: 2级氢低压保护 <br>bit16~19: 1级ecu油量低保护 <br>bit20~23: 2级ecu油量低保护 |
-| 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_VU_MAX       | 固定翼最大爬升率       | FLOAT  | 单位m/s, 范围1~10, 默认5                                                                                                                                                                   |
-| FW_VU_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_STALL   | 固定翼巡航空速         | 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_ROLL_KP      | 旋翼横滚角度比例系数   | UINT16 | 范围200~800                                                                                                                                                                                |
-| MC_PITCH_KP     | 旋翼横滚角度比例系数   | UINT16 | 范围200~800                                                                                                                                                                                |
-| MC_YAW_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                                                                                                                                                                          |
+| 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. <br>bit0~3:1级低电压保护 <br>bit4~7:2级低电压保护 <br>bit8~11: 1级氢低压保护 <br>bit12~15: 2级氢低压保护 <br>bit16~19: 1级ecu油量低保护 <br>bit20~23: 2级ecu油量低保护 |
+| 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_VU_MAX       | 固定翼最大爬升率         | FLOAT  | 单位m/s, 范围1~10, 默认5                                                                                                                                                                   |
+| FW_VU_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                                                                                                                                                                               |