Browse Source

增加一些协议 .h 文件

Liu Yang 9 months ago
parent
commit
6fcf999982

+ 70 - 42
readme.md

@@ -52,7 +52,7 @@
 
 ### 飞控通用遥测数据消息
 
-- [MAVLINK_MSG_ID_HEARTBEAT](https://mavlink.io/en/messages/common.html#HEARTBEAT)
+- [HEARTBEAT](https://mavlink.io/en/messages/common.html#HEARTBEAT)
 
   飞控和地面站定周期 1hz 向外发送, 用于判别是否失联. 包含基础的设备信息.
 
@@ -64,7 +64,7 @@
   | system_status   | 参考common.xml标准定义                                               |
   | mavlink_version | 当前仅支持v2.0, 值为200                                              |
 
-- [MAVLINK_MSG_ID_SYS_STATUS](https://mavlink.io/en/messages/common.html#SYS_STATUS)
+- [SYS_STATUS](https://mavlink.io/en/messages/common.html#SYS_STATUS)
   
   飞控定周期向外发送, 默认 2hz. 包含传感器\电池\故障码等一些重要状态信息.
 
@@ -87,7 +87,7 @@
   | onboard_control_sensors_enable_extended  | 参考 VKFLY_SYS_STATUS_SENSOR_EXTEND                                                 |
   | onboard_control_sensors_health_extended  | 参考 VKFLY_SYS_STATUS_SENSOR_EXTEND                                                 |
 
-- [MAVLINK_MSG_ID_HOME_POSITION](https://mavlink.io/en/messages/common.html#HOME_POSITION)
+- [HOME_POSITION](https://mavlink.io/en/messages/common.html#HOME_POSITION)
   
   home点. 飞控起飞时自动设置 home 点并发送本消息. 也可用 MAV_CMD_REQUEST_MESSAGE 进行读取.
 
@@ -105,7 +105,7 @@
   | approach_z | 进近矢量  (暂未使用)              |
   | time_usec  | 时间戳us                          |
 
-- [MAVLINK_MSG_ID_GPS_RAW_INT](https://mavlink.io/en/messages/common.html#GPS_RAW_INT) | [MAVLINK_MSG_ID_GPS2_RAW]((https://mavlink.io/en/messages/common.html#GPS2))
+- [GPS_RAW_INT](https://mavlink.io/en/messages/common.html#GPS_RAW_INT) | [GPS2_RAW]((https://mavlink.io/en/messages/common.html#GPS2))
 
   飞控定周期向外发送, 默认 1hz. 包含未经融合的原始普通 gps wgs84 坐标定位等信息.
   GPS_RAW_INT 为 RTK 板卡的原始定位数据, GPS2_RAW 为普通 GPS 的原定定位数据.
@@ -147,7 +147,7 @@
   | vel_acc            | 速度精度 mm                                                             |
   | hdg_acc            | 航向精度 degE5                                                          |
 
-- [MAVLINK_MSG_ID_GLOBAL_POSITION_INT](https://mavlink.io/en/messages/common.html#GLOBAL_POSITION_INT)
+- [GLOBAL_POSITION_INT](https://mavlink.io/en/messages/common.html#GLOBAL_POSITION_INT)
   
   融合后的 GLOBAL 定位信息
   飞控定周期向外发送, 默认 5hz. 包含融合后的 wgs84 坐标定位信息.
@@ -164,40 +164,40 @@
   | vz           | 地向速度 cm/s, 下为正               |
   | hdg          | 航向角 0.01deg 0.01deg, 0~359.99deg |
 
-- [MAVLINK_MSG_ID_ATTITUDE](https://mavlink.io/en/messages/common.html#ATTITUDE)
+- [ATTITUDE](https://mavlink.io/en/messages/common.html#ATTITUDE)
 
   飞控定周期向外发送, 默认 5hz. 包含飞行器的姿态\角速度等信息.
   欧拉角定义以 FRD-NED 系右手符号. (航向顺时针正, 俯仰抬头正, 横滚右滚正).
 
-- [MAVLINK_MSG_ID_LOCAL_POSITION_NED](https://mavlink.io/en/messages/common.html#LOCAL_POSITION_NED)
+- [LOCAL_POSITION_NED](https://mavlink.io/en/messages/common.html#LOCAL_POSITION_NED)
   
   LOCAL 定位信息
   飞控定周期向外发送, 默认 5hz. 包含以解算原点为原点的北东地坐标下的相对位置和速度信息.
 
-- [MAVLINK_MSG_ID_SERVO_OUTPUT_RAW](https://mavlink.io/en/messages/common.html#SERVO_OUTPUT_RAW)
+- [SERVO_OUTPUT_RAW](https://mavlink.io/en/messages/common.html#SERVO_OUTPUT_RAW)
   
   电机输出信息
   飞控顶周期向外发送, 默认 5hz. 包含各通道电机控制PWM信号的值.
 
-- [MAVLINK_MSG_ID_ESC_STATUS]
+- [ESC_STATUS]
   电调数据信息
   数字接口电调反馈的状态信息, 包括转速, 电压, 电流. 有电调接入后飞控以默认 2hz 发送给地面站.
 
-- [MAVLINK_MSG_ID_VFR_HUD](https://mavlink.io/en/messages/common.html#VFR_HUDhttps://mavlink.io/en/messages/common.html#VFR_HUD)
+- [VFR_HUD](https://mavlink.io/en/messages/common.html#VFR_HUDhttps://mavlink.io/en/messages/common.html#VFR_HUD)
   
   仪表HUD信息
   飞控定周期向外发送, 默认 5hz. 包含飞行器的高度\速度\油门等信息.
 
-- [MAVLINK_MSG_ID_MISSION_CURRENT](https://mavlink.io/en/messages/common.html#MISSION_CURRENT)
+- [MISSION_CURRENT](https://mavlink.io/en/messages/common.html#MISSION_CURRENT)
   当前任务点消息
   飞控定期下传, 默认 1hz. 包含当前任务航点序号等信息. 注意 seq 字段从 0 开始.
 
-- [MAVLINK_MSG_ID_RC_CHANNELS](https://mavlink.io/en/messages/common.html#RC_CHANNELS)
+- [RC_CHANNELS](https://mavlink.io/en/messages/common.html#RC_CHANNELS)
   
   遥控器通道信息
   飞控定周期向外发送, 默认 5hz. 包含飞行器接受到的遥控器输入通道(校准后)的数据.
 
-- [MAVLINK_MSG_ID_STATUSTEXT](https://mavlink.io/en/messages/common.html#STATUSTEXT)
+- [STATUSTEXT](https://mavlink.io/en/messages/common.html#STATUSTEXT)
   系统状态消息
   用于打印显示飞控向地面站传输的字符串. 包括 DEBUG\INFO\WARING\ERROR 等用途.
   对于 WARING 和更高等级的信息, 地面站应在操作界面给与用户醒目提示.
@@ -210,7 +210,7 @@
   | id        | 拼接超过50字符的长消息用, 暂未使用 |
   | chunk_seq | 拼接超过50字符的长消息用, 暂未使用 |
 
-- [MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED](https://mavlink.io/en/messages/common.html#CAMERA_IMAGE_CAPTURED)
+- [CAMERA_IMAGE_CAPTURED](https://mavlink.io/en/messages/common.html#CAMERA_IMAGE_CAPTURED)
   拍照pos消息
   每次拍照都进行下发, 可用  MAV_CMD_REQUEST_MESSAGE 进行读取.
   使用  MAV_CMD_REQUEST_MESSAGE 读取时, param2 非负数值表示要读取的第一个照片 index, -1 表示读取所有照片. param3 0表示仅
@@ -230,7 +230,7 @@
   | capture_result | 拍照结果 0失败 1成功                |
   | file_url       | 照片数据地址(网址, 飞控没有填0)     |
 
-- [MAVLINK_MSG_ID_CAMERA_TRACKING_GEO_STATUS](https://mavlink.io/en/messages/common.html#CAMERA_TRACKING_GEO_STATUS)
+- [CAMERA_TRACKING_GEO_STATUS](https://mavlink.io/en/messages/common.html#CAMERA_TRACKING_GEO_STATUS)
   相机目标跟踪信息
 
   | 字段            | 说明                         |
@@ -240,7 +240,7 @@
   | lon             | 目标经度                     |
   | alt             | 目标海拔高度                 |
 
-- [MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS](https://mavlink.io/en/messages/common.html#GIMBAL_DEVICE_ATTITUDE_STATUS)
+- [GIMBAL_DEVICE_ATTITUDE_STATUS](https://mavlink.io/en/messages/common.html#GIMBAL_DEVICE_ATTITUDE_STATUS)
   载荷吊舱设备姿态信息
 
   | 字段  | 说明                                                    |
@@ -248,7 +248,7 @@
   | flags | 参考链接中的说明, 一般用相对航向                        |
   | q     | 姿态四元数, 可用 mavlink_quaternion_to_euler 转为欧拉角 |
 
-- [MAVLINK_MSG_ID_DISTANCE_SENSOR](https://mavlink.io/en/messages/common.html#DISTANCE_SENSOR)
+- [DISTANCE_SENSOR](https://mavlink.io/en/messages/common.html#DISTANCE_SENSOR)
   测距仪距离数据
   目前该消息用于传输下向雷达测距. 当有雷达接入后 2hz 发送该消息
 
@@ -257,7 +257,7 @@
   | orientation      | ROTATION_PITCH_270 下向 |
   | current_distance | 测距距离 cm             |
 
-- [MAVLINK_MSG_ID_OBSTACLE_DISTANCE](https://mavlink.io/en/messages/common.html#OBSTACLE_DISTANCE)
+- [OBSTACLE_DISTANCE](https://mavlink.io/en/messages/common.html#OBSTACLE_DISTANCE)
   避障距离数据
   目前该消息用于传输水平面雷达. 当有雷达接入后 2hz 发送该消息
 
@@ -273,19 +273,19 @@
 
 参考 [mavlink services parameter](https://mavlink.io/en/services/parameter.html). 使用16字节的 paramid 作为每各参数的唯一表示码.
 
-- [MAVLINK_MSG_ID_PARAM_REQUEST_READ](https://mavlink.io/en/messages/common.html#PARAM_REQUEST_READ)
+- [PARAM_REQUEST_READ](https://mavlink.io/en/messages/common.html#PARAM_REQUEST_READ)
 
-  单个参数读取. 地面站向飞控发送, 读取某个指定参数. 飞控收到后回复 MAVLINK_MSG_ID_PARAM_VALUE 消息.
+  单个参数读取. 地面站向飞控发送, 读取某个指定参数. 飞控收到后回复 PARAM_VALUE 消息.
 
-- [MAVLINK_MSG_ID_PARAM_REQUEST_LIST](https://mavlink.io/en/messages/common.html#PARAM_REQUEST_LIST)
+- [PARAM_REQUEST_LIST](https://mavlink.io/en/messages/common.html#PARAM_REQUEST_LIST)
   
-  所有参数读取. 地面站向飞控发送, 读取所有飞控参数. 飞控收到后将所有参数依次按 MAVLINK_MSG_ID_PARAM_VALUE 消息回复.
+  所有参数读取. 地面站向飞控发送, 读取所有飞控参数. 飞控收到后将所有参数依次按 PARAM_VALUE 消息回复.
 
-- [MAVLINK_MSG_ID_PARAM_VALUE](https://mavlink.io/en/messages/common.html#PARAM_VALUE)
+- [PARAM_VALUE](https://mavlink.io/en/messages/common.html#PARAM_VALUE)
   
   参数值消息. 飞控向地面站回复读取对应的参数值信息.
 
-- [MAVLINK_MSG_ID_PARAM_SET](https://mavlink.io/en/messages/common.html#PARAM_SET)
+- [PARAM_SET](https://mavlink.io/en/messages/common.html#PARAM_SET)
 
   参数设置消息. 地面站向飞控发送参数设置消息.
 
@@ -342,9 +342,9 @@
 
 ### 地面站指令消息
 
-mavlink common 标准消息集中主要由 MAVLINK_MSG_ID_COMMAND_INT 和 MAVLINK_MSG_ID_COMMAND_LONG 两条.
+mavlink common 标准消息集中主要由 COMMAND_INT 和 COMMAND_LONG 两条.
 
-- [MAVLINK_MSG_ID_COMMAND_INT](https://mavlink.io/en/messages/common.html#COMMAND_INT)
+- [COMMAND_INT](https://mavlink.io/en/messages/common.html#COMMAND_INT)
 
   飞控接受以下几条 MAV_CMD 类型的指令
 
@@ -370,7 +370,7 @@ mavlink common 标准消息集中主要由 MAVLINK_MSG_ID_COMMAND_INT 和 MAVLIN
   - [MAV_CMD_DO_SET_ROI_NONE](https://mavlink.io/en/messages/common.html#MAV_CMD_DO_SET_ROI_NONE)
     取消吊舱兴趣点聚焦
 
-- [MAVLINK_MSG_ID_COMMAND_LONG](https://mavlink.io/en/messages/common.html#COMMAND_LONG)
+- [COMMAND_LONG](https://mavlink.io/en/messages/common.html#COMMAND_LONG)
 
   飞控接受以下几条 MAV_CMD 类型的指令
 
@@ -579,16 +579,16 @@ mavlink common 标准消息集中主要由 MAVLINK_MSG_ID_COMMAND_INT 和 MAVLIN
 
 ### 飞控 LOG 读取
 
-- MAVLINK_MSG_ID_LOG_REQUEST_LIST
-- MAVLINK_MSG_ID_LOG_ENTRY
-- MAVLINK_MSG_ID_LOG_REQUEST_DATA
-- MAVLINK_MSG_ID_LOG_DATA
-- MAVLINK_MSG_ID_LOG_ERASE
-- MAVLINK_MSG_ID_LOG_REQUEST_END
+- LOG_REQUEST_LIST
+- LOG_ENTRY
+- LOG_REQUEST_DATA
+- LOG_DATA
+- LOG_ERASE
+- LOG_REQUEST_END
 
 ### 飞控固件下载
 
-- MAVLINK_MSG_ID_VK_FW_UPDATE_BEGIN
+- VK_FW_UPDATE_BEGIN
 
   地面站向飞控发送此消息, 开始传输固件文件.
 
@@ -598,7 +598,7 @@ mavlink common 标准消息集中主要由 MAVLINK_MSG_ID_COMMAND_INT 和 MAVLIN
   | target_comp   | 目标compid, 飞控compid 为1                  |
   | file_size     | 文件字节大小字节数                          |
 
-- MAVLINK_MSG_ID_VK_FW_UPDATE_DATA_REQUEST
+- VK_FW_UPDATE_DATA_REQUEST
 
   飞控向地面站发送此消息, 请求文件数据内容.
   注意飞控请求count可能大于一包所能发送数量, 比如一次请求4096字节.
@@ -609,7 +609,7 @@ mavlink common 标准消息集中主要由 MAVLINK_MSG_ID_COMMAND_INT 和 MAVLIN
   | offset | 字节偏移 |
   | count  | 字节数   |
 
-- MAVLINK_MSG_ID_VK_FW_UPDATE_DATA
+- VK_FW_UPDATE_DATA
 
   地面站向飞控发送文件数据包.
 
@@ -619,7 +619,7 @@ mavlink common 标准消息集中主要由 MAVLINK_MSG_ID_COMMAND_INT 和 MAVLIN
   | count  | 本包字节数, 范围0~128 |
   | data   | 数据内容              |
 
-- MAVLINK_MSG_ID_VK_FW_UPDATE_ACK
+- VK_FW_UPDATE_ACK
 
   飞控向地面站发送应答消息.
 
@@ -719,7 +719,8 @@ mavlink common 标准消息集中主要由 MAVLINK_MSG_ID_COMMAND_INT 和 MAVLIN
     VKFLY_ARM_DENIED_SERVO_FAULT=17, /* 动力故障 | */
     VKFLY_ARM_DENIED_LEAN_ANG=18, /* 倾斜角过大 | */
     VKFLY_ARM_DENIED_IN_CALIBRATION=19, /* 正在校准中 | */
-    VKFLY_ARM_DENIED_REASON_ENUM_END=20, /*  | */
+    VKFLY_ARM_DENIED_HYDRO_BMS_CHECK_ERR=20, /* 氢电池自检故障 | */
+    VKFLY_ARM_DENIED_REASON_ENUM_END=21, /*  | */
   } VKFLY_ARM_DENIED_REASON;
   ```
 
@@ -1159,7 +1160,7 @@ mavlink common 标准消息集中主要由 MAVLINK_MSG_ID_COMMAND_INT 和 MAVLIN
 
 ### 自定义消息
 
-- **MAVLINK_VKINS_STATUS**
+- **VKINS_STATUS**
   
   VKins 系统的状态数据自定义消息, 主要用于一些自定状态的传输和排故.
 
@@ -1182,7 +1183,7 @@ mavlink common 标准消息集中主要由 MAVLINK_MSG_ID_COMMAND_INT 和 MAVLIN
   | solv_hsat_num   | 定向星数                                                                                  |
   | temperature     | 飞控温度, degC                                                                            |
   | vibe_coe        | 振动系数 0-无效                                                                           |
-- **MAVLINK_VKFMU_STATUS**
+- **VKFMU_STATUS**
 
   | 字段          | 说明                                  |
   | ------------- | ------------------------------------- |
@@ -1197,7 +1198,7 @@ mavlink common 标准消息集中主要由 MAVLINK_MSG_ID_COMMAND_INT 和 MAVLIN
   | servo_state   | 舵机状态, 每位对应一个舵机, 1-开 0-关 |
   | flight_dist   | 飞行距离, m, 本次上电开始飞行的总距离 |
 
-- **MAVLINK_VK_BMS_STATUS**
+- **VK_BMS_STATUS**
   智能电池状态数据
   当检测到智能电池数据接入, 飞控自动周期向地面站发送此消息
 
@@ -1215,7 +1216,34 @@ mavlink common 标准消息集中主要由 MAVLINK_MSG_ID_COMMAND_INT 和 MAVLIN
   | cyc_cnt      | 循环次数                     |
   | heath        | 电池健康度 1%                |
 
-- **MAVLINK_VK_COMP_VERSION**
+- **VK_ENGINE_ECU_STAUS**
+  发动机 ecu 状态信息
+  当检测到发动机数据接入后, 飞控自动周期向地面站发送此消息
+
+  | 字段           | 说明                              |
+  | -------------- | --------------------------------- |
+  | timestamp      | 系统本地时间戳ms                  |
+  | spd_rpm        | 转速 rpm                          |
+  | thr_pos        | 节气门位置 1%                     |
+  | fuel_pos       | 油位 1%                           |
+  | cylinderA_temp | 缸温1 degC                        |
+  | cylinderB_temp | 缸温2 degC                        |
+  | coolant_temp   | 冷却液温度 degC                   |
+  | fuel_remain    | 剩余油量 0.1L                     |
+  | alarm          | 警告状态, 参考 VK发动机CAN协议    |
+  | total_runtime  | 总工作时长, 1min                  |
+  | runtime        | 本次工作时长, 1min                |
+  | service_time   | 保养剩余时间, 1min                |
+  | output_volt    | 输出电压 0.1V                     |
+  | output_curr    | 输出电流 0.1A                     |
+  | fault          | 故障字, 参考 VK发动机CAN协议      |
+  | engine_state   | 工作状态 0-未启动 1\2-运行 3-锁机 |
+  | index          | 发动机编号 0-3                    |
+
+- **VK_FORMATION_LEADER**
+  编队飞行长机信息
+
+- **VK_COMP_VERSION**
   设备版本信息, 本消息可以通过 MAV_CMD_REQUEST_MESSAGE 进行读取, param2 是设备的 comp_id. comp_id 为 0 时, 飞控将回复多个消息逐个返回所有可获取设备的版本信息
   | 字段        | 说明                                                 |
   | ----------- | ---------------------------------------------------- |

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 -5831540222236224306
+#define MAVLINK_PRIMARY_XML_HASH -1656936398676691325
 
 #ifndef MAVLINK_STX
 #define MAVLINK_STX 253

+ 596 - 0
v2.0/VKFly/mavlink_msg_qingxie_bms.h

@@ -0,0 +1,596 @@
+#pragma once
+// MESSAGE QINGXIE_BMS PACKING
+
+#define MAVLINK_MSG_ID_QINGXIE_BMS 53300
+
+
+typedef struct __mavlink_qingxie_bms_t {
+ uint16_t bat_voltage; /*< [cV] Battery voltage.*/
+ uint16_t servo_current; /*< [cA] Servo current.*/
+ uint16_t stack_voltage; /*< [cV] Stack voltage.*/
+ uint16_t servo_voltage; /*< [cV] Servo voltage.*/
+ uint16_t bat_refuel_current; /*< [cA] Battery refuel current.*/
+ uint16_t gas_tank_pressure; /*<  Gas tank pressure.*/
+ uint16_t pipe_pressure; /*<  Pipe pressure.*/
+ uint16_t pcb_temp; /*<  PCB temperature.*/
+ uint16_t stack_temp; /*<  Stack temperature.*/
+ uint16_t work_status; /*<  */
+ uint16_t falt_status; /*<  */
+ uint8_t self_check; /*<  */
+ uint8_t Id; /*<  */
+} mavlink_qingxie_bms_t;
+
+#define MAVLINK_MSG_ID_QINGXIE_BMS_LEN 24
+#define MAVLINK_MSG_ID_QINGXIE_BMS_MIN_LEN 24
+#define MAVLINK_MSG_ID_53300_LEN 24
+#define MAVLINK_MSG_ID_53300_MIN_LEN 24
+
+#define MAVLINK_MSG_ID_QINGXIE_BMS_CRC 114
+#define MAVLINK_MSG_ID_53300_CRC 114
+
+
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_QINGXIE_BMS { \
+    53300, \
+    "QINGXIE_BMS", \
+    13, \
+    {  { "bat_voltage", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_qingxie_bms_t, bat_voltage) }, \
+         { "servo_current", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_qingxie_bms_t, servo_current) }, \
+         { "stack_voltage", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_qingxie_bms_t, stack_voltage) }, \
+         { "servo_voltage", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_qingxie_bms_t, servo_voltage) }, \
+         { "bat_refuel_current", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_qingxie_bms_t, bat_refuel_current) }, \
+         { "gas_tank_pressure", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_qingxie_bms_t, gas_tank_pressure) }, \
+         { "pipe_pressure", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_qingxie_bms_t, pipe_pressure) }, \
+         { "pcb_temp", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_qingxie_bms_t, pcb_temp) }, \
+         { "stack_temp", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_qingxie_bms_t, stack_temp) }, \
+         { "work_status", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_qingxie_bms_t, work_status) }, \
+         { "falt_status", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_qingxie_bms_t, falt_status) }, \
+         { "self_check", NULL, MAVLINK_TYPE_UINT8_T, 0, 22, offsetof(mavlink_qingxie_bms_t, self_check) }, \
+         { "Id", NULL, MAVLINK_TYPE_UINT8_T, 0, 23, offsetof(mavlink_qingxie_bms_t, Id) }, \
+         } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_QINGXIE_BMS { \
+    "QINGXIE_BMS", \
+    13, \
+    {  { "bat_voltage", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_qingxie_bms_t, bat_voltage) }, \
+         { "servo_current", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_qingxie_bms_t, servo_current) }, \
+         { "stack_voltage", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_qingxie_bms_t, stack_voltage) }, \
+         { "servo_voltage", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_qingxie_bms_t, servo_voltage) }, \
+         { "bat_refuel_current", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_qingxie_bms_t, bat_refuel_current) }, \
+         { "gas_tank_pressure", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_qingxie_bms_t, gas_tank_pressure) }, \
+         { "pipe_pressure", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_qingxie_bms_t, pipe_pressure) }, \
+         { "pcb_temp", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_qingxie_bms_t, pcb_temp) }, \
+         { "stack_temp", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_qingxie_bms_t, stack_temp) }, \
+         { "work_status", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_qingxie_bms_t, work_status) }, \
+         { "falt_status", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_qingxie_bms_t, falt_status) }, \
+         { "self_check", NULL, MAVLINK_TYPE_UINT8_T, 0, 22, offsetof(mavlink_qingxie_bms_t, self_check) }, \
+         { "Id", NULL, MAVLINK_TYPE_UINT8_T, 0, 23, offsetof(mavlink_qingxie_bms_t, Id) }, \
+         } \
+}
+#endif
+
+/**
+ * @brief Pack a qingxie_bms 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 bat_voltage [cV] Battery voltage.
+ * @param servo_current [cA] Servo current.
+ * @param stack_voltage [cV] Stack voltage.
+ * @param servo_voltage [cV] Servo voltage.
+ * @param bat_refuel_current [cA] Battery refuel current.
+ * @param gas_tank_pressure  Gas tank pressure.
+ * @param pipe_pressure  Pipe pressure.
+ * @param pcb_temp  PCB temperature.
+ * @param stack_temp  Stack temperature.
+ * @param work_status  
+ * @param falt_status  
+ * @param self_check  
+ * @param Id  
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_qingxie_bms_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+                               uint16_t bat_voltage, uint16_t servo_current, uint16_t stack_voltage, uint16_t servo_voltage, uint16_t bat_refuel_current, uint16_t gas_tank_pressure, uint16_t pipe_pressure, uint16_t pcb_temp, uint16_t stack_temp, uint16_t work_status, uint16_t falt_status, uint8_t self_check, uint8_t Id)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_QINGXIE_BMS_LEN];
+    _mav_put_uint16_t(buf, 0, bat_voltage);
+    _mav_put_uint16_t(buf, 2, servo_current);
+    _mav_put_uint16_t(buf, 4, stack_voltage);
+    _mav_put_uint16_t(buf, 6, servo_voltage);
+    _mav_put_uint16_t(buf, 8, bat_refuel_current);
+    _mav_put_uint16_t(buf, 10, gas_tank_pressure);
+    _mav_put_uint16_t(buf, 12, pipe_pressure);
+    _mav_put_uint16_t(buf, 14, pcb_temp);
+    _mav_put_uint16_t(buf, 16, stack_temp);
+    _mav_put_uint16_t(buf, 18, work_status);
+    _mav_put_uint16_t(buf, 20, falt_status);
+    _mav_put_uint8_t(buf, 22, self_check);
+    _mav_put_uint8_t(buf, 23, Id);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_QINGXIE_BMS_LEN);
+#else
+    mavlink_qingxie_bms_t packet;
+    packet.bat_voltage = bat_voltage;
+    packet.servo_current = servo_current;
+    packet.stack_voltage = stack_voltage;
+    packet.servo_voltage = servo_voltage;
+    packet.bat_refuel_current = bat_refuel_current;
+    packet.gas_tank_pressure = gas_tank_pressure;
+    packet.pipe_pressure = pipe_pressure;
+    packet.pcb_temp = pcb_temp;
+    packet.stack_temp = stack_temp;
+    packet.work_status = work_status;
+    packet.falt_status = falt_status;
+    packet.self_check = self_check;
+    packet.Id = Id;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_QINGXIE_BMS_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_QINGXIE_BMS;
+    return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_QINGXIE_BMS_MIN_LEN, MAVLINK_MSG_ID_QINGXIE_BMS_LEN, MAVLINK_MSG_ID_QINGXIE_BMS_CRC);
+}
+
+/**
+ * @brief Pack a qingxie_bms 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 bat_voltage [cV] Battery voltage.
+ * @param servo_current [cA] Servo current.
+ * @param stack_voltage [cV] Stack voltage.
+ * @param servo_voltage [cV] Servo voltage.
+ * @param bat_refuel_current [cA] Battery refuel current.
+ * @param gas_tank_pressure  Gas tank pressure.
+ * @param pipe_pressure  Pipe pressure.
+ * @param pcb_temp  PCB temperature.
+ * @param stack_temp  Stack temperature.
+ * @param work_status  
+ * @param falt_status  
+ * @param self_check  
+ * @param Id  
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_qingxie_bms_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+                               uint16_t bat_voltage, uint16_t servo_current, uint16_t stack_voltage, uint16_t servo_voltage, uint16_t bat_refuel_current, uint16_t gas_tank_pressure, uint16_t pipe_pressure, uint16_t pcb_temp, uint16_t stack_temp, uint16_t work_status, uint16_t falt_status, uint8_t self_check, uint8_t Id)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_QINGXIE_BMS_LEN];
+    _mav_put_uint16_t(buf, 0, bat_voltage);
+    _mav_put_uint16_t(buf, 2, servo_current);
+    _mav_put_uint16_t(buf, 4, stack_voltage);
+    _mav_put_uint16_t(buf, 6, servo_voltage);
+    _mav_put_uint16_t(buf, 8, bat_refuel_current);
+    _mav_put_uint16_t(buf, 10, gas_tank_pressure);
+    _mav_put_uint16_t(buf, 12, pipe_pressure);
+    _mav_put_uint16_t(buf, 14, pcb_temp);
+    _mav_put_uint16_t(buf, 16, stack_temp);
+    _mav_put_uint16_t(buf, 18, work_status);
+    _mav_put_uint16_t(buf, 20, falt_status);
+    _mav_put_uint8_t(buf, 22, self_check);
+    _mav_put_uint8_t(buf, 23, Id);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_QINGXIE_BMS_LEN);
+#else
+    mavlink_qingxie_bms_t packet;
+    packet.bat_voltage = bat_voltage;
+    packet.servo_current = servo_current;
+    packet.stack_voltage = stack_voltage;
+    packet.servo_voltage = servo_voltage;
+    packet.bat_refuel_current = bat_refuel_current;
+    packet.gas_tank_pressure = gas_tank_pressure;
+    packet.pipe_pressure = pipe_pressure;
+    packet.pcb_temp = pcb_temp;
+    packet.stack_temp = stack_temp;
+    packet.work_status = work_status;
+    packet.falt_status = falt_status;
+    packet.self_check = self_check;
+    packet.Id = Id;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_QINGXIE_BMS_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_QINGXIE_BMS;
+#if MAVLINK_CRC_EXTRA
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_QINGXIE_BMS_MIN_LEN, MAVLINK_MSG_ID_QINGXIE_BMS_LEN, MAVLINK_MSG_ID_QINGXIE_BMS_CRC);
+#else
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_QINGXIE_BMS_MIN_LEN, MAVLINK_MSG_ID_QINGXIE_BMS_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a qingxie_bms 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 bat_voltage [cV] Battery voltage.
+ * @param servo_current [cA] Servo current.
+ * @param stack_voltage [cV] Stack voltage.
+ * @param servo_voltage [cV] Servo voltage.
+ * @param bat_refuel_current [cA] Battery refuel current.
+ * @param gas_tank_pressure  Gas tank pressure.
+ * @param pipe_pressure  Pipe pressure.
+ * @param pcb_temp  PCB temperature.
+ * @param stack_temp  Stack temperature.
+ * @param work_status  
+ * @param falt_status  
+ * @param self_check  
+ * @param Id  
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_qingxie_bms_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+                               mavlink_message_t* msg,
+                                   uint16_t bat_voltage,uint16_t servo_current,uint16_t stack_voltage,uint16_t servo_voltage,uint16_t bat_refuel_current,uint16_t gas_tank_pressure,uint16_t pipe_pressure,uint16_t pcb_temp,uint16_t stack_temp,uint16_t work_status,uint16_t falt_status,uint8_t self_check,uint8_t Id)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_QINGXIE_BMS_LEN];
+    _mav_put_uint16_t(buf, 0, bat_voltage);
+    _mav_put_uint16_t(buf, 2, servo_current);
+    _mav_put_uint16_t(buf, 4, stack_voltage);
+    _mav_put_uint16_t(buf, 6, servo_voltage);
+    _mav_put_uint16_t(buf, 8, bat_refuel_current);
+    _mav_put_uint16_t(buf, 10, gas_tank_pressure);
+    _mav_put_uint16_t(buf, 12, pipe_pressure);
+    _mav_put_uint16_t(buf, 14, pcb_temp);
+    _mav_put_uint16_t(buf, 16, stack_temp);
+    _mav_put_uint16_t(buf, 18, work_status);
+    _mav_put_uint16_t(buf, 20, falt_status);
+    _mav_put_uint8_t(buf, 22, self_check);
+    _mav_put_uint8_t(buf, 23, Id);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_QINGXIE_BMS_LEN);
+#else
+    mavlink_qingxie_bms_t packet;
+    packet.bat_voltage = bat_voltage;
+    packet.servo_current = servo_current;
+    packet.stack_voltage = stack_voltage;
+    packet.servo_voltage = servo_voltage;
+    packet.bat_refuel_current = bat_refuel_current;
+    packet.gas_tank_pressure = gas_tank_pressure;
+    packet.pipe_pressure = pipe_pressure;
+    packet.pcb_temp = pcb_temp;
+    packet.stack_temp = stack_temp;
+    packet.work_status = work_status;
+    packet.falt_status = falt_status;
+    packet.self_check = self_check;
+    packet.Id = Id;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_QINGXIE_BMS_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_QINGXIE_BMS;
+    return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_QINGXIE_BMS_MIN_LEN, MAVLINK_MSG_ID_QINGXIE_BMS_LEN, MAVLINK_MSG_ID_QINGXIE_BMS_CRC);
+}
+
+/**
+ * @brief Encode a qingxie_bms 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 qingxie_bms C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_qingxie_bms_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_qingxie_bms_t* qingxie_bms)
+{
+    return mavlink_msg_qingxie_bms_pack(system_id, component_id, msg, qingxie_bms->bat_voltage, qingxie_bms->servo_current, qingxie_bms->stack_voltage, qingxie_bms->servo_voltage, qingxie_bms->bat_refuel_current, qingxie_bms->gas_tank_pressure, qingxie_bms->pipe_pressure, qingxie_bms->pcb_temp, qingxie_bms->stack_temp, qingxie_bms->work_status, qingxie_bms->falt_status, qingxie_bms->self_check, qingxie_bms->Id);
+}
+
+/**
+ * @brief Encode a qingxie_bms 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 qingxie_bms C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_qingxie_bms_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_qingxie_bms_t* qingxie_bms)
+{
+    return mavlink_msg_qingxie_bms_pack_chan(system_id, component_id, chan, msg, qingxie_bms->bat_voltage, qingxie_bms->servo_current, qingxie_bms->stack_voltage, qingxie_bms->servo_voltage, qingxie_bms->bat_refuel_current, qingxie_bms->gas_tank_pressure, qingxie_bms->pipe_pressure, qingxie_bms->pcb_temp, qingxie_bms->stack_temp, qingxie_bms->work_status, qingxie_bms->falt_status, qingxie_bms->self_check, qingxie_bms->Id);
+}
+
+/**
+ * @brief Encode a qingxie_bms 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 qingxie_bms C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_qingxie_bms_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_qingxie_bms_t* qingxie_bms)
+{
+    return mavlink_msg_qingxie_bms_pack_status(system_id, component_id, _status, msg,  qingxie_bms->bat_voltage, qingxie_bms->servo_current, qingxie_bms->stack_voltage, qingxie_bms->servo_voltage, qingxie_bms->bat_refuel_current, qingxie_bms->gas_tank_pressure, qingxie_bms->pipe_pressure, qingxie_bms->pcb_temp, qingxie_bms->stack_temp, qingxie_bms->work_status, qingxie_bms->falt_status, qingxie_bms->self_check, qingxie_bms->Id);
+}
+
+/**
+ * @brief Send a qingxie_bms message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param bat_voltage [cV] Battery voltage.
+ * @param servo_current [cA] Servo current.
+ * @param stack_voltage [cV] Stack voltage.
+ * @param servo_voltage [cV] Servo voltage.
+ * @param bat_refuel_current [cA] Battery refuel current.
+ * @param gas_tank_pressure  Gas tank pressure.
+ * @param pipe_pressure  Pipe pressure.
+ * @param pcb_temp  PCB temperature.
+ * @param stack_temp  Stack temperature.
+ * @param work_status  
+ * @param falt_status  
+ * @param self_check  
+ * @param Id  
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_qingxie_bms_send(mavlink_channel_t chan, uint16_t bat_voltage, uint16_t servo_current, uint16_t stack_voltage, uint16_t servo_voltage, uint16_t bat_refuel_current, uint16_t gas_tank_pressure, uint16_t pipe_pressure, uint16_t pcb_temp, uint16_t stack_temp, uint16_t work_status, uint16_t falt_status, uint8_t self_check, uint8_t Id)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_QINGXIE_BMS_LEN];
+    _mav_put_uint16_t(buf, 0, bat_voltage);
+    _mav_put_uint16_t(buf, 2, servo_current);
+    _mav_put_uint16_t(buf, 4, stack_voltage);
+    _mav_put_uint16_t(buf, 6, servo_voltage);
+    _mav_put_uint16_t(buf, 8, bat_refuel_current);
+    _mav_put_uint16_t(buf, 10, gas_tank_pressure);
+    _mav_put_uint16_t(buf, 12, pipe_pressure);
+    _mav_put_uint16_t(buf, 14, pcb_temp);
+    _mav_put_uint16_t(buf, 16, stack_temp);
+    _mav_put_uint16_t(buf, 18, work_status);
+    _mav_put_uint16_t(buf, 20, falt_status);
+    _mav_put_uint8_t(buf, 22, self_check);
+    _mav_put_uint8_t(buf, 23, Id);
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_QINGXIE_BMS, buf, MAVLINK_MSG_ID_QINGXIE_BMS_MIN_LEN, MAVLINK_MSG_ID_QINGXIE_BMS_LEN, MAVLINK_MSG_ID_QINGXIE_BMS_CRC);
+#else
+    mavlink_qingxie_bms_t packet;
+    packet.bat_voltage = bat_voltage;
+    packet.servo_current = servo_current;
+    packet.stack_voltage = stack_voltage;
+    packet.servo_voltage = servo_voltage;
+    packet.bat_refuel_current = bat_refuel_current;
+    packet.gas_tank_pressure = gas_tank_pressure;
+    packet.pipe_pressure = pipe_pressure;
+    packet.pcb_temp = pcb_temp;
+    packet.stack_temp = stack_temp;
+    packet.work_status = work_status;
+    packet.falt_status = falt_status;
+    packet.self_check = self_check;
+    packet.Id = Id;
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_QINGXIE_BMS, (const char *)&packet, MAVLINK_MSG_ID_QINGXIE_BMS_MIN_LEN, MAVLINK_MSG_ID_QINGXIE_BMS_LEN, MAVLINK_MSG_ID_QINGXIE_BMS_CRC);
+#endif
+}
+
+/**
+ * @brief Send a qingxie_bms message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_qingxie_bms_send_struct(mavlink_channel_t chan, const mavlink_qingxie_bms_t* qingxie_bms)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    mavlink_msg_qingxie_bms_send(chan, qingxie_bms->bat_voltage, qingxie_bms->servo_current, qingxie_bms->stack_voltage, qingxie_bms->servo_voltage, qingxie_bms->bat_refuel_current, qingxie_bms->gas_tank_pressure, qingxie_bms->pipe_pressure, qingxie_bms->pcb_temp, qingxie_bms->stack_temp, qingxie_bms->work_status, qingxie_bms->falt_status, qingxie_bms->self_check, qingxie_bms->Id);
+#else
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_QINGXIE_BMS, (const char *)qingxie_bms, MAVLINK_MSG_ID_QINGXIE_BMS_MIN_LEN, MAVLINK_MSG_ID_QINGXIE_BMS_LEN, MAVLINK_MSG_ID_QINGXIE_BMS_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_QINGXIE_BMS_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_qingxie_bms_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint16_t bat_voltage, uint16_t servo_current, uint16_t stack_voltage, uint16_t servo_voltage, uint16_t bat_refuel_current, uint16_t gas_tank_pressure, uint16_t pipe_pressure, uint16_t pcb_temp, uint16_t stack_temp, uint16_t work_status, uint16_t falt_status, uint8_t self_check, uint8_t Id)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char *buf = (char *)msgbuf;
+    _mav_put_uint16_t(buf, 0, bat_voltage);
+    _mav_put_uint16_t(buf, 2, servo_current);
+    _mav_put_uint16_t(buf, 4, stack_voltage);
+    _mav_put_uint16_t(buf, 6, servo_voltage);
+    _mav_put_uint16_t(buf, 8, bat_refuel_current);
+    _mav_put_uint16_t(buf, 10, gas_tank_pressure);
+    _mav_put_uint16_t(buf, 12, pipe_pressure);
+    _mav_put_uint16_t(buf, 14, pcb_temp);
+    _mav_put_uint16_t(buf, 16, stack_temp);
+    _mav_put_uint16_t(buf, 18, work_status);
+    _mav_put_uint16_t(buf, 20, falt_status);
+    _mav_put_uint8_t(buf, 22, self_check);
+    _mav_put_uint8_t(buf, 23, Id);
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_QINGXIE_BMS, buf, MAVLINK_MSG_ID_QINGXIE_BMS_MIN_LEN, MAVLINK_MSG_ID_QINGXIE_BMS_LEN, MAVLINK_MSG_ID_QINGXIE_BMS_CRC);
+#else
+    mavlink_qingxie_bms_t *packet = (mavlink_qingxie_bms_t *)msgbuf;
+    packet->bat_voltage = bat_voltage;
+    packet->servo_current = servo_current;
+    packet->stack_voltage = stack_voltage;
+    packet->servo_voltage = servo_voltage;
+    packet->bat_refuel_current = bat_refuel_current;
+    packet->gas_tank_pressure = gas_tank_pressure;
+    packet->pipe_pressure = pipe_pressure;
+    packet->pcb_temp = pcb_temp;
+    packet->stack_temp = stack_temp;
+    packet->work_status = work_status;
+    packet->falt_status = falt_status;
+    packet->self_check = self_check;
+    packet->Id = Id;
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_QINGXIE_BMS, (const char *)packet, MAVLINK_MSG_ID_QINGXIE_BMS_MIN_LEN, MAVLINK_MSG_ID_QINGXIE_BMS_LEN, MAVLINK_MSG_ID_QINGXIE_BMS_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE QINGXIE_BMS UNPACKING
+
+
+/**
+ * @brief Get field bat_voltage from qingxie_bms message
+ *
+ * @return [cV] Battery voltage.
+ */
+static inline uint16_t mavlink_msg_qingxie_bms_get_bat_voltage(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint16_t(msg,  0);
+}
+
+/**
+ * @brief Get field servo_current from qingxie_bms message
+ *
+ * @return [cA] Servo current.
+ */
+static inline uint16_t mavlink_msg_qingxie_bms_get_servo_current(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint16_t(msg,  2);
+}
+
+/**
+ * @brief Get field stack_voltage from qingxie_bms message
+ *
+ * @return [cV] Stack voltage.
+ */
+static inline uint16_t mavlink_msg_qingxie_bms_get_stack_voltage(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint16_t(msg,  4);
+}
+
+/**
+ * @brief Get field servo_voltage from qingxie_bms message
+ *
+ * @return [cV] Servo voltage.
+ */
+static inline uint16_t mavlink_msg_qingxie_bms_get_servo_voltage(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint16_t(msg,  6);
+}
+
+/**
+ * @brief Get field bat_refuel_current from qingxie_bms message
+ *
+ * @return [cA] Battery refuel current.
+ */
+static inline uint16_t mavlink_msg_qingxie_bms_get_bat_refuel_current(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint16_t(msg,  8);
+}
+
+/**
+ * @brief Get field gas_tank_pressure from qingxie_bms message
+ *
+ * @return  Gas tank pressure.
+ */
+static inline uint16_t mavlink_msg_qingxie_bms_get_gas_tank_pressure(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint16_t(msg,  10);
+}
+
+/**
+ * @brief Get field pipe_pressure from qingxie_bms message
+ *
+ * @return  Pipe pressure.
+ */
+static inline uint16_t mavlink_msg_qingxie_bms_get_pipe_pressure(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint16_t(msg,  12);
+}
+
+/**
+ * @brief Get field pcb_temp from qingxie_bms message
+ *
+ * @return  PCB temperature.
+ */
+static inline uint16_t mavlink_msg_qingxie_bms_get_pcb_temp(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint16_t(msg,  14);
+}
+
+/**
+ * @brief Get field stack_temp from qingxie_bms message
+ *
+ * @return  Stack temperature.
+ */
+static inline uint16_t mavlink_msg_qingxie_bms_get_stack_temp(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint16_t(msg,  16);
+}
+
+/**
+ * @brief Get field work_status from qingxie_bms message
+ *
+ * @return  
+ */
+static inline uint16_t mavlink_msg_qingxie_bms_get_work_status(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint16_t(msg,  18);
+}
+
+/**
+ * @brief Get field falt_status from qingxie_bms message
+ *
+ * @return  
+ */
+static inline uint16_t mavlink_msg_qingxie_bms_get_falt_status(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint16_t(msg,  20);
+}
+
+/**
+ * @brief Get field self_check from qingxie_bms message
+ *
+ * @return  
+ */
+static inline uint8_t mavlink_msg_qingxie_bms_get_self_check(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint8_t(msg,  22);
+}
+
+/**
+ * @brief Get field Id from qingxie_bms message
+ *
+ * @return  
+ */
+static inline uint8_t mavlink_msg_qingxie_bms_get_Id(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint8_t(msg,  23);
+}
+
+/**
+ * @brief Decode a qingxie_bms message into a struct
+ *
+ * @param msg The message to decode
+ * @param qingxie_bms C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_qingxie_bms_decode(const mavlink_message_t* msg, mavlink_qingxie_bms_t* qingxie_bms)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    qingxie_bms->bat_voltage = mavlink_msg_qingxie_bms_get_bat_voltage(msg);
+    qingxie_bms->servo_current = mavlink_msg_qingxie_bms_get_servo_current(msg);
+    qingxie_bms->stack_voltage = mavlink_msg_qingxie_bms_get_stack_voltage(msg);
+    qingxie_bms->servo_voltage = mavlink_msg_qingxie_bms_get_servo_voltage(msg);
+    qingxie_bms->bat_refuel_current = mavlink_msg_qingxie_bms_get_bat_refuel_current(msg);
+    qingxie_bms->gas_tank_pressure = mavlink_msg_qingxie_bms_get_gas_tank_pressure(msg);
+    qingxie_bms->pipe_pressure = mavlink_msg_qingxie_bms_get_pipe_pressure(msg);
+    qingxie_bms->pcb_temp = mavlink_msg_qingxie_bms_get_pcb_temp(msg);
+    qingxie_bms->stack_temp = mavlink_msg_qingxie_bms_get_stack_temp(msg);
+    qingxie_bms->work_status = mavlink_msg_qingxie_bms_get_work_status(msg);
+    qingxie_bms->falt_status = mavlink_msg_qingxie_bms_get_falt_status(msg);
+    qingxie_bms->self_check = mavlink_msg_qingxie_bms_get_self_check(msg);
+    qingxie_bms->Id = mavlink_msg_qingxie_bms_get_Id(msg);
+#else
+        uint8_t len = msg->len < MAVLINK_MSG_ID_QINGXIE_BMS_LEN? msg->len : MAVLINK_MSG_ID_QINGXIE_BMS_LEN;
+        memset(qingxie_bms, 0, MAVLINK_MSG_ID_QINGXIE_BMS_LEN);
+    memcpy(qingxie_bms, _MAV_PAYLOAD(msg), len);
+#endif
+}

+ 738 - 0
v2.0/VKFly/mavlink_msg_vk_engine_ecu_staus.h

@@ -0,0 +1,738 @@
+#pragma once
+// MESSAGE VK_ENGINE_ECU_STAUS PACKING
+
+#define MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS 53005
+
+
+typedef struct __mavlink_vk_engine_ecu_staus_t {
+ uint32_t timestamp; /*< [ms] Timestamp in ms from system boot.*/
+ uint32_t total_runtime; /*< [min] range extender output voltage*/
+ uint16_t spd_rpm; /*<  formation leader drone state bitmap*/
+ int16_t cylinderA_temp; /*< [degC] CylinderA head temperature*/
+ int16_t cylinderB_temp; /*< [degC] CylinderB head temperature*/
+ int16_t coolant_temp; /*< [degC] coolant head temperature*/
+ uint16_t fuel_remain; /*<  engine index*/
+ uint16_t alarm; /*<  range extender alarm bitmap*/
+ uint16_t runtime; /*< [min] range extender output voltage*/
+ uint16_t service_time; /*< [min] left time for service*/
+ uint16_t output_volt; /*< [dV] range extender output voltage*/
+ uint16_t output_curr; /*< [dA] range extender output current*/
+ uint8_t thr_pos; /*< [%] throttle
+        position */
+ uint8_t fuel_pos; /*< [%] fuel
+        position*/
+ uint8_t fault; /*<  engine fault*/
+ uint8_t engine_state; /*<  engine state*/
+ uint8_t index; /*<  engine index*/
+ uint8_t reserve[4]; /*<  engine state*/
+} mavlink_vk_engine_ecu_staus_t;
+
+#define MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_LEN 37
+#define MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_MIN_LEN 37
+#define MAVLINK_MSG_ID_53005_LEN 37
+#define MAVLINK_MSG_ID_53005_MIN_LEN 37
+
+#define MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_CRC 145
+#define MAVLINK_MSG_ID_53005_CRC 145
+
+#define MAVLINK_MSG_VK_ENGINE_ECU_STAUS_FIELD_RESERVE_LEN 4
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_VK_ENGINE_ECU_STAUS { \
+    53005, \
+    "VK_ENGINE_ECU_STAUS", \
+    18, \
+    {  { "timestamp", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_vk_engine_ecu_staus_t, timestamp) }, \
+         { "spd_rpm", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_vk_engine_ecu_staus_t, spd_rpm) }, \
+         { "thr_pos", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_vk_engine_ecu_staus_t, thr_pos) }, \
+         { "fuel_pos", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_vk_engine_ecu_staus_t, fuel_pos) }, \
+         { "cylinderA_temp", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_vk_engine_ecu_staus_t, cylinderA_temp) }, \
+         { "cylinderB_temp", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_vk_engine_ecu_staus_t, cylinderB_temp) }, \
+         { "coolant_temp", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_vk_engine_ecu_staus_t, coolant_temp) }, \
+         { "fuel_remain", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_vk_engine_ecu_staus_t, fuel_remain) }, \
+         { "alarm", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_vk_engine_ecu_staus_t, alarm) }, \
+         { "total_runtime", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_vk_engine_ecu_staus_t, total_runtime) }, \
+         { "runtime", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_vk_engine_ecu_staus_t, runtime) }, \
+         { "service_time", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_vk_engine_ecu_staus_t, service_time) }, \
+         { "output_volt", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_vk_engine_ecu_staus_t, output_volt) }, \
+         { "output_curr", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_vk_engine_ecu_staus_t, output_curr) }, \
+         { "fault", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_vk_engine_ecu_staus_t, fault) }, \
+         { "engine_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_vk_engine_ecu_staus_t, engine_state) }, \
+         { "index", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_vk_engine_ecu_staus_t, index) }, \
+         { "reserve", NULL, MAVLINK_TYPE_UINT8_T, 4, 33, offsetof(mavlink_vk_engine_ecu_staus_t, reserve) }, \
+         } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_VK_ENGINE_ECU_STAUS { \
+    "VK_ENGINE_ECU_STAUS", \
+    18, \
+    {  { "timestamp", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_vk_engine_ecu_staus_t, timestamp) }, \
+         { "spd_rpm", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_vk_engine_ecu_staus_t, spd_rpm) }, \
+         { "thr_pos", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_vk_engine_ecu_staus_t, thr_pos) }, \
+         { "fuel_pos", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_vk_engine_ecu_staus_t, fuel_pos) }, \
+         { "cylinderA_temp", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_vk_engine_ecu_staus_t, cylinderA_temp) }, \
+         { "cylinderB_temp", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_vk_engine_ecu_staus_t, cylinderB_temp) }, \
+         { "coolant_temp", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_vk_engine_ecu_staus_t, coolant_temp) }, \
+         { "fuel_remain", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_vk_engine_ecu_staus_t, fuel_remain) }, \
+         { "alarm", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_vk_engine_ecu_staus_t, alarm) }, \
+         { "total_runtime", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_vk_engine_ecu_staus_t, total_runtime) }, \
+         { "runtime", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_vk_engine_ecu_staus_t, runtime) }, \
+         { "service_time", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_vk_engine_ecu_staus_t, service_time) }, \
+         { "output_volt", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_vk_engine_ecu_staus_t, output_volt) }, \
+         { "output_curr", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_vk_engine_ecu_staus_t, output_curr) }, \
+         { "fault", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_vk_engine_ecu_staus_t, fault) }, \
+         { "engine_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_vk_engine_ecu_staus_t, engine_state) }, \
+         { "index", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_vk_engine_ecu_staus_t, index) }, \
+         { "reserve", NULL, MAVLINK_TYPE_UINT8_T, 4, 33, offsetof(mavlink_vk_engine_ecu_staus_t, reserve) }, \
+         } \
+}
+#endif
+
+/**
+ * @brief Pack a vk_engine_ecu_staus 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 timestamp [ms] Timestamp in ms from system boot.
+ * @param spd_rpm  formation leader drone state bitmap
+ * @param thr_pos [%] throttle
+        position 
+ * @param fuel_pos [%] fuel
+        position
+ * @param cylinderA_temp [degC] CylinderA head temperature
+ * @param cylinderB_temp [degC] CylinderB head temperature
+ * @param coolant_temp [degC] coolant head temperature
+ * @param fuel_remain  engine index
+ * @param alarm  range extender alarm bitmap
+ * @param total_runtime [min] range extender output voltage
+ * @param runtime [min] range extender output voltage
+ * @param service_time [min] left time for service
+ * @param output_volt [dV] range extender output voltage
+ * @param output_curr [dA] range extender output current
+ * @param fault  engine fault
+ * @param engine_state  engine state
+ * @param index  engine index
+ * @param reserve  engine state
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_vk_engine_ecu_staus_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+                               uint32_t timestamp, uint16_t spd_rpm, uint8_t thr_pos, uint8_t fuel_pos, int16_t cylinderA_temp, int16_t cylinderB_temp, int16_t coolant_temp, uint16_t fuel_remain, uint16_t alarm, uint32_t total_runtime, uint16_t runtime, uint16_t service_time, uint16_t output_volt, uint16_t output_curr, uint8_t fault, uint8_t engine_state, uint8_t index, const uint8_t *reserve)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_LEN];
+    _mav_put_uint32_t(buf, 0, timestamp);
+    _mav_put_uint32_t(buf, 4, total_runtime);
+    _mav_put_uint16_t(buf, 8, spd_rpm);
+    _mav_put_int16_t(buf, 10, cylinderA_temp);
+    _mav_put_int16_t(buf, 12, cylinderB_temp);
+    _mav_put_int16_t(buf, 14, coolant_temp);
+    _mav_put_uint16_t(buf, 16, fuel_remain);
+    _mav_put_uint16_t(buf, 18, alarm);
+    _mav_put_uint16_t(buf, 20, runtime);
+    _mav_put_uint16_t(buf, 22, service_time);
+    _mav_put_uint16_t(buf, 24, output_volt);
+    _mav_put_uint16_t(buf, 26, output_curr);
+    _mav_put_uint8_t(buf, 28, thr_pos);
+    _mav_put_uint8_t(buf, 29, fuel_pos);
+    _mav_put_uint8_t(buf, 30, fault);
+    _mav_put_uint8_t(buf, 31, engine_state);
+    _mav_put_uint8_t(buf, 32, index);
+    _mav_put_uint8_t_array(buf, 33, reserve, 4);
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_LEN);
+#else
+    mavlink_vk_engine_ecu_staus_t packet;
+    packet.timestamp = timestamp;
+    packet.total_runtime = total_runtime;
+    packet.spd_rpm = spd_rpm;
+    packet.cylinderA_temp = cylinderA_temp;
+    packet.cylinderB_temp = cylinderB_temp;
+    packet.coolant_temp = coolant_temp;
+    packet.fuel_remain = fuel_remain;
+    packet.alarm = alarm;
+    packet.runtime = runtime;
+    packet.service_time = service_time;
+    packet.output_volt = output_volt;
+    packet.output_curr = output_curr;
+    packet.thr_pos = thr_pos;
+    packet.fuel_pos = fuel_pos;
+    packet.fault = fault;
+    packet.engine_state = engine_state;
+    packet.index = index;
+    mav_array_memcpy(packet.reserve, reserve, sizeof(uint8_t)*4);
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS;
+    return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_MIN_LEN, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_LEN, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_CRC);
+}
+
+/**
+ * @brief Pack a vk_engine_ecu_staus 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 timestamp [ms] Timestamp in ms from system boot.
+ * @param spd_rpm  formation leader drone state bitmap
+ * @param thr_pos [%] throttle
+        position 
+ * @param fuel_pos [%] fuel
+        position
+ * @param cylinderA_temp [degC] CylinderA head temperature
+ * @param cylinderB_temp [degC] CylinderB head temperature
+ * @param coolant_temp [degC] coolant head temperature
+ * @param fuel_remain  engine index
+ * @param alarm  range extender alarm bitmap
+ * @param total_runtime [min] range extender output voltage
+ * @param runtime [min] range extender output voltage
+ * @param service_time [min] left time for service
+ * @param output_volt [dV] range extender output voltage
+ * @param output_curr [dA] range extender output current
+ * @param fault  engine fault
+ * @param engine_state  engine state
+ * @param index  engine index
+ * @param reserve  engine state
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_vk_engine_ecu_staus_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+                               uint32_t timestamp, uint16_t spd_rpm, uint8_t thr_pos, uint8_t fuel_pos, int16_t cylinderA_temp, int16_t cylinderB_temp, int16_t coolant_temp, uint16_t fuel_remain, uint16_t alarm, uint32_t total_runtime, uint16_t runtime, uint16_t service_time, uint16_t output_volt, uint16_t output_curr, uint8_t fault, uint8_t engine_state, uint8_t index, const uint8_t *reserve)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_LEN];
+    _mav_put_uint32_t(buf, 0, timestamp);
+    _mav_put_uint32_t(buf, 4, total_runtime);
+    _mav_put_uint16_t(buf, 8, spd_rpm);
+    _mav_put_int16_t(buf, 10, cylinderA_temp);
+    _mav_put_int16_t(buf, 12, cylinderB_temp);
+    _mav_put_int16_t(buf, 14, coolant_temp);
+    _mav_put_uint16_t(buf, 16, fuel_remain);
+    _mav_put_uint16_t(buf, 18, alarm);
+    _mav_put_uint16_t(buf, 20, runtime);
+    _mav_put_uint16_t(buf, 22, service_time);
+    _mav_put_uint16_t(buf, 24, output_volt);
+    _mav_put_uint16_t(buf, 26, output_curr);
+    _mav_put_uint8_t(buf, 28, thr_pos);
+    _mav_put_uint8_t(buf, 29, fuel_pos);
+    _mav_put_uint8_t(buf, 30, fault);
+    _mav_put_uint8_t(buf, 31, engine_state);
+    _mav_put_uint8_t(buf, 32, index);
+    _mav_put_uint8_t_array(buf, 33, reserve, 4);
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_LEN);
+#else
+    mavlink_vk_engine_ecu_staus_t packet;
+    packet.timestamp = timestamp;
+    packet.total_runtime = total_runtime;
+    packet.spd_rpm = spd_rpm;
+    packet.cylinderA_temp = cylinderA_temp;
+    packet.cylinderB_temp = cylinderB_temp;
+    packet.coolant_temp = coolant_temp;
+    packet.fuel_remain = fuel_remain;
+    packet.alarm = alarm;
+    packet.runtime = runtime;
+    packet.service_time = service_time;
+    packet.output_volt = output_volt;
+    packet.output_curr = output_curr;
+    packet.thr_pos = thr_pos;
+    packet.fuel_pos = fuel_pos;
+    packet.fault = fault;
+    packet.engine_state = engine_state;
+    packet.index = index;
+    mav_array_memcpy(packet.reserve, reserve, sizeof(uint8_t)*4);
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS;
+#if MAVLINK_CRC_EXTRA
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_MIN_LEN, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_LEN, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_CRC);
+#else
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_MIN_LEN, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a vk_engine_ecu_staus 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 timestamp [ms] Timestamp in ms from system boot.
+ * @param spd_rpm  formation leader drone state bitmap
+ * @param thr_pos [%] throttle
+        position 
+ * @param fuel_pos [%] fuel
+        position
+ * @param cylinderA_temp [degC] CylinderA head temperature
+ * @param cylinderB_temp [degC] CylinderB head temperature
+ * @param coolant_temp [degC] coolant head temperature
+ * @param fuel_remain  engine index
+ * @param alarm  range extender alarm bitmap
+ * @param total_runtime [min] range extender output voltage
+ * @param runtime [min] range extender output voltage
+ * @param service_time [min] left time for service
+ * @param output_volt [dV] range extender output voltage
+ * @param output_curr [dA] range extender output current
+ * @param fault  engine fault
+ * @param engine_state  engine state
+ * @param index  engine index
+ * @param reserve  engine state
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_vk_engine_ecu_staus_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+                               mavlink_message_t* msg,
+                                   uint32_t timestamp,uint16_t spd_rpm,uint8_t thr_pos,uint8_t fuel_pos,int16_t cylinderA_temp,int16_t cylinderB_temp,int16_t coolant_temp,uint16_t fuel_remain,uint16_t alarm,uint32_t total_runtime,uint16_t runtime,uint16_t service_time,uint16_t output_volt,uint16_t output_curr,uint8_t fault,uint8_t engine_state,uint8_t index,const uint8_t *reserve)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_LEN];
+    _mav_put_uint32_t(buf, 0, timestamp);
+    _mav_put_uint32_t(buf, 4, total_runtime);
+    _mav_put_uint16_t(buf, 8, spd_rpm);
+    _mav_put_int16_t(buf, 10, cylinderA_temp);
+    _mav_put_int16_t(buf, 12, cylinderB_temp);
+    _mav_put_int16_t(buf, 14, coolant_temp);
+    _mav_put_uint16_t(buf, 16, fuel_remain);
+    _mav_put_uint16_t(buf, 18, alarm);
+    _mav_put_uint16_t(buf, 20, runtime);
+    _mav_put_uint16_t(buf, 22, service_time);
+    _mav_put_uint16_t(buf, 24, output_volt);
+    _mav_put_uint16_t(buf, 26, output_curr);
+    _mav_put_uint8_t(buf, 28, thr_pos);
+    _mav_put_uint8_t(buf, 29, fuel_pos);
+    _mav_put_uint8_t(buf, 30, fault);
+    _mav_put_uint8_t(buf, 31, engine_state);
+    _mav_put_uint8_t(buf, 32, index);
+    _mav_put_uint8_t_array(buf, 33, reserve, 4);
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_LEN);
+#else
+    mavlink_vk_engine_ecu_staus_t packet;
+    packet.timestamp = timestamp;
+    packet.total_runtime = total_runtime;
+    packet.spd_rpm = spd_rpm;
+    packet.cylinderA_temp = cylinderA_temp;
+    packet.cylinderB_temp = cylinderB_temp;
+    packet.coolant_temp = coolant_temp;
+    packet.fuel_remain = fuel_remain;
+    packet.alarm = alarm;
+    packet.runtime = runtime;
+    packet.service_time = service_time;
+    packet.output_volt = output_volt;
+    packet.output_curr = output_curr;
+    packet.thr_pos = thr_pos;
+    packet.fuel_pos = fuel_pos;
+    packet.fault = fault;
+    packet.engine_state = engine_state;
+    packet.index = index;
+    mav_array_memcpy(packet.reserve, reserve, sizeof(uint8_t)*4);
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS;
+    return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_MIN_LEN, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_LEN, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_CRC);
+}
+
+/**
+ * @brief Encode a vk_engine_ecu_staus 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_engine_ecu_staus C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_vk_engine_ecu_staus_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_vk_engine_ecu_staus_t* vk_engine_ecu_staus)
+{
+    return mavlink_msg_vk_engine_ecu_staus_pack(system_id, component_id, msg, vk_engine_ecu_staus->timestamp, vk_engine_ecu_staus->spd_rpm, vk_engine_ecu_staus->thr_pos, vk_engine_ecu_staus->fuel_pos, vk_engine_ecu_staus->cylinderA_temp, vk_engine_ecu_staus->cylinderB_temp, vk_engine_ecu_staus->coolant_temp, vk_engine_ecu_staus->fuel_remain, vk_engine_ecu_staus->alarm, vk_engine_ecu_staus->total_runtime, vk_engine_ecu_staus->runtime, vk_engine_ecu_staus->service_time, vk_engine_ecu_staus->output_volt, vk_engine_ecu_staus->output_curr, vk_engine_ecu_staus->fault, vk_engine_ecu_staus->engine_state, vk_engine_ecu_staus->index, vk_engine_ecu_staus->reserve);
+}
+
+/**
+ * @brief Encode a vk_engine_ecu_staus 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_engine_ecu_staus C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_vk_engine_ecu_staus_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_vk_engine_ecu_staus_t* vk_engine_ecu_staus)
+{
+    return mavlink_msg_vk_engine_ecu_staus_pack_chan(system_id, component_id, chan, msg, vk_engine_ecu_staus->timestamp, vk_engine_ecu_staus->spd_rpm, vk_engine_ecu_staus->thr_pos, vk_engine_ecu_staus->fuel_pos, vk_engine_ecu_staus->cylinderA_temp, vk_engine_ecu_staus->cylinderB_temp, vk_engine_ecu_staus->coolant_temp, vk_engine_ecu_staus->fuel_remain, vk_engine_ecu_staus->alarm, vk_engine_ecu_staus->total_runtime, vk_engine_ecu_staus->runtime, vk_engine_ecu_staus->service_time, vk_engine_ecu_staus->output_volt, vk_engine_ecu_staus->output_curr, vk_engine_ecu_staus->fault, vk_engine_ecu_staus->engine_state, vk_engine_ecu_staus->index, vk_engine_ecu_staus->reserve);
+}
+
+/**
+ * @brief Encode a vk_engine_ecu_staus 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_engine_ecu_staus C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_vk_engine_ecu_staus_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_vk_engine_ecu_staus_t* vk_engine_ecu_staus)
+{
+    return mavlink_msg_vk_engine_ecu_staus_pack_status(system_id, component_id, _status, msg,  vk_engine_ecu_staus->timestamp, vk_engine_ecu_staus->spd_rpm, vk_engine_ecu_staus->thr_pos, vk_engine_ecu_staus->fuel_pos, vk_engine_ecu_staus->cylinderA_temp, vk_engine_ecu_staus->cylinderB_temp, vk_engine_ecu_staus->coolant_temp, vk_engine_ecu_staus->fuel_remain, vk_engine_ecu_staus->alarm, vk_engine_ecu_staus->total_runtime, vk_engine_ecu_staus->runtime, vk_engine_ecu_staus->service_time, vk_engine_ecu_staus->output_volt, vk_engine_ecu_staus->output_curr, vk_engine_ecu_staus->fault, vk_engine_ecu_staus->engine_state, vk_engine_ecu_staus->index, vk_engine_ecu_staus->reserve);
+}
+
+/**
+ * @brief Send a vk_engine_ecu_staus message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param timestamp [ms] Timestamp in ms from system boot.
+ * @param spd_rpm  formation leader drone state bitmap
+ * @param thr_pos [%] throttle
+        position 
+ * @param fuel_pos [%] fuel
+        position
+ * @param cylinderA_temp [degC] CylinderA head temperature
+ * @param cylinderB_temp [degC] CylinderB head temperature
+ * @param coolant_temp [degC] coolant head temperature
+ * @param fuel_remain  engine index
+ * @param alarm  range extender alarm bitmap
+ * @param total_runtime [min] range extender output voltage
+ * @param runtime [min] range extender output voltage
+ * @param service_time [min] left time for service
+ * @param output_volt [dV] range extender output voltage
+ * @param output_curr [dA] range extender output current
+ * @param fault  engine fault
+ * @param engine_state  engine state
+ * @param index  engine index
+ * @param reserve  engine state
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_vk_engine_ecu_staus_send(mavlink_channel_t chan, uint32_t timestamp, uint16_t spd_rpm, uint8_t thr_pos, uint8_t fuel_pos, int16_t cylinderA_temp, int16_t cylinderB_temp, int16_t coolant_temp, uint16_t fuel_remain, uint16_t alarm, uint32_t total_runtime, uint16_t runtime, uint16_t service_time, uint16_t output_volt, uint16_t output_curr, uint8_t fault, uint8_t engine_state, uint8_t index, const uint8_t *reserve)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_LEN];
+    _mav_put_uint32_t(buf, 0, timestamp);
+    _mav_put_uint32_t(buf, 4, total_runtime);
+    _mav_put_uint16_t(buf, 8, spd_rpm);
+    _mav_put_int16_t(buf, 10, cylinderA_temp);
+    _mav_put_int16_t(buf, 12, cylinderB_temp);
+    _mav_put_int16_t(buf, 14, coolant_temp);
+    _mav_put_uint16_t(buf, 16, fuel_remain);
+    _mav_put_uint16_t(buf, 18, alarm);
+    _mav_put_uint16_t(buf, 20, runtime);
+    _mav_put_uint16_t(buf, 22, service_time);
+    _mav_put_uint16_t(buf, 24, output_volt);
+    _mav_put_uint16_t(buf, 26, output_curr);
+    _mav_put_uint8_t(buf, 28, thr_pos);
+    _mav_put_uint8_t(buf, 29, fuel_pos);
+    _mav_put_uint8_t(buf, 30, fault);
+    _mav_put_uint8_t(buf, 31, engine_state);
+    _mav_put_uint8_t(buf, 32, index);
+    _mav_put_uint8_t_array(buf, 33, reserve, 4);
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS, buf, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_MIN_LEN, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_LEN, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_CRC);
+#else
+    mavlink_vk_engine_ecu_staus_t packet;
+    packet.timestamp = timestamp;
+    packet.total_runtime = total_runtime;
+    packet.spd_rpm = spd_rpm;
+    packet.cylinderA_temp = cylinderA_temp;
+    packet.cylinderB_temp = cylinderB_temp;
+    packet.coolant_temp = coolant_temp;
+    packet.fuel_remain = fuel_remain;
+    packet.alarm = alarm;
+    packet.runtime = runtime;
+    packet.service_time = service_time;
+    packet.output_volt = output_volt;
+    packet.output_curr = output_curr;
+    packet.thr_pos = thr_pos;
+    packet.fuel_pos = fuel_pos;
+    packet.fault = fault;
+    packet.engine_state = engine_state;
+    packet.index = index;
+    mav_array_memcpy(packet.reserve, reserve, sizeof(uint8_t)*4);
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS, (const char *)&packet, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_MIN_LEN, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_LEN, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_CRC);
+#endif
+}
+
+/**
+ * @brief Send a vk_engine_ecu_staus message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_vk_engine_ecu_staus_send_struct(mavlink_channel_t chan, const mavlink_vk_engine_ecu_staus_t* vk_engine_ecu_staus)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    mavlink_msg_vk_engine_ecu_staus_send(chan, vk_engine_ecu_staus->timestamp, vk_engine_ecu_staus->spd_rpm, vk_engine_ecu_staus->thr_pos, vk_engine_ecu_staus->fuel_pos, vk_engine_ecu_staus->cylinderA_temp, vk_engine_ecu_staus->cylinderB_temp, vk_engine_ecu_staus->coolant_temp, vk_engine_ecu_staus->fuel_remain, vk_engine_ecu_staus->alarm, vk_engine_ecu_staus->total_runtime, vk_engine_ecu_staus->runtime, vk_engine_ecu_staus->service_time, vk_engine_ecu_staus->output_volt, vk_engine_ecu_staus->output_curr, vk_engine_ecu_staus->fault, vk_engine_ecu_staus->engine_state, vk_engine_ecu_staus->index, vk_engine_ecu_staus->reserve);
+#else
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS, (const char *)vk_engine_ecu_staus, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_MIN_LEN, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_LEN, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_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_engine_ecu_staus_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint32_t timestamp, uint16_t spd_rpm, uint8_t thr_pos, uint8_t fuel_pos, int16_t cylinderA_temp, int16_t cylinderB_temp, int16_t coolant_temp, uint16_t fuel_remain, uint16_t alarm, uint32_t total_runtime, uint16_t runtime, uint16_t service_time, uint16_t output_volt, uint16_t output_curr, uint8_t fault, uint8_t engine_state, uint8_t index, const uint8_t *reserve)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char *buf = (char *)msgbuf;
+    _mav_put_uint32_t(buf, 0, timestamp);
+    _mav_put_uint32_t(buf, 4, total_runtime);
+    _mav_put_uint16_t(buf, 8, spd_rpm);
+    _mav_put_int16_t(buf, 10, cylinderA_temp);
+    _mav_put_int16_t(buf, 12, cylinderB_temp);
+    _mav_put_int16_t(buf, 14, coolant_temp);
+    _mav_put_uint16_t(buf, 16, fuel_remain);
+    _mav_put_uint16_t(buf, 18, alarm);
+    _mav_put_uint16_t(buf, 20, runtime);
+    _mav_put_uint16_t(buf, 22, service_time);
+    _mav_put_uint16_t(buf, 24, output_volt);
+    _mav_put_uint16_t(buf, 26, output_curr);
+    _mav_put_uint8_t(buf, 28, thr_pos);
+    _mav_put_uint8_t(buf, 29, fuel_pos);
+    _mav_put_uint8_t(buf, 30, fault);
+    _mav_put_uint8_t(buf, 31, engine_state);
+    _mav_put_uint8_t(buf, 32, index);
+    _mav_put_uint8_t_array(buf, 33, reserve, 4);
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS, buf, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_MIN_LEN, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_LEN, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_CRC);
+#else
+    mavlink_vk_engine_ecu_staus_t *packet = (mavlink_vk_engine_ecu_staus_t *)msgbuf;
+    packet->timestamp = timestamp;
+    packet->total_runtime = total_runtime;
+    packet->spd_rpm = spd_rpm;
+    packet->cylinderA_temp = cylinderA_temp;
+    packet->cylinderB_temp = cylinderB_temp;
+    packet->coolant_temp = coolant_temp;
+    packet->fuel_remain = fuel_remain;
+    packet->alarm = alarm;
+    packet->runtime = runtime;
+    packet->service_time = service_time;
+    packet->output_volt = output_volt;
+    packet->output_curr = output_curr;
+    packet->thr_pos = thr_pos;
+    packet->fuel_pos = fuel_pos;
+    packet->fault = fault;
+    packet->engine_state = engine_state;
+    packet->index = index;
+    mav_array_memcpy(packet->reserve, reserve, sizeof(uint8_t)*4);
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS, (const char *)packet, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_MIN_LEN, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_LEN, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE VK_ENGINE_ECU_STAUS UNPACKING
+
+
+/**
+ * @brief Get field timestamp from vk_engine_ecu_staus message
+ *
+ * @return [ms] Timestamp in ms from system boot.
+ */
+static inline uint32_t mavlink_msg_vk_engine_ecu_staus_get_timestamp(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint32_t(msg,  0);
+}
+
+/**
+ * @brief Get field spd_rpm from vk_engine_ecu_staus message
+ *
+ * @return  formation leader drone state bitmap
+ */
+static inline uint16_t mavlink_msg_vk_engine_ecu_staus_get_spd_rpm(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint16_t(msg,  8);
+}
+
+/**
+ * @brief Get field thr_pos from vk_engine_ecu_staus message
+ *
+ * @return [%] throttle
+        position 
+ */
+static inline uint8_t mavlink_msg_vk_engine_ecu_staus_get_thr_pos(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint8_t(msg,  28);
+}
+
+/**
+ * @brief Get field fuel_pos from vk_engine_ecu_staus message
+ *
+ * @return [%] fuel
+        position
+ */
+static inline uint8_t mavlink_msg_vk_engine_ecu_staus_get_fuel_pos(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint8_t(msg,  29);
+}
+
+/**
+ * @brief Get field cylinderA_temp from vk_engine_ecu_staus message
+ *
+ * @return [degC] CylinderA head temperature
+ */
+static inline int16_t mavlink_msg_vk_engine_ecu_staus_get_cylinderA_temp(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_int16_t(msg,  10);
+}
+
+/**
+ * @brief Get field cylinderB_temp from vk_engine_ecu_staus message
+ *
+ * @return [degC] CylinderB head temperature
+ */
+static inline int16_t mavlink_msg_vk_engine_ecu_staus_get_cylinderB_temp(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_int16_t(msg,  12);
+}
+
+/**
+ * @brief Get field coolant_temp from vk_engine_ecu_staus message
+ *
+ * @return [degC] coolant head temperature
+ */
+static inline int16_t mavlink_msg_vk_engine_ecu_staus_get_coolant_temp(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_int16_t(msg,  14);
+}
+
+/**
+ * @brief Get field fuel_remain from vk_engine_ecu_staus message
+ *
+ * @return  engine index
+ */
+static inline uint16_t mavlink_msg_vk_engine_ecu_staus_get_fuel_remain(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint16_t(msg,  16);
+}
+
+/**
+ * @brief Get field alarm from vk_engine_ecu_staus message
+ *
+ * @return  range extender alarm bitmap
+ */
+static inline uint16_t mavlink_msg_vk_engine_ecu_staus_get_alarm(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint16_t(msg,  18);
+}
+
+/**
+ * @brief Get field total_runtime from vk_engine_ecu_staus message
+ *
+ * @return [min] range extender output voltage
+ */
+static inline uint32_t mavlink_msg_vk_engine_ecu_staus_get_total_runtime(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint32_t(msg,  4);
+}
+
+/**
+ * @brief Get field runtime from vk_engine_ecu_staus message
+ *
+ * @return [min] range extender output voltage
+ */
+static inline uint16_t mavlink_msg_vk_engine_ecu_staus_get_runtime(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint16_t(msg,  20);
+}
+
+/**
+ * @brief Get field service_time from vk_engine_ecu_staus message
+ *
+ * @return [min] left time for service
+ */
+static inline uint16_t mavlink_msg_vk_engine_ecu_staus_get_service_time(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint16_t(msg,  22);
+}
+
+/**
+ * @brief Get field output_volt from vk_engine_ecu_staus message
+ *
+ * @return [dV] range extender output voltage
+ */
+static inline uint16_t mavlink_msg_vk_engine_ecu_staus_get_output_volt(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint16_t(msg,  24);
+}
+
+/**
+ * @brief Get field output_curr from vk_engine_ecu_staus message
+ *
+ * @return [dA] range extender output current
+ */
+static inline uint16_t mavlink_msg_vk_engine_ecu_staus_get_output_curr(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint16_t(msg,  26);
+}
+
+/**
+ * @brief Get field fault from vk_engine_ecu_staus message
+ *
+ * @return  engine fault
+ */
+static inline uint8_t mavlink_msg_vk_engine_ecu_staus_get_fault(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint8_t(msg,  30);
+}
+
+/**
+ * @brief Get field engine_state from vk_engine_ecu_staus message
+ *
+ * @return  engine state
+ */
+static inline uint8_t mavlink_msg_vk_engine_ecu_staus_get_engine_state(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint8_t(msg,  31);
+}
+
+/**
+ * @brief Get field index from vk_engine_ecu_staus message
+ *
+ * @return  engine index
+ */
+static inline uint8_t mavlink_msg_vk_engine_ecu_staus_get_index(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint8_t(msg,  32);
+}
+
+/**
+ * @brief Get field reserve from vk_engine_ecu_staus message
+ *
+ * @return  engine state
+ */
+static inline uint16_t mavlink_msg_vk_engine_ecu_staus_get_reserve(const mavlink_message_t* msg, uint8_t *reserve)
+{
+    return _MAV_RETURN_uint8_t_array(msg, reserve, 4,  33);
+}
+
+/**
+ * @brief Decode a vk_engine_ecu_staus message into a struct
+ *
+ * @param msg The message to decode
+ * @param vk_engine_ecu_staus C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_vk_engine_ecu_staus_decode(const mavlink_message_t* msg, mavlink_vk_engine_ecu_staus_t* vk_engine_ecu_staus)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    vk_engine_ecu_staus->timestamp = mavlink_msg_vk_engine_ecu_staus_get_timestamp(msg);
+    vk_engine_ecu_staus->total_runtime = mavlink_msg_vk_engine_ecu_staus_get_total_runtime(msg);
+    vk_engine_ecu_staus->spd_rpm = mavlink_msg_vk_engine_ecu_staus_get_spd_rpm(msg);
+    vk_engine_ecu_staus->cylinderA_temp = mavlink_msg_vk_engine_ecu_staus_get_cylinderA_temp(msg);
+    vk_engine_ecu_staus->cylinderB_temp = mavlink_msg_vk_engine_ecu_staus_get_cylinderB_temp(msg);
+    vk_engine_ecu_staus->coolant_temp = mavlink_msg_vk_engine_ecu_staus_get_coolant_temp(msg);
+    vk_engine_ecu_staus->fuel_remain = mavlink_msg_vk_engine_ecu_staus_get_fuel_remain(msg);
+    vk_engine_ecu_staus->alarm = mavlink_msg_vk_engine_ecu_staus_get_alarm(msg);
+    vk_engine_ecu_staus->runtime = mavlink_msg_vk_engine_ecu_staus_get_runtime(msg);
+    vk_engine_ecu_staus->service_time = mavlink_msg_vk_engine_ecu_staus_get_service_time(msg);
+    vk_engine_ecu_staus->output_volt = mavlink_msg_vk_engine_ecu_staus_get_output_volt(msg);
+    vk_engine_ecu_staus->output_curr = mavlink_msg_vk_engine_ecu_staus_get_output_curr(msg);
+    vk_engine_ecu_staus->thr_pos = mavlink_msg_vk_engine_ecu_staus_get_thr_pos(msg);
+    vk_engine_ecu_staus->fuel_pos = mavlink_msg_vk_engine_ecu_staus_get_fuel_pos(msg);
+    vk_engine_ecu_staus->fault = mavlink_msg_vk_engine_ecu_staus_get_fault(msg);
+    vk_engine_ecu_staus->engine_state = mavlink_msg_vk_engine_ecu_staus_get_engine_state(msg);
+    vk_engine_ecu_staus->index = mavlink_msg_vk_engine_ecu_staus_get_index(msg);
+    mavlink_msg_vk_engine_ecu_staus_get_reserve(msg, vk_engine_ecu_staus->reserve);
+#else
+        uint8_t len = msg->len < MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_LEN? msg->len : MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_LEN;
+        memset(vk_engine_ecu_staus, 0, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_LEN);
+    memcpy(vk_engine_ecu_staus, _MAV_PAYLOAD(msg), len);
+#endif
+}

+ 624 - 0
v2.0/VKFly/mavlink_msg_vk_formation_leader.h

@@ -0,0 +1,624 @@
+#pragma once
+// MESSAGE VK_FORMATION_LEADER PACKING
+
+#define MAVLINK_MSG_ID_VK_FORMATION_LEADER 53004
+
+
+typedef struct __mavlink_vk_formation_leader_t {
+ uint32_t timestamp; /*< [ms] Timestamp in ms from system boot.*/
+ uint32_t state; /*<  formation leader drone state bitmap*/
+ int32_t lat; /*< [degE7] formation leader latitude in 1e-7deg */
+ int32_t lon; /*< [degE7] formation leader longitude in 1e-7deg*/
+ float msl; /*< [m] formation leader msl altitude in meter*/
+ float ve; /*< [m/s] formation leader east speed*/
+ float vn; /*< [m/s] formation leader north speed*/
+ float vu; /*< [m/s] formation leader up speed*/
+ float yaw; /*< [deg] formation leader yaw*/
+ int16_t x_dist; /*< [cm] distance between drones in x axis*/
+ int16_t y_dist; /*< [cm] distance between drones in y axis*/
+ int16_t z_dist; /*< [cm] distance between drones in z axis*/
+ uint16_t rect_col_num; /*<  columns number of rectangle formation*/
+ uint8_t formation_type; /*<  formation type*/
+} mavlink_vk_formation_leader_t;
+
+#define MAVLINK_MSG_ID_VK_FORMATION_LEADER_LEN 45
+#define MAVLINK_MSG_ID_VK_FORMATION_LEADER_MIN_LEN 45
+#define MAVLINK_MSG_ID_53004_LEN 45
+#define MAVLINK_MSG_ID_53004_MIN_LEN 45
+
+#define MAVLINK_MSG_ID_VK_FORMATION_LEADER_CRC 219
+#define MAVLINK_MSG_ID_53004_CRC 219
+
+
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_VK_FORMATION_LEADER { \
+    53004, \
+    "VK_FORMATION_LEADER", \
+    14, \
+    {  { "timestamp", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_vk_formation_leader_t, timestamp) }, \
+         { "state", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_vk_formation_leader_t, state) }, \
+         { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_vk_formation_leader_t, lat) }, \
+         { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_vk_formation_leader_t, lon) }, \
+         { "msl", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_vk_formation_leader_t, msl) }, \
+         { "ve", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_vk_formation_leader_t, ve) }, \
+         { "vn", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_vk_formation_leader_t, vn) }, \
+         { "vu", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_vk_formation_leader_t, vu) }, \
+         { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_vk_formation_leader_t, yaw) }, \
+         { "formation_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 44, offsetof(mavlink_vk_formation_leader_t, formation_type) }, \
+         { "x_dist", NULL, MAVLINK_TYPE_INT16_T, 0, 36, offsetof(mavlink_vk_formation_leader_t, x_dist) }, \
+         { "y_dist", NULL, MAVLINK_TYPE_INT16_T, 0, 38, offsetof(mavlink_vk_formation_leader_t, y_dist) }, \
+         { "z_dist", NULL, MAVLINK_TYPE_INT16_T, 0, 40, offsetof(mavlink_vk_formation_leader_t, z_dist) }, \
+         { "rect_col_num", NULL, MAVLINK_TYPE_UINT16_T, 0, 42, offsetof(mavlink_vk_formation_leader_t, rect_col_num) }, \
+         } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_VK_FORMATION_LEADER { \
+    "VK_FORMATION_LEADER", \
+    14, \
+    {  { "timestamp", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_vk_formation_leader_t, timestamp) }, \
+         { "state", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_vk_formation_leader_t, state) }, \
+         { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_vk_formation_leader_t, lat) }, \
+         { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_vk_formation_leader_t, lon) }, \
+         { "msl", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_vk_formation_leader_t, msl) }, \
+         { "ve", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_vk_formation_leader_t, ve) }, \
+         { "vn", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_vk_formation_leader_t, vn) }, \
+         { "vu", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_vk_formation_leader_t, vu) }, \
+         { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_vk_formation_leader_t, yaw) }, \
+         { "formation_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 44, offsetof(mavlink_vk_formation_leader_t, formation_type) }, \
+         { "x_dist", NULL, MAVLINK_TYPE_INT16_T, 0, 36, offsetof(mavlink_vk_formation_leader_t, x_dist) }, \
+         { "y_dist", NULL, MAVLINK_TYPE_INT16_T, 0, 38, offsetof(mavlink_vk_formation_leader_t, y_dist) }, \
+         { "z_dist", NULL, MAVLINK_TYPE_INT16_T, 0, 40, offsetof(mavlink_vk_formation_leader_t, z_dist) }, \
+         { "rect_col_num", NULL, MAVLINK_TYPE_UINT16_T, 0, 42, offsetof(mavlink_vk_formation_leader_t, rect_col_num) }, \
+         } \
+}
+#endif
+
+/**
+ * @brief Pack a vk_formation_leader 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 timestamp [ms] Timestamp in ms from system boot.
+ * @param state  formation leader drone state bitmap
+ * @param lat [degE7] formation leader latitude in 1e-7deg 
+ * @param lon [degE7] formation leader longitude in 1e-7deg
+ * @param msl [m] formation leader msl altitude in meter
+ * @param ve [m/s] formation leader east speed
+ * @param vn [m/s] formation leader north speed
+ * @param vu [m/s] formation leader up speed
+ * @param yaw [deg] formation leader yaw
+ * @param formation_type  formation type
+ * @param x_dist [cm] distance between drones in x axis
+ * @param y_dist [cm] distance between drones in y axis
+ * @param z_dist [cm] distance between drones in z axis
+ * @param rect_col_num  columns number of rectangle formation
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_vk_formation_leader_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+                               uint32_t timestamp, uint32_t state, int32_t lat, int32_t lon, float msl, float ve, float vn, float vu, float yaw, uint8_t formation_type, int16_t x_dist, int16_t y_dist, int16_t z_dist, uint16_t rect_col_num)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_VK_FORMATION_LEADER_LEN];
+    _mav_put_uint32_t(buf, 0, timestamp);
+    _mav_put_uint32_t(buf, 4, state);
+    _mav_put_int32_t(buf, 8, lat);
+    _mav_put_int32_t(buf, 12, lon);
+    _mav_put_float(buf, 16, msl);
+    _mav_put_float(buf, 20, ve);
+    _mav_put_float(buf, 24, vn);
+    _mav_put_float(buf, 28, vu);
+    _mav_put_float(buf, 32, yaw);
+    _mav_put_int16_t(buf, 36, x_dist);
+    _mav_put_int16_t(buf, 38, y_dist);
+    _mav_put_int16_t(buf, 40, z_dist);
+    _mav_put_uint16_t(buf, 42, rect_col_num);
+    _mav_put_uint8_t(buf, 44, formation_type);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VK_FORMATION_LEADER_LEN);
+#else
+    mavlink_vk_formation_leader_t packet;
+    packet.timestamp = timestamp;
+    packet.state = state;
+    packet.lat = lat;
+    packet.lon = lon;
+    packet.msl = msl;
+    packet.ve = ve;
+    packet.vn = vn;
+    packet.vu = vu;
+    packet.yaw = yaw;
+    packet.x_dist = x_dist;
+    packet.y_dist = y_dist;
+    packet.z_dist = z_dist;
+    packet.rect_col_num = rect_col_num;
+    packet.formation_type = formation_type;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VK_FORMATION_LEADER_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_VK_FORMATION_LEADER;
+    return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_VK_FORMATION_LEADER_MIN_LEN, MAVLINK_MSG_ID_VK_FORMATION_LEADER_LEN, MAVLINK_MSG_ID_VK_FORMATION_LEADER_CRC);
+}
+
+/**
+ * @brief Pack a vk_formation_leader 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 timestamp [ms] Timestamp in ms from system boot.
+ * @param state  formation leader drone state bitmap
+ * @param lat [degE7] formation leader latitude in 1e-7deg 
+ * @param lon [degE7] formation leader longitude in 1e-7deg
+ * @param msl [m] formation leader msl altitude in meter
+ * @param ve [m/s] formation leader east speed
+ * @param vn [m/s] formation leader north speed
+ * @param vu [m/s] formation leader up speed
+ * @param yaw [deg] formation leader yaw
+ * @param formation_type  formation type
+ * @param x_dist [cm] distance between drones in x axis
+ * @param y_dist [cm] distance between drones in y axis
+ * @param z_dist [cm] distance between drones in z axis
+ * @param rect_col_num  columns number of rectangle formation
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_vk_formation_leader_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+                               uint32_t timestamp, uint32_t state, int32_t lat, int32_t lon, float msl, float ve, float vn, float vu, float yaw, uint8_t formation_type, int16_t x_dist, int16_t y_dist, int16_t z_dist, uint16_t rect_col_num)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_VK_FORMATION_LEADER_LEN];
+    _mav_put_uint32_t(buf, 0, timestamp);
+    _mav_put_uint32_t(buf, 4, state);
+    _mav_put_int32_t(buf, 8, lat);
+    _mav_put_int32_t(buf, 12, lon);
+    _mav_put_float(buf, 16, msl);
+    _mav_put_float(buf, 20, ve);
+    _mav_put_float(buf, 24, vn);
+    _mav_put_float(buf, 28, vu);
+    _mav_put_float(buf, 32, yaw);
+    _mav_put_int16_t(buf, 36, x_dist);
+    _mav_put_int16_t(buf, 38, y_dist);
+    _mav_put_int16_t(buf, 40, z_dist);
+    _mav_put_uint16_t(buf, 42, rect_col_num);
+    _mav_put_uint8_t(buf, 44, formation_type);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VK_FORMATION_LEADER_LEN);
+#else
+    mavlink_vk_formation_leader_t packet;
+    packet.timestamp = timestamp;
+    packet.state = state;
+    packet.lat = lat;
+    packet.lon = lon;
+    packet.msl = msl;
+    packet.ve = ve;
+    packet.vn = vn;
+    packet.vu = vu;
+    packet.yaw = yaw;
+    packet.x_dist = x_dist;
+    packet.y_dist = y_dist;
+    packet.z_dist = z_dist;
+    packet.rect_col_num = rect_col_num;
+    packet.formation_type = formation_type;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VK_FORMATION_LEADER_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_VK_FORMATION_LEADER;
+#if MAVLINK_CRC_EXTRA
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_VK_FORMATION_LEADER_MIN_LEN, MAVLINK_MSG_ID_VK_FORMATION_LEADER_LEN, MAVLINK_MSG_ID_VK_FORMATION_LEADER_CRC);
+#else
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_VK_FORMATION_LEADER_MIN_LEN, MAVLINK_MSG_ID_VK_FORMATION_LEADER_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a vk_formation_leader 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 timestamp [ms] Timestamp in ms from system boot.
+ * @param state  formation leader drone state bitmap
+ * @param lat [degE7] formation leader latitude in 1e-7deg 
+ * @param lon [degE7] formation leader longitude in 1e-7deg
+ * @param msl [m] formation leader msl altitude in meter
+ * @param ve [m/s] formation leader east speed
+ * @param vn [m/s] formation leader north speed
+ * @param vu [m/s] formation leader up speed
+ * @param yaw [deg] formation leader yaw
+ * @param formation_type  formation type
+ * @param x_dist [cm] distance between drones in x axis
+ * @param y_dist [cm] distance between drones in y axis
+ * @param z_dist [cm] distance between drones in z axis
+ * @param rect_col_num  columns number of rectangle formation
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_vk_formation_leader_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+                               mavlink_message_t* msg,
+                                   uint32_t timestamp,uint32_t state,int32_t lat,int32_t lon,float msl,float ve,float vn,float vu,float yaw,uint8_t formation_type,int16_t x_dist,int16_t y_dist,int16_t z_dist,uint16_t rect_col_num)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_VK_FORMATION_LEADER_LEN];
+    _mav_put_uint32_t(buf, 0, timestamp);
+    _mav_put_uint32_t(buf, 4, state);
+    _mav_put_int32_t(buf, 8, lat);
+    _mav_put_int32_t(buf, 12, lon);
+    _mav_put_float(buf, 16, msl);
+    _mav_put_float(buf, 20, ve);
+    _mav_put_float(buf, 24, vn);
+    _mav_put_float(buf, 28, vu);
+    _mav_put_float(buf, 32, yaw);
+    _mav_put_int16_t(buf, 36, x_dist);
+    _mav_put_int16_t(buf, 38, y_dist);
+    _mav_put_int16_t(buf, 40, z_dist);
+    _mav_put_uint16_t(buf, 42, rect_col_num);
+    _mav_put_uint8_t(buf, 44, formation_type);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VK_FORMATION_LEADER_LEN);
+#else
+    mavlink_vk_formation_leader_t packet;
+    packet.timestamp = timestamp;
+    packet.state = state;
+    packet.lat = lat;
+    packet.lon = lon;
+    packet.msl = msl;
+    packet.ve = ve;
+    packet.vn = vn;
+    packet.vu = vu;
+    packet.yaw = yaw;
+    packet.x_dist = x_dist;
+    packet.y_dist = y_dist;
+    packet.z_dist = z_dist;
+    packet.rect_col_num = rect_col_num;
+    packet.formation_type = formation_type;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VK_FORMATION_LEADER_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_VK_FORMATION_LEADER;
+    return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_VK_FORMATION_LEADER_MIN_LEN, MAVLINK_MSG_ID_VK_FORMATION_LEADER_LEN, MAVLINK_MSG_ID_VK_FORMATION_LEADER_CRC);
+}
+
+/**
+ * @brief Encode a vk_formation_leader 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_formation_leader C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_vk_formation_leader_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_vk_formation_leader_t* vk_formation_leader)
+{
+    return mavlink_msg_vk_formation_leader_pack(system_id, component_id, msg, vk_formation_leader->timestamp, vk_formation_leader->state, vk_formation_leader->lat, vk_formation_leader->lon, vk_formation_leader->msl, vk_formation_leader->ve, vk_formation_leader->vn, vk_formation_leader->vu, vk_formation_leader->yaw, vk_formation_leader->formation_type, vk_formation_leader->x_dist, vk_formation_leader->y_dist, vk_formation_leader->z_dist, vk_formation_leader->rect_col_num);
+}
+
+/**
+ * @brief Encode a vk_formation_leader 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_formation_leader C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_vk_formation_leader_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_vk_formation_leader_t* vk_formation_leader)
+{
+    return mavlink_msg_vk_formation_leader_pack_chan(system_id, component_id, chan, msg, vk_formation_leader->timestamp, vk_formation_leader->state, vk_formation_leader->lat, vk_formation_leader->lon, vk_formation_leader->msl, vk_formation_leader->ve, vk_formation_leader->vn, vk_formation_leader->vu, vk_formation_leader->yaw, vk_formation_leader->formation_type, vk_formation_leader->x_dist, vk_formation_leader->y_dist, vk_formation_leader->z_dist, vk_formation_leader->rect_col_num);
+}
+
+/**
+ * @brief Encode a vk_formation_leader 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_formation_leader C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_vk_formation_leader_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_vk_formation_leader_t* vk_formation_leader)
+{
+    return mavlink_msg_vk_formation_leader_pack_status(system_id, component_id, _status, msg,  vk_formation_leader->timestamp, vk_formation_leader->state, vk_formation_leader->lat, vk_formation_leader->lon, vk_formation_leader->msl, vk_formation_leader->ve, vk_formation_leader->vn, vk_formation_leader->vu, vk_formation_leader->yaw, vk_formation_leader->formation_type, vk_formation_leader->x_dist, vk_formation_leader->y_dist, vk_formation_leader->z_dist, vk_formation_leader->rect_col_num);
+}
+
+/**
+ * @brief Send a vk_formation_leader message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param timestamp [ms] Timestamp in ms from system boot.
+ * @param state  formation leader drone state bitmap
+ * @param lat [degE7] formation leader latitude in 1e-7deg 
+ * @param lon [degE7] formation leader longitude in 1e-7deg
+ * @param msl [m] formation leader msl altitude in meter
+ * @param ve [m/s] formation leader east speed
+ * @param vn [m/s] formation leader north speed
+ * @param vu [m/s] formation leader up speed
+ * @param yaw [deg] formation leader yaw
+ * @param formation_type  formation type
+ * @param x_dist [cm] distance between drones in x axis
+ * @param y_dist [cm] distance between drones in y axis
+ * @param z_dist [cm] distance between drones in z axis
+ * @param rect_col_num  columns number of rectangle formation
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_vk_formation_leader_send(mavlink_channel_t chan, uint32_t timestamp, uint32_t state, int32_t lat, int32_t lon, float msl, float ve, float vn, float vu, float yaw, uint8_t formation_type, int16_t x_dist, int16_t y_dist, int16_t z_dist, uint16_t rect_col_num)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_VK_FORMATION_LEADER_LEN];
+    _mav_put_uint32_t(buf, 0, timestamp);
+    _mav_put_uint32_t(buf, 4, state);
+    _mav_put_int32_t(buf, 8, lat);
+    _mav_put_int32_t(buf, 12, lon);
+    _mav_put_float(buf, 16, msl);
+    _mav_put_float(buf, 20, ve);
+    _mav_put_float(buf, 24, vn);
+    _mav_put_float(buf, 28, vu);
+    _mav_put_float(buf, 32, yaw);
+    _mav_put_int16_t(buf, 36, x_dist);
+    _mav_put_int16_t(buf, 38, y_dist);
+    _mav_put_int16_t(buf, 40, z_dist);
+    _mav_put_uint16_t(buf, 42, rect_col_num);
+    _mav_put_uint8_t(buf, 44, formation_type);
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VK_FORMATION_LEADER, buf, MAVLINK_MSG_ID_VK_FORMATION_LEADER_MIN_LEN, MAVLINK_MSG_ID_VK_FORMATION_LEADER_LEN, MAVLINK_MSG_ID_VK_FORMATION_LEADER_CRC);
+#else
+    mavlink_vk_formation_leader_t packet;
+    packet.timestamp = timestamp;
+    packet.state = state;
+    packet.lat = lat;
+    packet.lon = lon;
+    packet.msl = msl;
+    packet.ve = ve;
+    packet.vn = vn;
+    packet.vu = vu;
+    packet.yaw = yaw;
+    packet.x_dist = x_dist;
+    packet.y_dist = y_dist;
+    packet.z_dist = z_dist;
+    packet.rect_col_num = rect_col_num;
+    packet.formation_type = formation_type;
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VK_FORMATION_LEADER, (const char *)&packet, MAVLINK_MSG_ID_VK_FORMATION_LEADER_MIN_LEN, MAVLINK_MSG_ID_VK_FORMATION_LEADER_LEN, MAVLINK_MSG_ID_VK_FORMATION_LEADER_CRC);
+#endif
+}
+
+/**
+ * @brief Send a vk_formation_leader message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_vk_formation_leader_send_struct(mavlink_channel_t chan, const mavlink_vk_formation_leader_t* vk_formation_leader)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    mavlink_msg_vk_formation_leader_send(chan, vk_formation_leader->timestamp, vk_formation_leader->state, vk_formation_leader->lat, vk_formation_leader->lon, vk_formation_leader->msl, vk_formation_leader->ve, vk_formation_leader->vn, vk_formation_leader->vu, vk_formation_leader->yaw, vk_formation_leader->formation_type, vk_formation_leader->x_dist, vk_formation_leader->y_dist, vk_formation_leader->z_dist, vk_formation_leader->rect_col_num);
+#else
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VK_FORMATION_LEADER, (const char *)vk_formation_leader, MAVLINK_MSG_ID_VK_FORMATION_LEADER_MIN_LEN, MAVLINK_MSG_ID_VK_FORMATION_LEADER_LEN, MAVLINK_MSG_ID_VK_FORMATION_LEADER_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_VK_FORMATION_LEADER_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_formation_leader_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint32_t timestamp, uint32_t state, int32_t lat, int32_t lon, float msl, float ve, float vn, float vu, float yaw, uint8_t formation_type, int16_t x_dist, int16_t y_dist, int16_t z_dist, uint16_t rect_col_num)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char *buf = (char *)msgbuf;
+    _mav_put_uint32_t(buf, 0, timestamp);
+    _mav_put_uint32_t(buf, 4, state);
+    _mav_put_int32_t(buf, 8, lat);
+    _mav_put_int32_t(buf, 12, lon);
+    _mav_put_float(buf, 16, msl);
+    _mav_put_float(buf, 20, ve);
+    _mav_put_float(buf, 24, vn);
+    _mav_put_float(buf, 28, vu);
+    _mav_put_float(buf, 32, yaw);
+    _mav_put_int16_t(buf, 36, x_dist);
+    _mav_put_int16_t(buf, 38, y_dist);
+    _mav_put_int16_t(buf, 40, z_dist);
+    _mav_put_uint16_t(buf, 42, rect_col_num);
+    _mav_put_uint8_t(buf, 44, formation_type);
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VK_FORMATION_LEADER, buf, MAVLINK_MSG_ID_VK_FORMATION_LEADER_MIN_LEN, MAVLINK_MSG_ID_VK_FORMATION_LEADER_LEN, MAVLINK_MSG_ID_VK_FORMATION_LEADER_CRC);
+#else
+    mavlink_vk_formation_leader_t *packet = (mavlink_vk_formation_leader_t *)msgbuf;
+    packet->timestamp = timestamp;
+    packet->state = state;
+    packet->lat = lat;
+    packet->lon = lon;
+    packet->msl = msl;
+    packet->ve = ve;
+    packet->vn = vn;
+    packet->vu = vu;
+    packet->yaw = yaw;
+    packet->x_dist = x_dist;
+    packet->y_dist = y_dist;
+    packet->z_dist = z_dist;
+    packet->rect_col_num = rect_col_num;
+    packet->formation_type = formation_type;
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VK_FORMATION_LEADER, (const char *)packet, MAVLINK_MSG_ID_VK_FORMATION_LEADER_MIN_LEN, MAVLINK_MSG_ID_VK_FORMATION_LEADER_LEN, MAVLINK_MSG_ID_VK_FORMATION_LEADER_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE VK_FORMATION_LEADER UNPACKING
+
+
+/**
+ * @brief Get field timestamp from vk_formation_leader message
+ *
+ * @return [ms] Timestamp in ms from system boot.
+ */
+static inline uint32_t mavlink_msg_vk_formation_leader_get_timestamp(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint32_t(msg,  0);
+}
+
+/**
+ * @brief Get field state from vk_formation_leader message
+ *
+ * @return  formation leader drone state bitmap
+ */
+static inline uint32_t mavlink_msg_vk_formation_leader_get_state(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint32_t(msg,  4);
+}
+
+/**
+ * @brief Get field lat from vk_formation_leader message
+ *
+ * @return [degE7] formation leader latitude in 1e-7deg 
+ */
+static inline int32_t mavlink_msg_vk_formation_leader_get_lat(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_int32_t(msg,  8);
+}
+
+/**
+ * @brief Get field lon from vk_formation_leader message
+ *
+ * @return [degE7] formation leader longitude in 1e-7deg
+ */
+static inline int32_t mavlink_msg_vk_formation_leader_get_lon(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_int32_t(msg,  12);
+}
+
+/**
+ * @brief Get field msl from vk_formation_leader message
+ *
+ * @return [m] formation leader msl altitude in meter
+ */
+static inline float mavlink_msg_vk_formation_leader_get_msl(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_float(msg,  16);
+}
+
+/**
+ * @brief Get field ve from vk_formation_leader message
+ *
+ * @return [m/s] formation leader east speed
+ */
+static inline float mavlink_msg_vk_formation_leader_get_ve(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_float(msg,  20);
+}
+
+/**
+ * @brief Get field vn from vk_formation_leader message
+ *
+ * @return [m/s] formation leader north speed
+ */
+static inline float mavlink_msg_vk_formation_leader_get_vn(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_float(msg,  24);
+}
+
+/**
+ * @brief Get field vu from vk_formation_leader message
+ *
+ * @return [m/s] formation leader up speed
+ */
+static inline float mavlink_msg_vk_formation_leader_get_vu(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_float(msg,  28);
+}
+
+/**
+ * @brief Get field yaw from vk_formation_leader message
+ *
+ * @return [deg] formation leader yaw
+ */
+static inline float mavlink_msg_vk_formation_leader_get_yaw(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_float(msg,  32);
+}
+
+/**
+ * @brief Get field formation_type from vk_formation_leader message
+ *
+ * @return  formation type
+ */
+static inline uint8_t mavlink_msg_vk_formation_leader_get_formation_type(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint8_t(msg,  44);
+}
+
+/**
+ * @brief Get field x_dist from vk_formation_leader message
+ *
+ * @return [cm] distance between drones in x axis
+ */
+static inline int16_t mavlink_msg_vk_formation_leader_get_x_dist(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_int16_t(msg,  36);
+}
+
+/**
+ * @brief Get field y_dist from vk_formation_leader message
+ *
+ * @return [cm] distance between drones in y axis
+ */
+static inline int16_t mavlink_msg_vk_formation_leader_get_y_dist(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_int16_t(msg,  38);
+}
+
+/**
+ * @brief Get field z_dist from vk_formation_leader message
+ *
+ * @return [cm] distance between drones in z axis
+ */
+static inline int16_t mavlink_msg_vk_formation_leader_get_z_dist(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_int16_t(msg,  40);
+}
+
+/**
+ * @brief Get field rect_col_num from vk_formation_leader message
+ *
+ * @return  columns number of rectangle formation
+ */
+static inline uint16_t mavlink_msg_vk_formation_leader_get_rect_col_num(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint16_t(msg,  42);
+}
+
+/**
+ * @brief Decode a vk_formation_leader message into a struct
+ *
+ * @param msg The message to decode
+ * @param vk_formation_leader C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_vk_formation_leader_decode(const mavlink_message_t* msg, mavlink_vk_formation_leader_t* vk_formation_leader)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    vk_formation_leader->timestamp = mavlink_msg_vk_formation_leader_get_timestamp(msg);
+    vk_formation_leader->state = mavlink_msg_vk_formation_leader_get_state(msg);
+    vk_formation_leader->lat = mavlink_msg_vk_formation_leader_get_lat(msg);
+    vk_formation_leader->lon = mavlink_msg_vk_formation_leader_get_lon(msg);
+    vk_formation_leader->msl = mavlink_msg_vk_formation_leader_get_msl(msg);
+    vk_formation_leader->ve = mavlink_msg_vk_formation_leader_get_ve(msg);
+    vk_formation_leader->vn = mavlink_msg_vk_formation_leader_get_vn(msg);
+    vk_formation_leader->vu = mavlink_msg_vk_formation_leader_get_vu(msg);
+    vk_formation_leader->yaw = mavlink_msg_vk_formation_leader_get_yaw(msg);
+    vk_formation_leader->x_dist = mavlink_msg_vk_formation_leader_get_x_dist(msg);
+    vk_formation_leader->y_dist = mavlink_msg_vk_formation_leader_get_y_dist(msg);
+    vk_formation_leader->z_dist = mavlink_msg_vk_formation_leader_get_z_dist(msg);
+    vk_formation_leader->rect_col_num = mavlink_msg_vk_formation_leader_get_rect_col_num(msg);
+    vk_formation_leader->formation_type = mavlink_msg_vk_formation_leader_get_formation_type(msg);
+#else
+        uint8_t len = msg->len < MAVLINK_MSG_ID_VK_FORMATION_LEADER_LEN? msg->len : MAVLINK_MSG_ID_VK_FORMATION_LEADER_LEN;
+        memset(vk_formation_leader, 0, MAVLINK_MSG_ID_VK_FORMATION_LEADER_LEN);
+    memcpy(vk_formation_leader, _MAV_PAYLOAD(msg), len);
+#endif
+}

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

@@ -301,6 +301,154 @@ static void mavlink_test_vk_bms_status(uint8_t system_id, uint8_t component_id,
 #endif
 }
 
+static void mavlink_test_vk_formation_leader(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_FORMATION_LEADER >= 256) {
+            return;
+        }
+#endif
+    mavlink_message_t msg;
+        uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+        uint16_t i;
+    mavlink_vk_formation_leader_t packet_in = {
+        963497464,963497672,963497880,963498088,129.0,157.0,185.0,213.0,241.0,19107,19211,19315,19419,137
+    };
+    mavlink_vk_formation_leader_t packet1, packet2;
+        memset(&packet1, 0, sizeof(packet1));
+        packet1.timestamp = packet_in.timestamp;
+        packet1.state = packet_in.state;
+        packet1.lat = packet_in.lat;
+        packet1.lon = packet_in.lon;
+        packet1.msl = packet_in.msl;
+        packet1.ve = packet_in.ve;
+        packet1.vn = packet_in.vn;
+        packet1.vu = packet_in.vu;
+        packet1.yaw = packet_in.yaw;
+        packet1.x_dist = packet_in.x_dist;
+        packet1.y_dist = packet_in.y_dist;
+        packet1.z_dist = packet_in.z_dist;
+        packet1.rect_col_num = packet_in.rect_col_num;
+        packet1.formation_type = packet_in.formation_type;
+        
+        
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+        if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+           // cope with extensions
+           memset(MAVLINK_MSG_ID_VK_FORMATION_LEADER_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_VK_FORMATION_LEADER_MIN_LEN);
+        }
+#endif
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_vk_formation_leader_encode(system_id, component_id, &msg, &packet1);
+    mavlink_msg_vk_formation_leader_decode(&msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_vk_formation_leader_pack(system_id, component_id, &msg , packet1.timestamp , packet1.state , packet1.lat , packet1.lon , packet1.msl , packet1.ve , packet1.vn , packet1.vu , packet1.yaw , packet1.formation_type , packet1.x_dist , packet1.y_dist , packet1.z_dist , packet1.rect_col_num );
+    mavlink_msg_vk_formation_leader_decode(&msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_vk_formation_leader_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.state , packet1.lat , packet1.lon , packet1.msl , packet1.ve , packet1.vn , packet1.vu , packet1.yaw , packet1.formation_type , packet1.x_dist , packet1.y_dist , packet1.z_dist , packet1.rect_col_num );
+    mavlink_msg_vk_formation_leader_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_formation_leader_decode(last_msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+        
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_vk_formation_leader_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.state , packet1.lat , packet1.lon , packet1.msl , packet1.ve , packet1.vn , packet1.vu , packet1.yaw , packet1.formation_type , packet1.x_dist , packet1.y_dist , packet1.z_dist , packet1.rect_col_num );
+    mavlink_msg_vk_formation_leader_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_FORMATION_LEADER") != NULL);
+    MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_VK_FORMATION_LEADER) != NULL);
+#endif
+}
+
+static void mavlink_test_vk_engine_ecu_staus(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_ENGINE_ECU_STAUS >= 256) {
+            return;
+        }
+#endif
+    mavlink_message_t msg;
+        uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+        uint16_t i;
+    mavlink_vk_engine_ecu_staus_t packet_in = {
+        963497464,963497672,17651,17755,17859,17963,18067,18171,18275,18379,18483,18587,89,156,223,34,101,{ 168, 169, 170, 171 }
+    };
+    mavlink_vk_engine_ecu_staus_t packet1, packet2;
+        memset(&packet1, 0, sizeof(packet1));
+        packet1.timestamp = packet_in.timestamp;
+        packet1.total_runtime = packet_in.total_runtime;
+        packet1.spd_rpm = packet_in.spd_rpm;
+        packet1.cylinderA_temp = packet_in.cylinderA_temp;
+        packet1.cylinderB_temp = packet_in.cylinderB_temp;
+        packet1.coolant_temp = packet_in.coolant_temp;
+        packet1.fuel_remain = packet_in.fuel_remain;
+        packet1.alarm = packet_in.alarm;
+        packet1.runtime = packet_in.runtime;
+        packet1.service_time = packet_in.service_time;
+        packet1.output_volt = packet_in.output_volt;
+        packet1.output_curr = packet_in.output_curr;
+        packet1.thr_pos = packet_in.thr_pos;
+        packet1.fuel_pos = packet_in.fuel_pos;
+        packet1.fault = packet_in.fault;
+        packet1.engine_state = packet_in.engine_state;
+        packet1.index = packet_in.index;
+        
+        mav_array_memcpy(packet1.reserve, packet_in.reserve, sizeof(uint8_t)*4);
+        
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+        if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+           // cope with extensions
+           memset(MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_MIN_LEN);
+        }
+#endif
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_vk_engine_ecu_staus_encode(system_id, component_id, &msg, &packet1);
+    mavlink_msg_vk_engine_ecu_staus_decode(&msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_vk_engine_ecu_staus_pack(system_id, component_id, &msg , packet1.timestamp , packet1.spd_rpm , packet1.thr_pos , packet1.fuel_pos , packet1.cylinderA_temp , packet1.cylinderB_temp , packet1.coolant_temp , packet1.fuel_remain , packet1.alarm , packet1.total_runtime , packet1.runtime , packet1.service_time , packet1.output_volt , packet1.output_curr , packet1.fault , packet1.engine_state , packet1.index , packet1.reserve );
+    mavlink_msg_vk_engine_ecu_staus_decode(&msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_vk_engine_ecu_staus_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.spd_rpm , packet1.thr_pos , packet1.fuel_pos , packet1.cylinderA_temp , packet1.cylinderB_temp , packet1.coolant_temp , packet1.fuel_remain , packet1.alarm , packet1.total_runtime , packet1.runtime , packet1.service_time , packet1.output_volt , packet1.output_curr , packet1.fault , packet1.engine_state , packet1.index , packet1.reserve );
+    mavlink_msg_vk_engine_ecu_staus_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_engine_ecu_staus_decode(last_msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+        
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_vk_engine_ecu_staus_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.spd_rpm , packet1.thr_pos , packet1.fuel_pos , packet1.cylinderA_temp , packet1.cylinderB_temp , packet1.coolant_temp , packet1.fuel_remain , packet1.alarm , packet1.total_runtime , packet1.runtime , packet1.service_time , packet1.output_volt , packet1.output_curr , packet1.fault , packet1.engine_state , packet1.index , packet1.reserve );
+    mavlink_msg_vk_engine_ecu_staus_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_ENGINE_ECU_STAUS") != NULL);
+    MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS) != NULL);
+#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
@@ -667,18 +815,92 @@ static void mavlink_test_vk_update_terminate(uint8_t system_id, uint8_t componen
 #endif
 }
 
+static void mavlink_test_qingxie_bms(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_QINGXIE_BMS >= 256) {
+            return;
+        }
+#endif
+    mavlink_message_t msg;
+        uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+        uint16_t i;
+    mavlink_qingxie_bms_t packet_in = {
+        17235,17339,17443,17547,17651,17755,17859,17963,18067,18171,18275,199,10
+    };
+    mavlink_qingxie_bms_t packet1, packet2;
+        memset(&packet1, 0, sizeof(packet1));
+        packet1.bat_voltage = packet_in.bat_voltage;
+        packet1.servo_current = packet_in.servo_current;
+        packet1.stack_voltage = packet_in.stack_voltage;
+        packet1.servo_voltage = packet_in.servo_voltage;
+        packet1.bat_refuel_current = packet_in.bat_refuel_current;
+        packet1.gas_tank_pressure = packet_in.gas_tank_pressure;
+        packet1.pipe_pressure = packet_in.pipe_pressure;
+        packet1.pcb_temp = packet_in.pcb_temp;
+        packet1.stack_temp = packet_in.stack_temp;
+        packet1.work_status = packet_in.work_status;
+        packet1.falt_status = packet_in.falt_status;
+        packet1.self_check = packet_in.self_check;
+        packet1.Id = packet_in.Id;
+        
+        
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+        if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+           // cope with extensions
+           memset(MAVLINK_MSG_ID_QINGXIE_BMS_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_QINGXIE_BMS_MIN_LEN);
+        }
+#endif
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_qingxie_bms_encode(system_id, component_id, &msg, &packet1);
+    mavlink_msg_qingxie_bms_decode(&msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_qingxie_bms_pack(system_id, component_id, &msg , packet1.bat_voltage , packet1.servo_current , packet1.stack_voltage , packet1.servo_voltage , packet1.bat_refuel_current , packet1.gas_tank_pressure , packet1.pipe_pressure , packet1.pcb_temp , packet1.stack_temp , packet1.work_status , packet1.falt_status , packet1.self_check , packet1.Id );
+    mavlink_msg_qingxie_bms_decode(&msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_qingxie_bms_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.bat_voltage , packet1.servo_current , packet1.stack_voltage , packet1.servo_voltage , packet1.bat_refuel_current , packet1.gas_tank_pressure , packet1.pipe_pressure , packet1.pcb_temp , packet1.stack_temp , packet1.work_status , packet1.falt_status , packet1.self_check , packet1.Id );
+    mavlink_msg_qingxie_bms_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_qingxie_bms_decode(last_msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+        
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_qingxie_bms_send(MAVLINK_COMM_1 , packet1.bat_voltage , packet1.servo_current , packet1.stack_voltage , packet1.servo_voltage , packet1.bat_refuel_current , packet1.gas_tank_pressure , packet1.pipe_pressure , packet1.pcb_temp , packet1.stack_temp , packet1.work_status , packet1.falt_status , packet1.self_check , packet1.Id );
+    mavlink_msg_qingxie_bms_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("QINGXIE_BMS") != NULL);
+    MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_QINGXIE_BMS) != NULL);
+#endif
+}
+
 static void mavlink_test_VKFly(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
 {
     mavlink_test_vkins_status(system_id, component_id, last_msg);
     mavlink_test_vkfmu_status(system_id, component_id, last_msg);
     mavlink_test_vk_roi_target(system_id, component_id, last_msg);
     mavlink_test_vk_bms_status(system_id, component_id, last_msg);
+    mavlink_test_vk_formation_leader(system_id, component_id, last_msg);
+    mavlink_test_vk_engine_ecu_staus(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);
     mavlink_test_vk_fw_update_data(system_id, component_id, last_msg);
     mavlink_test_vk_update_terminate(system_id, component_id, last_msg);
+    mavlink_test_qingxie_bms(system_id, component_id, last_msg);
 }
 
 #ifdef __cplusplus

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

@@ -7,7 +7,7 @@
 #ifndef MAVLINK_VERSION_H
 #define MAVLINK_VERSION_H
 
-#define MAVLINK_BUILD_DATE "Fri Sep 20 2024"
+#define MAVLINK_BUILD_DATE "Thu Oct 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 -4195061038551433624
+#define MAVLINK_COMMON_XML_HASH -447032916152566987
 
 #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 -4195061038551433624
+#define MAVLINK_PRIMARY_XML_HASH -447032916152566987
 
 #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 "Fri Sep 20 2024"
+#define MAVLINK_BUILD_DATE "Thu Oct 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 1477761769770448604
+#define MAVLINK_PRIMARY_XML_HASH -8051468545453087379
 
 #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 1477761769770448604
+#define MAVLINK_MINIMAL_XML_HASH -8051468545453087379
 
 #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 "Fri Sep 20 2024"
+#define MAVLINK_BUILD_DATE "Thu Oct 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 2084718673588589710
+#define MAVLINK_PRIMARY_XML_HASH -3977686896628553582
 
 #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 2084718673588589710
+#define MAVLINK_STANDARD_XML_HASH -3977686896628553582
 
 #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 "Fri Sep 20 2024"
+#define MAVLINK_BUILD_DATE "Thu Oct 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