Browse Source

增加组件版本信息等

Liu Yang 10 months ago
parent
commit
94964a8b83

+ 29 - 0
msg_definitions/VKFly.xml

@@ -63,6 +63,22 @@
       </entry>
     </enum>
 
+    <enum name="VKFLY_USER_COMP_ID">
+      <description>user define compnent id, 0-all 1-autopilot</description>
+      <entry value="3" name="VKFLY_COMP_ID_VKGPSA"></entry>
+      <entry value="4" name="VKFLY_COMP_ID_VKGPSB"></entry>
+      <entry value="5" name="VKFLY_COMP_ID_RFD_F"></entry>
+      <entry value="6" name="VKFLY_COMP_ID_RFD_R"></entry>
+      <entry value="7" name="VKFLY_COMP_ID_RFD_D"></entry>
+      <entry value="8" name="VKFLY_COMP_ID_RFD_360"></entry>
+      <entry value="10" name="VKFLY_COMP_ID_BAT0"></entry>
+      <entry value="11" name="VKFLY_COMP_ID_BAT1"></entry>
+      <entry value="12" name="VKFLY_COMP_ID_BAT2"></entry>
+      <entry value="13" name="VKFLY_COMP_ID_BAT3"></entry>
+      <entry value="14" name="VKFLY_COMP_ID_BAT4"></entry>
+      <entry value="15" name="VKFLY_COMP_ID_BAT5"></entry>
+    </enum>
+
     <enum name="VKFLY_FS_ACTION">
       <description>Failsafe action</description>
       <entry value="0" name="FAIL_SAFE_ACT_NONE">
@@ -475,6 +491,9 @@
       <entry value="1" name="VKFLY_MISSION_DONE_RETURN_TO_LAUNCH"></entry>
       <entry value="2" name="VKFLY_MISSION_DONE_LAND"></entry>
       <entry value="3" name="VKFLY_MISSION_DONE_RETURN_TO_RALLY"></entry>
+      <entry value="4" name="VKFLY_MISSION_DONE_RETURN_TO_LAUNCH_AB_WP"></entry>
+      <entry value="5" name="VKFLY_MISSION_DONE_RETURN_TO_LAUNCH_BA_WP"></entry>
+      <entry value="6" name="VKFLY_MISSION_DONE_THEN_REDO"></entry>
     </enum>
 
     <enum name="VKFLY_RTL_EXEC_MODE">
@@ -680,6 +699,16 @@
       <field type="uint8_t[10]" name="fw_ver">BMS firmware version string</field>
     </message>
 
+    <message id="53006" name="VK_COMP_VERSION">
+      <description>vkfly gps version</description>
+      <field type="uint16_t" name="comp_id" enum="VKFLY_USER_COMP_ID">component id</field>
+      <field type="uint8_t[16]" name="hw_ver">hardware version</field>
+      <field type="uint8_t[16]" name="fw_ver">firmware version</field>
+      <field type="uint8_t[16]" name="SN">SN number</field>
+      <field type="uint8_t[16]" name="manufactory">manufactory</field>
+      <field type="uint8_t[16]" name="model">model</field>
+      <field type="uint8_t[16]" name="priv_data">gnss configuration</field>
+    </message>
 
     <message id="53100" name="VK_FW_UPDATE_BEGIN">
       <description>VKFLY autopilot update firmware begin. This message send from GCS to autopilot. </description>

+ 143 - 67
readme.md

@@ -90,6 +90,7 @@
 - [MAVLINK_MSG_ID_HOME_POSITION](https://mavlink.io/en/messages/common.html#HOME_POSITION)
   
   home点. 飞控起飞时自动设置 home 点并发送本消息. 也可用 MAV_CMD_REQUEST_MESSAGE 进行读取.
+
   | 字段       | 说明                              |
   | ---------- | --------------------------------- |
   | latitude   | wgs84纬度 degE7                   |
@@ -110,6 +111,7 @@
   GPS_RAW_INT 为 RTK 板卡的原始定位数据, GPS2_RAW 为普通 GPS 的原定定位数据.
 
   GPS_RAW
+
   | 字段               | 说明                        |
   | ------------------ | --------------------------- |
   | time_usec          | 时间戳 us                   |
@@ -124,6 +126,7 @@
   | satellites_visible | 星数                        |
 
   GPS2_RAW
+
   | 字段               | 说明                                                                    |
   | ------------------ | ----------------------------------------------------------------------- |
   | time_usec          | 时间戳 us                                                               |
@@ -229,6 +232,7 @@
 
 - [MAVLINK_MSG_ID_CAMERA_TRACKING_GEO_STATUS](https://mavlink.io/en/messages/common.html#CAMERA_TRACKING_GEO_STATUS)
   相机目标跟踪信息
+
   | 字段            | 说明                         |
   | --------------- | ---------------------------- |
   | tracking_status | 0-未跟踪 1-在跟踪 2-跟踪异常 |
@@ -238,6 +242,7 @@
 
 - [MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS](https://mavlink.io/en/messages/common.html#GIMBAL_DEVICE_ATTITUDE_STATUS)
   载荷吊舱设备姿态信息
+
   | 字段  | 说明                                                    |
   | ----- | ------------------------------------------------------- |
   | flags | 参考链接中的说明, 一般用相对航向                        |
@@ -246,6 +251,7 @@
 - [MAVLINK_MSG_ID_DISTANCE_SENSOR](https://mavlink.io/en/messages/common.html#DISTANCE_SENSOR)
   测距仪距离数据
   目前该消息用于传输下向雷达测距. 当有雷达接入后 2hz 发送该消息
+
   | 字段             | 说明                    |
   | ---------------- | ----------------------- |
   | orientation      | ROTATION_PITCH_270 下向 |
@@ -254,6 +260,7 @@
 - [MAVLINK_MSG_ID_OBSTACLE_DISTANCE](https://mavlink.io/en/messages/common.html#OBSTACLE_DISTANCE)
   避障距离数据
   目前该消息用于传输水平面雷达. 当有雷达接入后 2hz 发送该消息
+
   | 字段          | 说明                                  |
   | ------------- | ------------------------------------- |
   | distances[72] | 水平各向障碍距离                      |
@@ -261,7 +268,7 @@
   | increment_f   | 各向角度间隔, 此项不为0时优先使用此项 |
   | angle_offset  | distances[0] 与正前向的夹角           |
   | frame         | MAV_FRAME_BODY_FRD, 机体坐标系        |
-  
+
 ### 参数设置
 
 参考 [mavlink services parameter](https://mavlink.io/en/services/parameter.html). 使用16字节的 paramid 作为每各参数的唯一表示码.
@@ -272,7 +279,7 @@
 
 - [MAVLINK_MSG_ID_PARAM_REQUEST_LIST](https://mavlink.io/en/messages/common.html#PARAM_REQUEST_LIST)
   
-   所有参数读取. 地面站向飞控发送, 读取所有飞控参数. 飞控收到后将所有参数依次按 MAVLINK_MSG_ID_PARAM_VALUE 消息回复.
+  所有参数读取. 地面站向飞控发送, 读取所有飞控参数. 飞控收到后将所有参数依次按 MAVLINK_MSG_ID_PARAM_VALUE 消息回复.
 
 - [MAVLINK_MSG_ID_PARAM_VALUE](https://mavlink.io/en/messages/common.html#PARAM_VALUE)
   
@@ -289,6 +296,7 @@
 目前对 common 标准协议的航线支持有限的几种 MAV_CMD 和 MAV_FRAME.
 
 支持的 MAV_FRAME 如下
+
 | FRAME                             | 说明                              |
 | --------------------------------- | --------------------------------- |
 | MAV_FRAME_GLOBAL_RELATIVE_ALT_INT | xy经纬度, z相对起飞点高度         |
@@ -304,6 +312,7 @@
 
 - [MAV_CMD_NAV_LAND](https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_LAND)
   降落点
+  param3 作为飞往该点速度使用m/s, NAN表示使用飞控默认巡航速度参数.
 
 #### 电子围栏 MAV_MISSION_TYPE_FENCE
 
@@ -349,6 +358,7 @@ mavlink common 标准消息集中主要由 MAVLINK_MSG_ID_COMMAND_INT 和 MAVLIN
 
   - [MAV_CMD_DO_SET_ROI_LOCATION](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_ROI_LOCATION)
     设置吊舱经纬度兴趣点聚焦
+
     | 参数   | 说明                                                           |
     | ------ | -------------------------------------------------------------- |
     | param1 | GIMBAL_ID (暂未使用)                                           |
@@ -384,8 +394,8 @@ mavlink common 标准消息集中主要由 MAVLINK_MSG_ID_COMMAND_INT 和 MAVLIN
 
     | 参数   | 说明                                                                                                          |
     | ------ | ------------------------------------------------------------------------------------------------------------- |
-    | param1 | 电机0~1对应最小到最大油门, 舵机-1~1对应最大负向~正向行程. 特殊约定 NAN 表示电机输出设置怠速                   |
-    | param2 | 检测时间 0~3s                                                                                                 |
+    | param1 | 电机0-1对应最小到最大油门, 舵机(-1,1)对应(最大负向,正向行程). 特殊约定 NAN 表示电机输出设置怠速               |
+    | param2 | 检测时间 0-3s                                                                                                 |
     | param3 |                                                                                                               |
     | param4 |                                                                                                               |
     | param5 | 检测通道, 参考[ACTUATOR_OUTPUT_FUNCTION](https://mavlink.io/en/messages/common.html#ACTUATOR_OUTPUT_FUNCTION) |
@@ -424,6 +434,7 @@ mavlink common 标准消息集中主要由 MAVLINK_MSG_ID_COMMAND_INT 和 MAVLIN
 
   - [MAV_CMD_NAV_RETURN_TO_LAUNCH](https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_RETURN_TO_LAUNCH)
     返航, 返回起飞点.
+    本指令会按直线返航执行, 需要按航线返航的话, 请参考 VKFLY_CMD_RETURN_TO_LAUCH
 
   - [MAV_CMD_NAV_LAND](https://mavlink.io/en/messages/common.html#MAV_CMD_NAV_LAND)
     降落
@@ -444,6 +455,7 @@ mavlink common 标准消息集中主要由 MAVLINK_MSG_ID_COMMAND_INT 和 MAVLIN
 
   - [MAV_CMD_DO_SET_ACTUATOR](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_ACTUATOR)
     设置舵机指令, 用于抛投
+
     | 参数        | 说明                                                                        |
     | ----------- | --------------------------------------------------------------------------- |
     | Actuator1~6 | 舵机位置 -1 表示关闭位置, 1 表示打开位置, 0表示中间位置, NAN 表示不进行动作 |
@@ -476,6 +488,7 @@ mavlink common 标准消息集中主要由 MAVLINK_MSG_ID_COMMAND_INT 和 MAVLIN
     设置俯仰低头20度, 航向右60度, param1=-20, param2=60
     设置俯仰低头20度, 航向不变, param1=-20, param2=NAN,
     param1\param2都为NAN, param3 或 param4 不为 NAN, 则表示吊舱俯仰或航向以给定速率运动
+
     | 参数   | 说明                                                                                        |
     | ------ | ------------------------------------------------------------------------------------------- |
     | param1 | 俯仰角, 抬头为正, -180~180deg, NAN 表示不改变当前俯仰                                       |
@@ -493,6 +506,7 @@ mavlink common 标准消息集中主要由 MAVLINK_MSG_ID_COMMAND_INT 和 MAVLIN
     停止连拍 param1=0, param2=NAN, param3=0
     停止连拍且当前单拍一张 param1=0, param2=NAN, param3=1
     触发定10m拍照 param1 = 10, param2=NAN, param3=0
+
     | 参数   | 说明                                                        |
     | ------ | ----------------------------------------------------------- |
     | param1 | 定距触发距离m, 0表示不定距离触发, NAN表示不改变当前触发状态 |
@@ -502,6 +516,7 @@ mavlink common 标准消息集中主要由 MAVLINK_MSG_ID_COMMAND_INT 和 MAVLIN
   - [MAV_CMD_DO_SET_CAM_TRIGG_INTERVAL](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_CAM_TRIGG_INTERVAL)
     拍照-定时指令
     若进行定时拍照, 则会关闭当前正进行的定距拍照.
+
     | 参数   | 说明                                   |
     | ------ | -------------------------------------- |
     | param1 | 定时触发周期ms, 0表示不进行定时触发    |
@@ -511,6 +526,7 @@ mavlink common 标准消息集中主要由 MAVLINK_MSG_ID_COMMAND_INT 和 MAVLIN
   - [MAV_CMD_DO_DIGICAM_CONTROL](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_DIGICAM_CONTROL)
     相机控制
     param1~param5中,
+
     | 参数   | 说明                                                              |
     | ------ | ----------------------------------------------------------------- |
     | param1 | 未用, 给0或NAN                                                    |
@@ -523,6 +539,7 @@ mavlink common 标准消息集中主要由 MAVLINK_MSG_ID_COMMAND_INT 和 MAVLIN
 
   - [MAV_CMD_SET_CAMERA_ZOOM](https://mavlink.io/en/messages/common.html#MAV_CMD_SET_CAMERA_ZOOM)
     变焦指令
+
     | 参数   | 说明                                                                                   |
     | ------ | -------------------------------------------------------------------------------------- |
     | param1 | 1-连续变焦 2-设置变焦值                                                                |
@@ -530,6 +547,7 @@ mavlink common 标准消息集中主要由 MAVLINK_MSG_ID_COMMAND_INT 和 MAVLIN
 
   - [MAV_CMD_CAMERA_TRACK_POINT](https://mavlink.io/en/messages/common.html#MAV_CMD_CAMERA_TRACK_POINT)
     指点跟踪
+
     | 参数   | 说明                                    |
     | ------ | --------------------------------------- |
     | param1 | px, 水平图像位置, 0~1, 0为最左, 1为最右 |
@@ -619,7 +637,7 @@ mavlink common 标准消息集中主要由 MAVLINK_MSG_ID_COMMAND_INT 和 MAVLIN
 
 ### 自定义枚举类型
 
-- VKFLY_AP_TYPE
+- **VKFLY_AP_TYPE**
   
   飞行器动力布局类型
 
@@ -646,8 +664,29 @@ mavlink common 标准消息集中主要由 MAVLINK_MSG_ID_COMMAND_INT 和 MAVLIN
     VKFLY_AP_TYPE_ENUM_END=163, /*  | */
   } VKFLY_AP_TYPE;
   ```
+- **VKFLY_USER_COMP_ID**
+  自定义设备 comp_id
 
-- VKFLY_FS_ACTION
+  ```c
+  typedef enum VKFLY_USER_COMP_ID
+  {
+    VKFLY_COMP_ID_VKGPSA=3, /* 普通 GPSA | */
+    VKFLY_COMP_ID_VKGPSB=4, /* 普通 GPSB | */
+    VKFLY_COMP_ID_RFD_F=5, /* 前雷达 | */
+    VKFLY_COMP_ID_RFD_R=6, /* 后雷达 | */
+    VKFLY_COMP_ID_RFD_D=7, /* 下雷达 | */
+    VKFLY_COMP_ID_RFD_360=8, /* 360雷达 | */
+    VKFLY_COMP_ID_BAT0=10, /* 电池0 | */
+    VKFLY_COMP_ID_BAT1=11, /* 电池1 | */
+    VKFLY_COMP_ID_BAT2=12, /* 电池2 | */
+    VKFLY_COMP_ID_BAT3=13, /* 电池3 | */
+    VKFLY_COMP_ID_BAT4=14, /* 电池4 | */
+    VKFLY_COMP_ID_BAT5=15, /* 电池5 | */
+    VKFLY_USER_COMP_ID_ENUM_END=16, /*  | */
+  }
+  ```
+
+- **VKFLY_FS_ACTION**
 
   失控保护动作类型
 
@@ -664,7 +703,7 @@ mavlink common 标准消息集中主要由 MAVLINK_MSG_ID_COMMAND_INT 和 MAVLIN
   } VKFLY_FS_ACTION;
   ```
 
-- VKFLY_SYS_STATUS_SENSOR_EXTEND
+- **VKFLY_SYS_STATUS_SENSOR_EXTEND**
   
   ```c
   typedef enum VKFLY_SYS_STATUS_SENSOR_EXTEND
@@ -676,7 +715,7 @@ mavlink common 标准消息集中主要由 MAVLINK_MSG_ID_COMMAND_INT 和 MAVLIN
   } VKFLY_SYS_STATUS_SENSOR_EXTEND;
   ```
 
-- VKFLY_SYS_ERROR1
+- **VKFLY_SYS_ERROR1**
   用于 SYS_STATUS 消息中对应的字节. 详细参考 VKFLY.xml
 
   ```c
@@ -693,7 +732,7 @@ mavlink common 标准消息集中主要由 MAVLINK_MSG_ID_COMMAND_INT 和 MAVLIN
   } VKFLY_SYS_ERROR1;
   ```
 
-- VKFLY_SYS_ERROR2
+- **VKFLY_SYS_ERROR2**
   用于 SYS_STATUS 消息中对应的字节. 详细参考 VKFLY.xml
 
   ```c
@@ -707,7 +746,7 @@ mavlink common 标准消息集中主要由 MAVLINK_MSG_ID_COMMAND_INT 和 MAVLIN
   } VKFLY_SYS_ERROR2;
   ```
 
-- VKFLY_SYS_ERROR3
+- **VKFLY_SYS_ERROR3**
 
   用于 SYS_STATUS 消息中对应的字节. 详细参考 VKFLY.xml
 
@@ -726,11 +765,11 @@ mavlink common 标准消息集中主要由 MAVLINK_MSG_ID_COMMAND_INT 和 MAVLIN
   } VKFLY_SYS_ERROR3;
   ```
 
-- VKFLY_SYS_ERROR4
+- **VKFLY_SYS_ERROR4**
 
   用于 SYS_STATUS 消息中对应的字节. 详细参考 VKFLY.xml (待定义)
 
-- VKFLY_CUSTOM_MODE
+- **VKFLY_CUSTOM_MODE**
 
   用于 HEARTBEAT 消息中对应的字节. 详细参考 VKFLY.xml
 
@@ -756,7 +795,7 @@ mavlink common 标准消息集中主要由 MAVLINK_MSG_ID_COMMAND_INT 和 MAVLIN
   } VKFLY_CUSTOM_MODE;
   ```
 
-- VKFLY_RTL_REASON
+- **VKFLY_RTL_REASON**
   返航原因
 
   ```c
@@ -779,7 +818,8 @@ mavlink common 标准消息集中主要由 MAVLINK_MSG_ID_COMMAND_INT 和 MAVLIN
     VKFLY_RTL_REASON_ENUM_END=14, /*  | */
   } VKFLY_RTL_REASON;
   ```
-- VKFLY_LOITER_REASON
+
+- **VKFLY_LOITER_REASON**
   悬停原因
   
   ```c
@@ -804,8 +844,7 @@ mavlink common 标准消息集中主要由 MAVLINK_MSG_ID_COMMAND_INT 和 MAVLIN
   #endif
   ```
 
-
-- VKFLY_VKINS_NAV_STATUS
+- **VKFLY_VKINS_NAV_STATUS**
 
   vkins 导航状态字 bitmap
 
@@ -820,7 +859,7 @@ mavlink common 标准消息集中主要由 MAVLINK_MSG_ID_COMMAND_INT 和 MAVLIN
   } VKFLY_VKINS_NAV_STATUS;
   ```
 
-- VKFLY_YAW_CTRL_MODE
+- **VKFLY_YAW_CTRL_MODE**
   
   航向控制模式
   
@@ -838,7 +877,7 @@ mavlink common 标准消息集中主要由 MAVLINK_MSG_ID_COMMAND_INT 和 MAVLIN
   } VKFLY_YAW_CTRL_MODE;
   ```
 
-- VKFLY_PHOTO_CTRL_MODE
+- **VKFLY_PHOTO_CTRL_MODE**
   
   自动拍照模式
 
@@ -855,7 +894,7 @@ mavlink common 标准消息集中主要由 MAVLINK_MSG_ID_COMMAND_INT 和 MAVLIN
   } VKFLY_PHOTO_CTRL_MODE;
   ```
 
-- VKFLY_DIGICAM_WP_ACT
+- **VKFLY_DIGICAM_WP_ACT**
   
   相机航点触发动作
 
@@ -870,7 +909,7 @@ mavlink common 标准消息集中主要由 MAVLINK_MSG_ID_COMMAND_INT 和 MAVLIN
   } VKFLY_DIGICAM_WP_ACT;
   ```
 
-- VKFLY_GIMBAL_WP_ACT
+- **VKFLY_GIMBAL_WP_ACT**
   
   云台航点触发动作
 
@@ -884,7 +923,7 @@ mavlink common 标准消息集中主要由 MAVLINK_MSG_ID_COMMAND_INT 和 MAVLIN
   } VKFLY_GIMBAL_WP_ACT;
   ```
 
-- VKFLY_THROW_CHAN_TYPE
+- **VKFLY_THROW_CHAN_TYPE**
   
   抛投通道 bitmap
 
@@ -911,8 +950,10 @@ mavlink common 标准消息集中主要由 MAVLINK_MSG_ID_COMMAND_INT 和 MAVLIN
     VKFLY_THROW_CHAN_TYPE_ENUM_END=65536, /*  | */
   } VKFLY_THROW_CHAN_TYPE;
   ```
-- VKFLY_MISSION_EXEC_MODE
+
+- **VKFLY_MISSION_EXEC_MODE**
   航线执行方式
+
   ```c
   typedef enum VKFLY_MISSION_EXEC_MODE
   {
@@ -925,8 +966,10 @@ mavlink common 标准消息集中主要由 MAVLINK_MSG_ID_COMMAND_INT 和 MAVLIN
     VKFLY_MISSION_EXEC_MODE_ENUM_END=6, /*  | */
   } VKFLY_MISSION_EXEC_MODE;
   ```
-- VKFLY_MISSION_DONE_ACT
+
+- **VKFLY_MISSION_DONE_ACT**
   航线任务完成后动作
+
   ```c
   typedef enum VKFLY_MISSION_DONE_ACT
   {
@@ -934,18 +977,22 @@ mavlink common 标准消息集中主要由 MAVLINK_MSG_ID_COMMAND_INT 和 MAVLIN
     VKFLY_MISSION_DONE_RETURN_TO_LAUNCH=1, /* 返航回 home  | */
     VKFLY_MISSION_DONE_LAND=2, /* 原地降落 | */
     VKFLY_MISSION_DONE_RETURN_TO_RALLY=3, /* 返回回备降点 | */
-    VKFLY_MISSION_DONE_ACT_ENUM_END=4, /*  | */
+    VKFLY_MISSION_DONE_RETURN_TO_LAUNCH_AB_WP=4, /* 返航回 home, 按顺序航线执行 | */ 
+    VKFLY_MISSION_DONE_RETURN_TO_LAUNCH_BA_WP=5, /* 返航回 home, 按逆序航线执行 | */
+    VKFLY_MISSION_DONE_THEN_REDO=6, /* 重新执行循环航线 | */ 
+    VKFLY_MISSION_DONE_ACT_ENUM_END=7, /*  | */
   } VKFLY_MISSION_DONE_ACT;
   ```
 
-- VKFLY_RTL_EXEC_MODE
+- **VKFLY_RTL_EXEC_MODE**
   返航执行方式
+
   ```c
   typedef enum VKFLY_RTL_EXEC_MODE
   {
-    VKFLY_RTL_EXEC_MODE_NORMAL=0, /*  | */
-    VKFLY_RTL_EXEC_MODE_BY_MISSION_SEQ=1, /*  | */
-    VKFLY_RTL_EXEC_MODE_BY_MISSION_SEQ_REVERSE=2, /*  | */
+    VKFLY_RTL_EXEC_MODE_NORMAL=0, /* 直线返航 | */
+    VKFLY_RTL_EXEC_MODE_BY_MISSION_SEQ=1, /* 沿航线正序返航 | */
+    VKFLY_RTL_EXEC_MODE_BY_MISSION_SEQ_REVERSE=2, /* 沿航线逆序返航 | */
     VKFLY_RTL_EXEC_MODE_ENUM_END=3, /*  | */
   } VKFLY_RTL_EXEC_MODE;
   ```
@@ -954,81 +1001,81 @@ mavlink common 标准消息集中主要由 MAVLINK_MSG_ID_COMMAND_INT 和 MAVLIN
 
 对标准 common 库的 MAV_CMD 类型做几个补充, 用于定义自定义航点.
 
-- VKFLY_CMD_NAV_WP
+- **VKFLY_CMD_NAV_WP**
 
   拍照航点.
   
   | 参数   | 说明                                                                                                                                                                                                                                                                                                         |
   | ------ | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------ |
-  | param1 | 该参数按 byte[4] 进行使用. <br>byte[0]~byte[1] s16, 悬停时间, 单位 s. 0 表示不进行悬停自动转弯. <br>byte[2]~byte[3] s16, 巡航速度, 单位 dm/s. 0 或负数表示使用默认巡航速度参数.                                                                                                                              |
-  | param2 | 该参数按 byte[4] 进行使用. <br>byte[0] u8, 达到该航点时是否单独触发一次相机动作. 参考 VKFLY_DIGICAM_WP_ACT <br>byte[1] u8, 为启动相机自动拍照控制模式. 参考 VKFLY_PHOTO_CTRL_MODE. <br>byte[2]~byte[3] u16, 为拍照模式间隔参数. 当拍照模式为定时时单位为s, 当拍照模式为定距拍照时单位为m. 范围 1~UINT16_MAX. |
-  | param3 | 该参数按 byte[4] 进行使用. <br>byte[0] u8, 吊舱云台控制动作. 参考 VKFLY_GIMBAL_WP_ACT <br>byte[1] s8, 给定俯仰角, 单位 deg, 下视负.<br>byte[2]~byte[3] s16, 给定吊舱相对航向角, 单位 deg, 右转为正.                                                                                                          |
-  | 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 等给定点点时, 表示叠加的航向偏移.                 |
+  | param1 | 该参数按 byte[4] 进行使用. <br>byte[0]-byte[1] s16, 悬停时间, 单位 s. 0 表示不进行悬停自动转弯. <br>byte[2]-byte[3] s16, 巡航速度, 单位 dm/s. 0 或负数表示使用默认巡航速度参数.                                                                                                                              |
+  | param2 | 该参数按 byte[4] 进行使用. <br>byte[0] u8, 达到该航点时是否单独触发一次相机动作. 参考 VKFLY_DIGICAM_WP_ACT <br>byte[1] u8, 为启动相机自动拍照控制模式. 参考 VKFLY_PHOTO_CTRL_MODE. <br>byte[2]-byte[3] u16, 为拍照模式间隔参数. 当拍照模式为定时时单位为s, 当拍照模式为定距拍照时单位为m. 范围 1-UINT16_MAX. |
+  | param3 | 该参数按 byte[4] 进行使用. <br>byte[0] u8, 吊舱云台控制动作. 参考 VKFLY_GIMBAL_WP_ACT <br>byte[1] s8, 给定俯仰角, 单位 deg, 下视负.<br>byte[2]-byte[3] s16, 给定吊舱相对航向角, 单位 deg, 右转为正.                                                                                                          |
+  | 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 等给定点点时, 表示叠加的航向偏移.                 |
   | param5 | 纬度 1e-7deg                                                                                                                                                                                                                                                                                                 |
   | param6 | 经度 1e-7deg                                                                                                                                                                                                                                                                                                 |
   | param7 | 高度 m                                                                                                                                                                                                                                                                                                       |
 
-- VKFLY_CMD_NAV_WP_THROW
+- **VKFLY_CMD_NAV_WP_THROW**
   抛投航点, 抛投完成后继续执行后续航点, 无后续航点则悬停
 
   | 参数   | 说明                                                                                                                                                                                                                                                                                                 |
   | ------ | ---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- |
-  | param1 | 该参数按 byte[4] 进行使用. <br>byte[0]~byte[1] s16, 悬停时间, 单位 s. 0 表示不进行悬停自动转弯. 悬停到时间后将执行抛投信号触发. <br>byte[2]~byte[3] s16, 巡航速度, 单位 dm/s. 0 或负数表示使用默认巡航速度参数.                                                                                      |
-  | param2 | 该参数按 byte[4] 进行使用. <br>byte[0]~byte[1] s16, 抛投对地高度, 单位 dm. 0或者负数表示在航点当前高度抛投. 若有有效的对地高度信息如雷达测距仪等, 则自动在航点进行下降到设定的对地高度再执行抛投. <br>byte[2]~byte[3] u16, 抛投通道. 每 bit 代表一个抛投执行通道, bitmap 参考 VKFLY_THROW_CHAN_TYPE. |
+  | param1 | 该参数按 byte[4] 进行使用. <br>byte[0]-byte[1] s16, 悬停时间, 单位 s. 0 表示不进行悬停自动转弯. 悬停到时间后将执行抛投信号触发. <br>byte[2]-byte[3] s16, 巡航速度, 单位 dm/s. 0 或负数表示使用默认巡航速度参数.                                                                                      |
+  | param2 | 该参数按 byte[4] 进行使用. <br>byte[0]-byte[1] s16, 抛投对地高度, 单位 dm. 0或者负数表示在航点当前高度抛投. 若有有效的对地高度信息如雷达测距仪等, 则自动在航点进行下降到设定的对地高度再执行抛投. <br>byte[2]-byte[3] u16, 抛投通道. 每 bit 代表一个抛投执行通道, bitmap 参考 VKFLY_THROW_CHAN_TYPE. |
   | param3 | 预留                                                                                                                                                                                                                                                                                                 |
-  | param4 | 该参数作为 byte[4] 类型使用. <br>byte[0] u8, 为航向模式参考 VKFLY_YAW_CTRL_MODE. <br>byte[1]预留. <br>byte[2]~byte[3] s16, 范围-180~180. 当航向模式为 VKFLY_YAW_TO_SETVAL 时表示给定的航向值, 单位deg. 当航向模式为指向 <br>HOME 或 NEXT_WP 或 INTEREST 等给定点点时, 表示叠加的航向偏移.            |
+  | param4 | 该参数作为 byte[4] 类型使用. <br>byte[0] u8, 为航向模式参考 VKFLY_YAW_CTRL_MODE. <br>byte[1]预留. <br>byte[2]-byte[3] s16, 范围-180-180. 当航向模式为 VKFLY_YAW_TO_SETVAL 时表示给定的航向值, 单位deg. 当航向模式为指向 <br>HOME 或 NEXT_WP 或 INTEREST 等给定点点时, 表示叠加的航向偏移.            |
   | param5 | 纬度 1e-7deg                                                                                                                                                                                                                                                                                         |
   | param6 | 经度 1e-7deg                                                                                                                                                                                                                                                                                         |
   | param7 | 高度 m                                                                                                                                                                                                                                                                                               |
 
-- VKFLY_CMD_NAV_WP_THROW_THEN_INVERSE_MISSION
+- **VKFLY_CMD_NAV_WP_THROW_THEN_INVERSE_MISSION**
   抛投航点, 抛投完成后反向执行前续航点, 到达第一个航点后按参数执行悬停或降落
 
   | 参数   | 说明                                                                                                                                                                                                                                                                                                 |
   | ------ | ---------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- |
-  | param1 | 该参数按 byte[4] 进行使用. <br>byte[0]~byte[1] s16, 悬停时间, 单位 s. 0 表示不进行悬停自动转弯. 悬停到时间后将执行抛投信号触发. <br>byte[2]~byte[3] s16, 巡航速度, 单位 dm/s. 0 或负数表示使用默认巡航速度参数.                                                                                      |
-  | param2 | 该参数按 byte[4] 进行使用. <br>byte[0]~byte[1] s16, 抛投对地高度, 单位 dm. 0或者负数表示在航点当前高度抛投. 若有有效的对地高度信息如雷达测距仪等, 则自动在航点进行下降到设定的对地高度再执行抛投. <br>byte[2]~byte[3] u16, 抛投通道. 每 bit 代表一个抛投执行通道, bitmap 参考 VKFLY_THROW_CHAN_TYPE. |
+  | param1 | 该参数按 byte[4] 进行使用. <br>byte[0]-byte[1] s16, 悬停时间, 单位 s. 0 表示不进行悬停自动转弯. 悬停到时间后将执行抛投信号触发. <br>byte[2]-byte[3] s16, 巡航速度, 单位 dm/s. 0 或负数表示使用默认巡航速度参数.                                                                                      |
+  | param2 | 该参数按 byte[4] 进行使用. <br>byte[0]-byte[1] s16, 抛投对地高度, 单位 dm. 0或者负数表示在航点当前高度抛投. 若有有效的对地高度信息如雷达测距仪等, 则自动在航点进行下降到设定的对地高度再执行抛投. <br>byte[2]-byte[3] u16, 抛投通道. 每 bit 代表一个抛投执行通道, bitmap 参考 VKFLY_THROW_CHAN_TYPE. |
   | param3 | 改参数按 byte[4] 进行使用.                                                                                                                                                                                                                                                                           |
-  | param4 | 该参数作为 byte[4] 类型使用. <br>byte[0] u8, 为航向模式参考 VKFLY_YAW_CTRL_MODE. <br>byte[1]预留. <br>byte[2]~byte[3] s16, 范围-180~180. 当航向模式为 VKFLY_YAW_TO_SETVAL 时表示给定的航向值, 单位deg. 当航向模式为指向 <br>HOME 或 NEXT_WP 或 INTEREST 等给定点点时, 表示叠加的航向偏移.            |
+  | param4 | 该参数作为 byte[4] 类型使用. <br>byte[0] u8, 为航向模式参考 VKFLY_YAW_CTRL_MODE. <br>byte[1]预留. <br>byte[2]-byte[3] s16, 范围-180-180. 当航向模式为 VKFLY_YAW_TO_SETVAL 时表示给定的航向值, 单位deg. 当航向模式为指向 <br>HOME 或 NEXT_WP 或 INTEREST 等给定点点时, 表示叠加的航向偏移.            |
   | param5 | 纬度 1e-7deg                                                                                                                                                                                                                                                                                         |
   | param6 | 经度 1e-7deg                                                                                                                                                                                                                                                                                         |
   | param7 | 高度 m                                                                                                                                                                                                                                                                                               |
 
-
-- VKFLY_CMD_NAV_WP_ORBIT_DO_PHOTO
+- **VKFLY_CMD_NAV_WP_ORBIT_DO_PHOTO**
 
   环绕航点
+
   | 参数   | 说明                                                                                                                                                                                                                                                                                                                |
   | ------ | ------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------- |
-  | param1 | 该参数按 byte[4] 进行使用. <br>byte[0]~byte[1] s16, 环绕半径, 单位 dm. 正数表示顺时针方向环绕, 负数表示逆时针方向环绕. <br>byte[2]~byte[3] s16, 巡航速度. 单位 dm/s. 0或负数表示使用默认的巡航速度设置参数.                                                                                                         |
-  | param2 | 拍照控制. 该参数按 byte[4] 进行使用. <br>byte[0] u8, 达到该航点时是否单独触发一次相机动作. 参考 VKFLY_DIGICAM_WP_ACT. <br>byte[1] u8, 为启动相机自动拍照控制模式. 参考 VKFLY_PHOTO_CTRL_MODE. <br>byte[2]~byte[3] u16, 为拍照模式参数. 当拍照模式为定时时单位为s, 当拍照模式为定距拍照时单位为m. 范围 1~UINT16_MAX. |
-  | param3 | 该参数按 byte[4] 进行使用. <br>byte[0]~byte[1] u16, 为环绕圈数, 单位 0.1 圈. <br>byte[2]~byte[3] u16, 为环绕速度, 单位 dm/s.                                                                                                                                                                                        |
-  | param4 | 该参数作为 byte[4] 类型使用. <br>byte[0] u8, 为航向模式参考 VKFLY_YAW_CTRL_MODE. <br>byte[1]预留. <br>byte[2]~byte[3] s16, 范围-180~180. 当航向模式为 VKFLY_YAW_TO_SETVAL 时表示给定的航向值, 单位deg. 当航向模式为指向 <br>HOME 或 NEXT_WP 或 INTEREST 等给定点点时, 表示叠加的航向偏移.                           |
+  | param1 | 该参数按 byte[4] 进行使用. <br>byte[0]-byte[1] s16, 环绕半径, 单位 dm. 正数表示顺时针方向环绕, 负数表示逆时针方向环绕. <br>byte[2]-byte[3] s16, 巡航速度. 单位 dm/s. 0或负数表示使用默认的巡航速度设置参数.                                                                                                         |
+  | param2 | 拍照控制. 该参数按 byte[4] 进行使用. <br>byte[0] u8, 达到该航点时是否单独触发一次相机动作. 参考 VKFLY_DIGICAM_WP_ACT. <br>byte[1] u8, 为启动相机自动拍照控制模式. 参考 VKFLY_PHOTO_CTRL_MODE. <br>byte[2]-byte[3] u16, 为拍照模式参数. 当拍照模式为定时时单位为s, 当拍照模式为定距拍照时单位为m. 范围 1-UINT16_MAX. |
+  | param3 | 该参数按 byte[4] 进行使用. <br>byte[0]-byte[1] u16, 为环绕圈数, 单位 0.1 圈. <br>byte[2]-byte[3] u16, 为环绕速度, 单位 dm/s.                                                                                                                                                                                        |
+  | param4 | 该参数作为 byte[4] 类型使用. <br>byte[0] u8, 为航向模式参考 VKFLY_YAW_CTRL_MODE. <br>byte[1]预留. <br>byte[2]-byte[3] s16, 范围-180-180. 当航向模式为 VKFLY_YAW_TO_SETVAL 时表示给定的航向值, 单位deg. 当航向模式为指向 <br>HOME 或 NEXT_WP 或 INTEREST 等给定点点时, 表示叠加的航向偏移.                           |
   | param5 | 纬度 1e-7deg                                                                                                                                                                                                                                                                                                        |
   | param6 | 经度 1e-7deg                                                                                                                                                                                                                                                                                                        |
   | param7 | 高度 m                                                                                                                                                                                                                                                                                                              |
 
 其它的自定义 command
 
-- VKFLY_CMD_ESC_CONFIG
+- **VKFLY_CMD_ESC_CONFIG**
   电调设置
 
 | 参数   | 说明                                  |
 | ------ | ------------------------------------- |
-| param1 | 设置电调编号, 1~16, NAN表示忽略该指令 |
+| param1 | 设置电调编号, 1-16, NAN表示忽略该指令 |
 
-- VKFLY_CMD_DO_REPOSITION_THAN_THROW
-  指点后抛投, 本指令仅支持 COMMAND_INT 
+- **VKFLY_CMD_DO_REPOSITION_THAN_THROW**
+  指点后抛投, 本指令仅支持 COMMAND_INT
 
   | 参数   | 说明                                                                       |
   | ------ | -------------------------------------------------------------------------- |
-  | param1 | 抛投舵机编号, 0~0xFFFF, 从低到高每bit对应一舵机, 参考VKFLY_THROW_CHAN_TYPE |
+  | param1 | 抛投舵机编号, 0-0xFFFF, 从低到高每bit对应一舵机, 参考VKFLY_THROW_CHAN_TYPE |
   | param2 | 抛投后动作, NAN或0为悬停, 1为返航                                          |
   | x      | 纬度, 1e-7deg                                                              |
   | y      | 经度, 1e-7deg                                                              |
   | z      | 高度, m                                                                    |
 
-- VKFLY_CMD_DO_REPOSITION_THAN_LAND
+- **VKFLY_CMD_DO_REPOSITION_THAN_LAND**
   指点后降落, 本指令仅支持 COMMAND_INT
 
   | 参数   | 说明                                                                   |
@@ -1040,7 +1087,7 @@ mavlink common 标准消息集中主要由 MAVLINK_MSG_ID_COMMAND_INT 和 MAVLIN
   | y      | 精度,1e-7deg                                                           |
   | z      | 高度, m. 飞往该点过程中的相对高度                                      |
 
-- VKFLY_CMD_MISSION_START 
+- **VKFLY_CMD_MISSION_START**
   开始航线
 
   | 参数   | 说明                                                                            |
@@ -1049,20 +1096,37 @@ mavlink common 标准消息集中主要由 MAVLINK_MSG_ID_COMMAND_INT 和 MAVLIN
   | param2 | 任务执行方式, 参考 VKFLY_MISSION_EXEC_MODE                                      |
   | param3 | 任务完成后动作, 参考 VKFLY_MISSION_DONE_ACT                                     |
 
-- VKFLY_CMD_RETURN_TO_LAUCH
+- **VKFLY_CMD_RETURN_TO_LAUCH**
   返航
 
+  - **直线返航** 从指令开始位置直线返回到降落点
+  - **逆序返航** 从指令开始位置逆序返回到降落点
+    - 若指定了起始航点, 则从指定起始航点开始执行
+    - 若未指定起始航点, 未执行过航线
+      - 地面站指令返航, 则从最后一航点开始执行
+      - 自动触发返航, 则直线返航
+    - 若未指定起始航点, 执行过航线
+      - 若前序航线顺序执行, 航线目标航点为第一个航点, 则直线返航
+      - 若前序航线顺序执行, 航线目标航点不为第一个航点, 则从航线目标航点-1开始执行
+      - 若前序航线逆序执行, 则从航线目标航点开始执行。
+  - **顺序返航** 从指令开始位置顺序返回到降落点
+    - 若指定了起始航点, 则从指定起始航点开始执行。
+    - 若未指定起始航点, 未执行过航线,
+      - 地面站指令返航, 则从第一个航点开始执行
+      - 自主触发返航, 则直线返航
+    - 若未指定起始航点, 执行过航线
+      - 若前序航线顺序执行, 则从航线目标航点开始执行
+      - 若前序航线逆序执行, 航线目标航点为最后一个航点, 则直线返航
+      - 若前序航线逆序执行, 航线目标航点不为最后一个航点, 则从航线目标航点+1开始执行
+
   | 参数   | 说明                                                                                         |
   | ------ | -------------------------------------------------------------------------------------------- |
   | param1 | 起始航点序号, 0-UINT16_MAX. 当返航执行方式为正序或逆序航线返航时参数有效. NAN 表示忽略该参数 |
-  | param2 | 返航执行, 参考 VKFLY_RTL_EXEC_MODE                                                        |
-
-
-
+  | param2 | 返航执行, 参考 VKFLY_RTL_EXEC_MODE                                                           |
 
 ### 自定义消息
 
-- MAVLINK_VKINS_STATUS
+- **MAVLINK_VKINS_STATUS**
   
   VKins 系统的状态数据自定义消息, 主要用于一些自定状态的传输和排故.
 
@@ -1082,7 +1146,8 @@ mavlink common 标准消息集中主要由 MAVLINK_MSG_ID_COMMAND_INT 和 MAVLIN
   | baro_alt        | vkins解算使用的原始气压高m                                                                |
   | raw_gps_alt     | vkins解算使用的原始海拔高度m                                                              |
 
-- MAVLINK_VKFMU_STATUS
+- **MAVLINK_VKFMU_STATUS**
+
   | 字段          | 说明                               |
   | ------------- | ---------------------------------- |
   | time_boot_ms  | 系统本地时间戳ms                   |
@@ -1094,9 +1159,10 @@ mavlink common 标准消息集中主要由 MAVLINK_MSG_ID_COMMAND_INT 和 MAVLIN
   | flight_time   | 飞行时间,s                         |
   | dist_t_tar    | 目标距离, cm                       |
 
-- MAVLINK_VK_BMS_STATUS
+- **MAVLINK_VK_BMS_STATUS**
   智能电池状态数据
   当检测到智能电池数据接入, 飞控自动周期向地面站发送此消息
+
   | 字段         | 说明                         |
   | ------------ | ---------------------------- |
   | time_boot_ms | 系统本地时间戳ms             |
@@ -1104,13 +1170,14 @@ mavlink common 标准消息集中主要由 MAVLINK_MSG_ID_COMMAND_INT 和 MAVLIN
   | current      | 电流 cA(0.01A), 负数表示充电 |
   | temperature  | 温度 1度                     |
   | cap_percent  | 电量 1%                      |
-  | bat_id       | 电池编号, 0~5                |
+  | bat_id       | 电池编号, 0-5                |
   | err_code     | 故障码, 0为无故障            |
   | cell_num     | 电芯数                       |
   | cell_volt    | 电芯电压 mV                  |
 
-- MAVLINK_VK_BMS_INFO
-  智能电池 info 数据, 本数据可以通过 MAV_CMD_REQUEST 进行读取, param1 是电池的 bat_id.
+- **MAVLINK_VK_BMS_INFO**
+  智能电池 info 数据, 本数据可以通过 MAV_CMD_REQUEST_MESSAGE 进行读取, param2 是电池的 bat_id.
+
   | 字段         | 说明             |
   | ------------ | ---------------- |
   | time_boot_ms | 系统本地时间戳ms |
@@ -1119,7 +1186,17 @@ mavlink common 标准消息集中主要由 MAVLINK_MSG_ID_COMMAND_INT 和 MAVLIN
   | sn_id        | 序列号           |
   | hw_ver       | 硬件号           |
   | fw_ver       | 软件号           |
- 
+
+- **MAVLINK_VK_COMP_VERSION**
+  设备版本信息, 本消息可以通过 MAV_CMD_REQUEST_MESSAGE 进行读取, param2 是设备的 comp_id. comp_id 为 0 时, 飞控将回复多个消息逐个返回所有可获取设备的版本信息
+  | 字段        | 说明                                                 |
+  | ----------- | ---------------------------------------------------- |
+  | comp_id     | 组件编号 0-全部, 1-飞控, 其它参考 VKFLY_USER_COMP_ID |
+  | hw_ver      | 硬件版本号                                           |
+  | fw_ver      | 软件版本号                                           |
+  | SN          | SN号                                                 |
+  | manufactory | 软件版本号字符串                                     |
+  | model       | 设备型号                                             |
 
 ## 飞控参数说明
 
@@ -1132,7 +1209,6 @@ mavlink common 标准消息集中主要由 MAVLINK_MSG_ID_COMMAND_INT 和 MAVLIN
 | 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-上电到下电                            |
-| LOOP_MISSION    | 航线循环开关                         | UINT8  | 范围0~1 <br>0-不循环 <br>1-循环(暂未启用)                                                      |
 | BOOT_MODE       | 系统启动模式                         | UINT8  | 范围0~1, 0-正常启动, 1-U盘模式(用于导入导出数据文件)                                           |
 | HW_SN_NUM       | 硬件SN号                             | UINT32 | 范围0~UINT32_MAX                                                                               |
 | AIRFRAME        | 飞机布局类型                         | UINT16 | 范围0~UINT16_MAX, 区分不同的飞机布局类型, 参考 enum AP_TYPE                                    |

File diff suppressed because it is too large
+ 1 - 1
v2.0/VKFly/VKFly.h


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

@@ -6,7 +6,7 @@
 #ifndef MAVLINK_H
 #define MAVLINK_H
 
-#define MAVLINK_PRIMARY_XML_HASH -8759080805051931211
+#define MAVLINK_PRIMARY_XML_HASH 8768893837624279133
 
 #ifndef MAVLINK_STX
 #define MAVLINK_STX 253

+ 423 - 0
v2.0/VKFly/mavlink_msg_vk_comp_version.h

@@ -0,0 +1,423 @@
+#pragma once
+// MESSAGE VK_COMP_VERSION PACKING
+
+#define MAVLINK_MSG_ID_VK_COMP_VERSION 53006
+
+
+typedef struct __mavlink_vk_comp_version_t {
+ uint16_t comp_id; /*<  component id*/
+ uint8_t hw_ver[16]; /*<  hardware version*/
+ uint8_t fw_ver[16]; /*<  firmware version*/
+ uint8_t SN[16]; /*<  SN number*/
+ uint8_t manufactory[16]; /*<  manufactory*/
+ uint8_t model[16]; /*<  model*/
+ uint8_t priv_data[16]; /*<  gnss configuration*/
+} mavlink_vk_comp_version_t;
+
+#define MAVLINK_MSG_ID_VK_COMP_VERSION_LEN 98
+#define MAVLINK_MSG_ID_VK_COMP_VERSION_MIN_LEN 98
+#define MAVLINK_MSG_ID_53006_LEN 98
+#define MAVLINK_MSG_ID_53006_MIN_LEN 98
+
+#define MAVLINK_MSG_ID_VK_COMP_VERSION_CRC 227
+#define MAVLINK_MSG_ID_53006_CRC 227
+
+#define MAVLINK_MSG_VK_COMP_VERSION_FIELD_HW_VER_LEN 16
+#define MAVLINK_MSG_VK_COMP_VERSION_FIELD_FW_VER_LEN 16
+#define MAVLINK_MSG_VK_COMP_VERSION_FIELD_SN_LEN 16
+#define MAVLINK_MSG_VK_COMP_VERSION_FIELD_MANUFACTORY_LEN 16
+#define MAVLINK_MSG_VK_COMP_VERSION_FIELD_MODEL_LEN 16
+#define MAVLINK_MSG_VK_COMP_VERSION_FIELD_PRIV_DATA_LEN 16
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_VK_COMP_VERSION { \
+    53006, \
+    "VK_COMP_VERSION", \
+    7, \
+    {  { "comp_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_vk_comp_version_t, comp_id) }, \
+         { "hw_ver", NULL, MAVLINK_TYPE_UINT8_T, 16, 2, offsetof(mavlink_vk_comp_version_t, hw_ver) }, \
+         { "fw_ver", NULL, MAVLINK_TYPE_UINT8_T, 16, 18, offsetof(mavlink_vk_comp_version_t, fw_ver) }, \
+         { "SN", NULL, MAVLINK_TYPE_UINT8_T, 16, 34, offsetof(mavlink_vk_comp_version_t, SN) }, \
+         { "manufactory", NULL, MAVLINK_TYPE_UINT8_T, 16, 50, offsetof(mavlink_vk_comp_version_t, manufactory) }, \
+         { "model", NULL, MAVLINK_TYPE_UINT8_T, 16, 66, offsetof(mavlink_vk_comp_version_t, model) }, \
+         { "priv_data", NULL, MAVLINK_TYPE_UINT8_T, 16, 82, offsetof(mavlink_vk_comp_version_t, priv_data) }, \
+         } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_VK_COMP_VERSION { \
+    "VK_COMP_VERSION", \
+    7, \
+    {  { "comp_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_vk_comp_version_t, comp_id) }, \
+         { "hw_ver", NULL, MAVLINK_TYPE_UINT8_T, 16, 2, offsetof(mavlink_vk_comp_version_t, hw_ver) }, \
+         { "fw_ver", NULL, MAVLINK_TYPE_UINT8_T, 16, 18, offsetof(mavlink_vk_comp_version_t, fw_ver) }, \
+         { "SN", NULL, MAVLINK_TYPE_UINT8_T, 16, 34, offsetof(mavlink_vk_comp_version_t, SN) }, \
+         { "manufactory", NULL, MAVLINK_TYPE_UINT8_T, 16, 50, offsetof(mavlink_vk_comp_version_t, manufactory) }, \
+         { "model", NULL, MAVLINK_TYPE_UINT8_T, 16, 66, offsetof(mavlink_vk_comp_version_t, model) }, \
+         { "priv_data", NULL, MAVLINK_TYPE_UINT8_T, 16, 82, offsetof(mavlink_vk_comp_version_t, priv_data) }, \
+         } \
+}
+#endif
+
+/**
+ * @brief Pack a vk_comp_version message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param comp_id  component id
+ * @param hw_ver  hardware version
+ * @param fw_ver  firmware version
+ * @param SN  SN number
+ * @param manufactory  manufactory
+ * @param model  model
+ * @param priv_data  gnss configuration
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_vk_comp_version_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+                               uint16_t comp_id, const uint8_t *hw_ver, const uint8_t *fw_ver, const uint8_t *SN, const uint8_t *manufactory, const uint8_t *model, const uint8_t *priv_data)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_VK_COMP_VERSION_LEN];
+    _mav_put_uint16_t(buf, 0, comp_id);
+    _mav_put_uint8_t_array(buf, 2, hw_ver, 16);
+    _mav_put_uint8_t_array(buf, 18, fw_ver, 16);
+    _mav_put_uint8_t_array(buf, 34, SN, 16);
+    _mav_put_uint8_t_array(buf, 50, manufactory, 16);
+    _mav_put_uint8_t_array(buf, 66, model, 16);
+    _mav_put_uint8_t_array(buf, 82, priv_data, 16);
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VK_COMP_VERSION_LEN);
+#else
+    mavlink_vk_comp_version_t packet;
+    packet.comp_id = comp_id;
+    mav_array_memcpy(packet.hw_ver, hw_ver, sizeof(uint8_t)*16);
+    mav_array_memcpy(packet.fw_ver, fw_ver, sizeof(uint8_t)*16);
+    mav_array_memcpy(packet.SN, SN, sizeof(uint8_t)*16);
+    mav_array_memcpy(packet.manufactory, manufactory, sizeof(uint8_t)*16);
+    mav_array_memcpy(packet.model, model, sizeof(uint8_t)*16);
+    mav_array_memcpy(packet.priv_data, priv_data, sizeof(uint8_t)*16);
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VK_COMP_VERSION_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_VK_COMP_VERSION;
+    return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_VK_COMP_VERSION_MIN_LEN, MAVLINK_MSG_ID_VK_COMP_VERSION_LEN, MAVLINK_MSG_ID_VK_COMP_VERSION_CRC);
+}
+
+/**
+ * @brief Pack a vk_comp_version message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param comp_id  component id
+ * @param hw_ver  hardware version
+ * @param fw_ver  firmware version
+ * @param SN  SN number
+ * @param manufactory  manufactory
+ * @param model  model
+ * @param priv_data  gnss configuration
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_vk_comp_version_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+                               uint16_t comp_id, const uint8_t *hw_ver, const uint8_t *fw_ver, const uint8_t *SN, const uint8_t *manufactory, const uint8_t *model, const uint8_t *priv_data)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_VK_COMP_VERSION_LEN];
+    _mav_put_uint16_t(buf, 0, comp_id);
+    _mav_put_uint8_t_array(buf, 2, hw_ver, 16);
+    _mav_put_uint8_t_array(buf, 18, fw_ver, 16);
+    _mav_put_uint8_t_array(buf, 34, SN, 16);
+    _mav_put_uint8_t_array(buf, 50, manufactory, 16);
+    _mav_put_uint8_t_array(buf, 66, model, 16);
+    _mav_put_uint8_t_array(buf, 82, priv_data, 16);
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VK_COMP_VERSION_LEN);
+#else
+    mavlink_vk_comp_version_t packet;
+    packet.comp_id = comp_id;
+    mav_array_memcpy(packet.hw_ver, hw_ver, sizeof(uint8_t)*16);
+    mav_array_memcpy(packet.fw_ver, fw_ver, sizeof(uint8_t)*16);
+    mav_array_memcpy(packet.SN, SN, sizeof(uint8_t)*16);
+    mav_array_memcpy(packet.manufactory, manufactory, sizeof(uint8_t)*16);
+    mav_array_memcpy(packet.model, model, sizeof(uint8_t)*16);
+    mav_array_memcpy(packet.priv_data, priv_data, sizeof(uint8_t)*16);
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VK_COMP_VERSION_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_VK_COMP_VERSION;
+#if MAVLINK_CRC_EXTRA
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_VK_COMP_VERSION_MIN_LEN, MAVLINK_MSG_ID_VK_COMP_VERSION_LEN, MAVLINK_MSG_ID_VK_COMP_VERSION_CRC);
+#else
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_VK_COMP_VERSION_MIN_LEN, MAVLINK_MSG_ID_VK_COMP_VERSION_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a vk_comp_version message on a channel
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param chan The MAVLink channel this message will be sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param comp_id  component id
+ * @param hw_ver  hardware version
+ * @param fw_ver  firmware version
+ * @param SN  SN number
+ * @param manufactory  manufactory
+ * @param model  model
+ * @param priv_data  gnss configuration
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_vk_comp_version_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+                               mavlink_message_t* msg,
+                                   uint16_t comp_id,const uint8_t *hw_ver,const uint8_t *fw_ver,const uint8_t *SN,const uint8_t *manufactory,const uint8_t *model,const uint8_t *priv_data)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_VK_COMP_VERSION_LEN];
+    _mav_put_uint16_t(buf, 0, comp_id);
+    _mav_put_uint8_t_array(buf, 2, hw_ver, 16);
+    _mav_put_uint8_t_array(buf, 18, fw_ver, 16);
+    _mav_put_uint8_t_array(buf, 34, SN, 16);
+    _mav_put_uint8_t_array(buf, 50, manufactory, 16);
+    _mav_put_uint8_t_array(buf, 66, model, 16);
+    _mav_put_uint8_t_array(buf, 82, priv_data, 16);
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VK_COMP_VERSION_LEN);
+#else
+    mavlink_vk_comp_version_t packet;
+    packet.comp_id = comp_id;
+    mav_array_memcpy(packet.hw_ver, hw_ver, sizeof(uint8_t)*16);
+    mav_array_memcpy(packet.fw_ver, fw_ver, sizeof(uint8_t)*16);
+    mav_array_memcpy(packet.SN, SN, sizeof(uint8_t)*16);
+    mav_array_memcpy(packet.manufactory, manufactory, sizeof(uint8_t)*16);
+    mav_array_memcpy(packet.model, model, sizeof(uint8_t)*16);
+    mav_array_memcpy(packet.priv_data, priv_data, sizeof(uint8_t)*16);
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VK_COMP_VERSION_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_VK_COMP_VERSION;
+    return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_VK_COMP_VERSION_MIN_LEN, MAVLINK_MSG_ID_VK_COMP_VERSION_LEN, MAVLINK_MSG_ID_VK_COMP_VERSION_CRC);
+}
+
+/**
+ * @brief Encode a vk_comp_version struct
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param msg The MAVLink message to compress the data into
+ * @param vk_comp_version C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_vk_comp_version_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_vk_comp_version_t* vk_comp_version)
+{
+    return mavlink_msg_vk_comp_version_pack(system_id, component_id, msg, vk_comp_version->comp_id, vk_comp_version->hw_ver, vk_comp_version->fw_ver, vk_comp_version->SN, vk_comp_version->manufactory, vk_comp_version->model, vk_comp_version->priv_data);
+}
+
+/**
+ * @brief Encode a vk_comp_version struct on a channel
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param chan The MAVLink channel this message will be sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param vk_comp_version C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_vk_comp_version_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_vk_comp_version_t* vk_comp_version)
+{
+    return mavlink_msg_vk_comp_version_pack_chan(system_id, component_id, chan, msg, vk_comp_version->comp_id, vk_comp_version->hw_ver, vk_comp_version->fw_ver, vk_comp_version->SN, vk_comp_version->manufactory, vk_comp_version->model, vk_comp_version->priv_data);
+}
+
+/**
+ * @brief Encode a vk_comp_version struct with provided status structure
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ * @param vk_comp_version C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_vk_comp_version_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_vk_comp_version_t* vk_comp_version)
+{
+    return mavlink_msg_vk_comp_version_pack_status(system_id, component_id, _status, msg,  vk_comp_version->comp_id, vk_comp_version->hw_ver, vk_comp_version->fw_ver, vk_comp_version->SN, vk_comp_version->manufactory, vk_comp_version->model, vk_comp_version->priv_data);
+}
+
+/**
+ * @brief Send a vk_comp_version message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param comp_id  component id
+ * @param hw_ver  hardware version
+ * @param fw_ver  firmware version
+ * @param SN  SN number
+ * @param manufactory  manufactory
+ * @param model  model
+ * @param priv_data  gnss configuration
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_vk_comp_version_send(mavlink_channel_t chan, uint16_t comp_id, const uint8_t *hw_ver, const uint8_t *fw_ver, const uint8_t *SN, const uint8_t *manufactory, const uint8_t *model, const uint8_t *priv_data)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_VK_COMP_VERSION_LEN];
+    _mav_put_uint16_t(buf, 0, comp_id);
+    _mav_put_uint8_t_array(buf, 2, hw_ver, 16);
+    _mav_put_uint8_t_array(buf, 18, fw_ver, 16);
+    _mav_put_uint8_t_array(buf, 34, SN, 16);
+    _mav_put_uint8_t_array(buf, 50, manufactory, 16);
+    _mav_put_uint8_t_array(buf, 66, model, 16);
+    _mav_put_uint8_t_array(buf, 82, priv_data, 16);
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VK_COMP_VERSION, buf, MAVLINK_MSG_ID_VK_COMP_VERSION_MIN_LEN, MAVLINK_MSG_ID_VK_COMP_VERSION_LEN, MAVLINK_MSG_ID_VK_COMP_VERSION_CRC);
+#else
+    mavlink_vk_comp_version_t packet;
+    packet.comp_id = comp_id;
+    mav_array_memcpy(packet.hw_ver, hw_ver, sizeof(uint8_t)*16);
+    mav_array_memcpy(packet.fw_ver, fw_ver, sizeof(uint8_t)*16);
+    mav_array_memcpy(packet.SN, SN, sizeof(uint8_t)*16);
+    mav_array_memcpy(packet.manufactory, manufactory, sizeof(uint8_t)*16);
+    mav_array_memcpy(packet.model, model, sizeof(uint8_t)*16);
+    mav_array_memcpy(packet.priv_data, priv_data, sizeof(uint8_t)*16);
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VK_COMP_VERSION, (const char *)&packet, MAVLINK_MSG_ID_VK_COMP_VERSION_MIN_LEN, MAVLINK_MSG_ID_VK_COMP_VERSION_LEN, MAVLINK_MSG_ID_VK_COMP_VERSION_CRC);
+#endif
+}
+
+/**
+ * @brief Send a vk_comp_version message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_vk_comp_version_send_struct(mavlink_channel_t chan, const mavlink_vk_comp_version_t* vk_comp_version)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    mavlink_msg_vk_comp_version_send(chan, vk_comp_version->comp_id, vk_comp_version->hw_ver, vk_comp_version->fw_ver, vk_comp_version->SN, vk_comp_version->manufactory, vk_comp_version->model, vk_comp_version->priv_data);
+#else
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VK_COMP_VERSION, (const char *)vk_comp_version, MAVLINK_MSG_ID_VK_COMP_VERSION_MIN_LEN, MAVLINK_MSG_ID_VK_COMP_VERSION_LEN, MAVLINK_MSG_ID_VK_COMP_VERSION_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_VK_COMP_VERSION_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+  This variant of _send() can be used to save stack space by re-using
+  memory from the receive buffer.  The caller provides a
+  mavlink_message_t which is the size of a full mavlink message. This
+  is usually the receive buffer for the channel, and allows a reply to an
+  incoming message with minimum stack space usage.
+ */
+static inline void mavlink_msg_vk_comp_version_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint16_t comp_id, const uint8_t *hw_ver, const uint8_t *fw_ver, const uint8_t *SN, const uint8_t *manufactory, const uint8_t *model, const uint8_t *priv_data)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char *buf = (char *)msgbuf;
+    _mav_put_uint16_t(buf, 0, comp_id);
+    _mav_put_uint8_t_array(buf, 2, hw_ver, 16);
+    _mav_put_uint8_t_array(buf, 18, fw_ver, 16);
+    _mav_put_uint8_t_array(buf, 34, SN, 16);
+    _mav_put_uint8_t_array(buf, 50, manufactory, 16);
+    _mav_put_uint8_t_array(buf, 66, model, 16);
+    _mav_put_uint8_t_array(buf, 82, priv_data, 16);
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VK_COMP_VERSION, buf, MAVLINK_MSG_ID_VK_COMP_VERSION_MIN_LEN, MAVLINK_MSG_ID_VK_COMP_VERSION_LEN, MAVLINK_MSG_ID_VK_COMP_VERSION_CRC);
+#else
+    mavlink_vk_comp_version_t *packet = (mavlink_vk_comp_version_t *)msgbuf;
+    packet->comp_id = comp_id;
+    mav_array_memcpy(packet->hw_ver, hw_ver, sizeof(uint8_t)*16);
+    mav_array_memcpy(packet->fw_ver, fw_ver, sizeof(uint8_t)*16);
+    mav_array_memcpy(packet->SN, SN, sizeof(uint8_t)*16);
+    mav_array_memcpy(packet->manufactory, manufactory, sizeof(uint8_t)*16);
+    mav_array_memcpy(packet->model, model, sizeof(uint8_t)*16);
+    mav_array_memcpy(packet->priv_data, priv_data, sizeof(uint8_t)*16);
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VK_COMP_VERSION, (const char *)packet, MAVLINK_MSG_ID_VK_COMP_VERSION_MIN_LEN, MAVLINK_MSG_ID_VK_COMP_VERSION_LEN, MAVLINK_MSG_ID_VK_COMP_VERSION_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE VK_COMP_VERSION UNPACKING
+
+
+/**
+ * @brief Get field comp_id from vk_comp_version message
+ *
+ * @return  component id
+ */
+static inline uint16_t mavlink_msg_vk_comp_version_get_comp_id(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint16_t(msg,  0);
+}
+
+/**
+ * @brief Get field hw_ver from vk_comp_version message
+ *
+ * @return  hardware version
+ */
+static inline uint16_t mavlink_msg_vk_comp_version_get_hw_ver(const mavlink_message_t* msg, uint8_t *hw_ver)
+{
+    return _MAV_RETURN_uint8_t_array(msg, hw_ver, 16,  2);
+}
+
+/**
+ * @brief Get field fw_ver from vk_comp_version message
+ *
+ * @return  firmware version
+ */
+static inline uint16_t mavlink_msg_vk_comp_version_get_fw_ver(const mavlink_message_t* msg, uint8_t *fw_ver)
+{
+    return _MAV_RETURN_uint8_t_array(msg, fw_ver, 16,  18);
+}
+
+/**
+ * @brief Get field SN from vk_comp_version message
+ *
+ * @return  SN number
+ */
+static inline uint16_t mavlink_msg_vk_comp_version_get_SN(const mavlink_message_t* msg, uint8_t *SN)
+{
+    return _MAV_RETURN_uint8_t_array(msg, SN, 16,  34);
+}
+
+/**
+ * @brief Get field manufactory from vk_comp_version message
+ *
+ * @return  manufactory
+ */
+static inline uint16_t mavlink_msg_vk_comp_version_get_manufactory(const mavlink_message_t* msg, uint8_t *manufactory)
+{
+    return _MAV_RETURN_uint8_t_array(msg, manufactory, 16,  50);
+}
+
+/**
+ * @brief Get field model from vk_comp_version message
+ *
+ * @return  model
+ */
+static inline uint16_t mavlink_msg_vk_comp_version_get_model(const mavlink_message_t* msg, uint8_t *model)
+{
+    return _MAV_RETURN_uint8_t_array(msg, model, 16,  66);
+}
+
+/**
+ * @brief Get field priv_data from vk_comp_version message
+ *
+ * @return  gnss configuration
+ */
+static inline uint16_t mavlink_msg_vk_comp_version_get_priv_data(const mavlink_message_t* msg, uint8_t *priv_data)
+{
+    return _MAV_RETURN_uint8_t_array(msg, priv_data, 16,  82);
+}
+
+/**
+ * @brief Decode a vk_comp_version message into a struct
+ *
+ * @param msg The message to decode
+ * @param vk_comp_version C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_vk_comp_version_decode(const mavlink_message_t* msg, mavlink_vk_comp_version_t* vk_comp_version)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    vk_comp_version->comp_id = mavlink_msg_vk_comp_version_get_comp_id(msg);
+    mavlink_msg_vk_comp_version_get_hw_ver(msg, vk_comp_version->hw_ver);
+    mavlink_msg_vk_comp_version_get_fw_ver(msg, vk_comp_version->fw_ver);
+    mavlink_msg_vk_comp_version_get_SN(msg, vk_comp_version->SN);
+    mavlink_msg_vk_comp_version_get_manufactory(msg, vk_comp_version->manufactory);
+    mavlink_msg_vk_comp_version_get_model(msg, vk_comp_version->model);
+    mavlink_msg_vk_comp_version_get_priv_data(msg, vk_comp_version->priv_data);
+#else
+        uint8_t len = msg->len < MAVLINK_MSG_ID_VK_COMP_VERSION_LEN? msg->len : MAVLINK_MSG_ID_VK_COMP_VERSION_LEN;
+        memset(vk_comp_version, 0, MAVLINK_MSG_ID_VK_COMP_VERSION_LEN);
+    memcpy(vk_comp_version, _MAV_PAYLOAD(msg), len);
+#endif
+}

+ 66 - 0
v2.0/VKFly/testsuite.h

@@ -426,6 +426,71 @@ static void mavlink_test_vk_digi_esc_status(uint8_t system_id, uint8_t component
 #endif
 }
 
+static void mavlink_test_vk_comp_version(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
+{
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+    mavlink_status_t *status = mavlink_get_channel_status(MAVLINK_COMM_0);
+        if ((status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_VK_COMP_VERSION >= 256) {
+            return;
+        }
+#endif
+    mavlink_message_t msg;
+        uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+        uint16_t i;
+    mavlink_vk_comp_version_t packet_in = {
+        17235,{ 139, 140, 141, 142, 143, 144, 145, 146, 147, 148, 149, 150, 151, 152, 153, 154 },{ 187, 188, 189, 190, 191, 192, 193, 194, 195, 196, 197, 198, 199, 200, 201, 202 },{ 235, 236, 237, 238, 239, 240, 241, 242, 243, 244, 245, 246, 247, 248, 249, 250 },{ 27, 28, 29, 30, 31, 32, 33, 34, 35, 36, 37, 38, 39, 40, 41, 42 },{ 75, 76, 77, 78, 79, 80, 81, 82, 83, 84, 85, 86, 87, 88, 89, 90 },{ 123, 124, 125, 126, 127, 128, 129, 130, 131, 132, 133, 134, 135, 136, 137, 138 }
+    };
+    mavlink_vk_comp_version_t packet1, packet2;
+        memset(&packet1, 0, sizeof(packet1));
+        packet1.comp_id = packet_in.comp_id;
+        
+        mav_array_memcpy(packet1.hw_ver, packet_in.hw_ver, sizeof(uint8_t)*16);
+        mav_array_memcpy(packet1.fw_ver, packet_in.fw_ver, sizeof(uint8_t)*16);
+        mav_array_memcpy(packet1.SN, packet_in.SN, sizeof(uint8_t)*16);
+        mav_array_memcpy(packet1.manufactory, packet_in.manufactory, sizeof(uint8_t)*16);
+        mav_array_memcpy(packet1.model, packet_in.model, sizeof(uint8_t)*16);
+        mav_array_memcpy(packet1.priv_data, packet_in.priv_data, sizeof(uint8_t)*16);
+        
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+        if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+           // cope with extensions
+           memset(MAVLINK_MSG_ID_VK_COMP_VERSION_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_VK_COMP_VERSION_MIN_LEN);
+        }
+#endif
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_vk_comp_version_encode(system_id, component_id, &msg, &packet1);
+    mavlink_msg_vk_comp_version_decode(&msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_vk_comp_version_pack(system_id, component_id, &msg , packet1.comp_id , packet1.hw_ver , packet1.fw_ver , packet1.SN , packet1.manufactory , packet1.model , packet1.priv_data );
+    mavlink_msg_vk_comp_version_decode(&msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_vk_comp_version_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.comp_id , packet1.hw_ver , packet1.fw_ver , packet1.SN , packet1.manufactory , packet1.model , packet1.priv_data );
+    mavlink_msg_vk_comp_version_decode(&msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+        memset(&packet2, 0, sizeof(packet2));
+        mavlink_msg_to_send_buffer(buffer, &msg);
+        for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
+            comm_send_ch(MAVLINK_COMM_0, buffer[i]);
+        }
+    mavlink_msg_vk_comp_version_decode(last_msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+        
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_vk_comp_version_send(MAVLINK_COMM_1 , packet1.comp_id , packet1.hw_ver , packet1.fw_ver , packet1.SN , packet1.manufactory , packet1.model , packet1.priv_data );
+    mavlink_msg_vk_comp_version_decode(last_msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
+    MAVLINK_ASSERT(mavlink_get_message_info_by_name("VK_COMP_VERSION") != NULL);
+    MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_VK_COMP_VERSION) != NULL);
+#endif
+}
+
 static void mavlink_test_vk_fw_update_begin(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
 {
 #ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
@@ -735,6 +800,7 @@ static void mavlink_test_VKFly(uint8_t system_id, uint8_t component_id, mavlink_
     mavlink_test_vk_bms_status(system_id, component_id, last_msg);
     mavlink_test_vk_bms_info(system_id, component_id, last_msg);
     mavlink_test_vk_digi_esc_status(system_id, component_id, last_msg);
+    mavlink_test_vk_comp_version(system_id, component_id, last_msg);
     mavlink_test_vk_fw_update_begin(system_id, component_id, last_msg);
     mavlink_test_vk_fw_update_ack(system_id, component_id, last_msg);
     mavlink_test_vk_fw_update_data_request(system_id, component_id, last_msg);

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

@@ -7,7 +7,7 @@
 #ifndef MAVLINK_VERSION_H
 #define MAVLINK_VERSION_H
 
-#define MAVLINK_BUILD_DATE "Tue Sep 03 2024"
+#define MAVLINK_BUILD_DATE "Tue Sep 10 2024"
 #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 2119984325654329320
+#define MAVLINK_COMMON_XML_HASH 8093961037565932851
 
 #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 2119984325654329320
+#define MAVLINK_PRIMARY_XML_HASH 8093961037565932851
 
 #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 "Tue Sep 03 2024"
+#define MAVLINK_BUILD_DATE "Tue Sep 10 2024"
 #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 -7192635655080444157
+#define MAVLINK_PRIMARY_XML_HASH -1903176616712080717
 
 #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 -7192635655080444157
+#define MAVLINK_MINIMAL_XML_HASH -1903176616712080717
 
 #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 "Tue Sep 03 2024"
+#define MAVLINK_BUILD_DATE "Tue Sep 10 2024"
 #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 928119734354877572
+#define MAVLINK_PRIMARY_XML_HASH 1640796470349844457
 
 #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 928119734354877572
+#define MAVLINK_STANDARD_XML_HASH 1640796470349844457
 
 #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 "Tue Sep 03 2024"
+#define MAVLINK_BUILD_DATE "Tue Sep 10 2024"
 #define MAVLINK_WIRE_PROTOCOL_VERSION "2.0"
 #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 22
  

Some files were not shown because too many files changed in this diff