Explorar o código

增加 VK_DIGI_ESC_STATUS 消息

Liu Yang hai 6 meses
pai
achega
95228390f9

+ 14 - 1
msg_definitions/VKFly.xml

@@ -839,6 +839,19 @@
       <field type="uint8_t" name="reserved">reserved</field>
     </message>
 
+    <message id="53008" name="VK_DIGI_ESC_STATUS">
+      <description>Mosaic_h gps raw data</description>
+      <field type="uint8_t" name="index" instance="true">Index of the first ESC in this message.
+        minValue = 0, maxValue = 60, increment = 4.</field>
+      <field type="uint32_t" name="timestamp" units="ms">Timestamp from system boot.</field>
+      <field type="int32_t[4]" name="rpm" units="rpm">Reported motor RPM from each ESC (negative for
+        reverse rotation).</field>
+      <field type="float[4]" name="voltage" units="V">Voltage measured from each ESC.</field>
+      <field type="float[4]" name="current" units="A">Current measured from each ESC.</field>
+      <field type="int16_t[4]" name="temperature" units="degC">Temperature measured from each ESC.</field>
+      <field type="uint32_t[4]" name="status">Status data from each ESC.</field>
+    </message>
+
     <message id="53020" name="VK_PARACHUTE_STATUS">
       <description>parachute status</description>
       <field type="uint32_t" name="timestamp" units="ms">timestamp from system boot</field>
@@ -907,4 +920,4 @@
 
   </messages>
 
-</mavlink>
+</mavlink>

+ 16 - 1
readme.md

@@ -30,7 +30,7 @@ typedef enum VKFLY_AP_TYPE
     VKFLY_AP_TYPE_4X8DR=86, /* 4轴8桨*/
     VKFLY_AP_TYPE_6I12=121, /* 6轴12桨, 十字布局 */
     VKFLY_AP_TYPE_6X12=122, /* 6轴12桨, X字布局 */
-    VKFLY_AP_TYPE_6X12=123, /* 6轴12桨, H字布局 */
+    VKFLY_AP_TYPE_6H12=123, /* 6轴12桨, H字布局 */
     VKFLY_AP_TYPE_8I16=161, /* 8轴16桨, 十字布局 */
     VKFLY_AP_TYPE_8X16=162, /* 8轴16桨, X字布局 */
     VKFLY_AP_TYPE_ENUM_END=163, /*  | */
@@ -797,6 +797,21 @@ LOCAL 定位信息
 | work_state | 工作状态             |
 | err_code   | 称重器故障码         |
 
+### 2.25 电调状态数据 VK_DIGI_ESC_STATUS
+
+当有数字电调设备数据接入后, 飞控自动周期向地面站发送此消息. 每4个电调作为一组发送一帧, 通过index字段区分.
+
+| 字段           | 说明                                                                       |
+| -------------- | -------------------------------------------------------------------------- |
+| timestamp      | 毫秒时间戳   ms                                                            |
+| index          | 本组第一个电调索引序号, 自增4. (第一组为0, 第二组为4, 第三组为8, 依次类推) |
+| rpm[4]         | 转速 1rpm                                                                  |
+| voltage[4]     | 电压 V                                                                     |
+| current[4]     | 电流 A                                                                     |
+| temperature[4] | 温度 degC                                                                  |
+| status[4]      | 状态字 (不同品牌型号有不同的状态定义)                                      |
+
+
 ## 3 参数设置
 
 飞控的参数修改、读取方法参考 [mavlink services parameter](https://mavlink.io/en/services/parameter.html). 使用16字节的 paramid 作为每各参数的唯一表示码.

A diferenza do arquivo foi suprimida porque é demasiado grande
+ 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 -20221784796664669
+#define MAVLINK_PRIMARY_XML_HASH 215163825287409684
 
 #ifndef MAVLINK_STX
 #define MAVLINK_STX 253

+ 0 - 428
v2.0/VKFly/mavlink_msg_vk_bms_info.h

@@ -1,428 +0,0 @@
-#pragma once
-// MESSAGE VK_BMS_INFO PACKING
-
-#define MAVLINK_MSG_ID_VK_BMS_INFO 53004
-
-
-typedef struct __mavlink_vk_bms_info_t {
- uint32_t time_boot_ms; /*< [ms] Timestamp in ms from system boot.*/
- uint16_t cyc_cnt; /*<  BMS change and discharge
-        cycle times*/
- uint8_t man_name[20]; /*<  BMS manufactor string*/
- uint8_t model_name[20]; /*<  BMS equpment model name string*/
- uint8_t sn_id[20]; /*<  BMS SN id string*/
- uint8_t hw_ver[10]; /*<  BMS hardware version string*/
- uint8_t fw_ver[10]; /*<  BMS firmware version string*/
-} mavlink_vk_bms_info_t;
-
-#define MAVLINK_MSG_ID_VK_BMS_INFO_LEN 86
-#define MAVLINK_MSG_ID_VK_BMS_INFO_MIN_LEN 86
-#define MAVLINK_MSG_ID_53004_LEN 86
-#define MAVLINK_MSG_ID_53004_MIN_LEN 86
-
-#define MAVLINK_MSG_ID_VK_BMS_INFO_CRC 3
-#define MAVLINK_MSG_ID_53004_CRC 3
-
-#define MAVLINK_MSG_VK_BMS_INFO_FIELD_MAN_NAME_LEN 20
-#define MAVLINK_MSG_VK_BMS_INFO_FIELD_MODEL_NAME_LEN 20
-#define MAVLINK_MSG_VK_BMS_INFO_FIELD_SN_ID_LEN 20
-#define MAVLINK_MSG_VK_BMS_INFO_FIELD_HW_VER_LEN 10
-#define MAVLINK_MSG_VK_BMS_INFO_FIELD_FW_VER_LEN 10
-
-#if MAVLINK_COMMAND_24BIT
-#define MAVLINK_MESSAGE_INFO_VK_BMS_INFO { \
-    53004, \
-    "VK_BMS_INFO", \
-    7, \
-    {  { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_vk_bms_info_t, time_boot_ms) }, \
-         { "man_name", NULL, MAVLINK_TYPE_UINT8_T, 20, 6, offsetof(mavlink_vk_bms_info_t, man_name) }, \
-         { "model_name", NULL, MAVLINK_TYPE_UINT8_T, 20, 26, offsetof(mavlink_vk_bms_info_t, model_name) }, \
-         { "sn_id", NULL, MAVLINK_TYPE_UINT8_T, 20, 46, offsetof(mavlink_vk_bms_info_t, sn_id) }, \
-         { "hw_ver", NULL, MAVLINK_TYPE_UINT8_T, 10, 66, offsetof(mavlink_vk_bms_info_t, hw_ver) }, \
-         { "fw_ver", NULL, MAVLINK_TYPE_UINT8_T, 10, 76, offsetof(mavlink_vk_bms_info_t, fw_ver) }, \
-         { "cyc_cnt", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_vk_bms_info_t, cyc_cnt) }, \
-         } \
-}
-#else
-#define MAVLINK_MESSAGE_INFO_VK_BMS_INFO { \
-    "VK_BMS_INFO", \
-    7, \
-    {  { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_vk_bms_info_t, time_boot_ms) }, \
-         { "man_name", NULL, MAVLINK_TYPE_UINT8_T, 20, 6, offsetof(mavlink_vk_bms_info_t, man_name) }, \
-         { "model_name", NULL, MAVLINK_TYPE_UINT8_T, 20, 26, offsetof(mavlink_vk_bms_info_t, model_name) }, \
-         { "sn_id", NULL, MAVLINK_TYPE_UINT8_T, 20, 46, offsetof(mavlink_vk_bms_info_t, sn_id) }, \
-         { "hw_ver", NULL, MAVLINK_TYPE_UINT8_T, 10, 66, offsetof(mavlink_vk_bms_info_t, hw_ver) }, \
-         { "fw_ver", NULL, MAVLINK_TYPE_UINT8_T, 10, 76, offsetof(mavlink_vk_bms_info_t, fw_ver) }, \
-         { "cyc_cnt", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_vk_bms_info_t, cyc_cnt) }, \
-         } \
-}
-#endif
-
-/**
- * @brief Pack a vk_bms_info 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 time_boot_ms [ms] Timestamp in ms from system boot.
- * @param man_name  BMS manufactor string
- * @param model_name  BMS equpment model name string
- * @param sn_id  BMS SN id string
- * @param hw_ver  BMS hardware version string
- * @param fw_ver  BMS firmware version string
- * @param cyc_cnt  BMS change and discharge
-        cycle times
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_vk_bms_info_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
-                               uint32_t time_boot_ms, const uint8_t *man_name, const uint8_t *model_name, const uint8_t *sn_id, const uint8_t *hw_ver, const uint8_t *fw_ver, uint16_t cyc_cnt)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
-    char buf[MAVLINK_MSG_ID_VK_BMS_INFO_LEN];
-    _mav_put_uint32_t(buf, 0, time_boot_ms);
-    _mav_put_uint16_t(buf, 4, cyc_cnt);
-    _mav_put_uint8_t_array(buf, 6, man_name, 20);
-    _mav_put_uint8_t_array(buf, 26, model_name, 20);
-    _mav_put_uint8_t_array(buf, 46, sn_id, 20);
-    _mav_put_uint8_t_array(buf, 66, hw_ver, 10);
-    _mav_put_uint8_t_array(buf, 76, fw_ver, 10);
-        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VK_BMS_INFO_LEN);
-#else
-    mavlink_vk_bms_info_t packet;
-    packet.time_boot_ms = time_boot_ms;
-    packet.cyc_cnt = cyc_cnt;
-    mav_array_memcpy(packet.man_name, man_name, sizeof(uint8_t)*20);
-    mav_array_memcpy(packet.model_name, model_name, sizeof(uint8_t)*20);
-    mav_array_memcpy(packet.sn_id, sn_id, sizeof(uint8_t)*20);
-    mav_array_memcpy(packet.hw_ver, hw_ver, sizeof(uint8_t)*10);
-    mav_array_memcpy(packet.fw_ver, fw_ver, sizeof(uint8_t)*10);
-        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VK_BMS_INFO_LEN);
-#endif
-
-    msg->msgid = MAVLINK_MSG_ID_VK_BMS_INFO;
-    return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_VK_BMS_INFO_MIN_LEN, MAVLINK_MSG_ID_VK_BMS_INFO_LEN, MAVLINK_MSG_ID_VK_BMS_INFO_CRC);
-}
-
-/**
- * @brief Pack a vk_bms_info 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 time_boot_ms [ms] Timestamp in ms from system boot.
- * @param man_name  BMS manufactor string
- * @param model_name  BMS equpment model name string
- * @param sn_id  BMS SN id string
- * @param hw_ver  BMS hardware version string
- * @param fw_ver  BMS firmware version string
- * @param cyc_cnt  BMS change and discharge
-        cycle times
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_vk_bms_info_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
-                               uint32_t time_boot_ms, const uint8_t *man_name, const uint8_t *model_name, const uint8_t *sn_id, const uint8_t *hw_ver, const uint8_t *fw_ver, uint16_t cyc_cnt)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
-    char buf[MAVLINK_MSG_ID_VK_BMS_INFO_LEN];
-    _mav_put_uint32_t(buf, 0, time_boot_ms);
-    _mav_put_uint16_t(buf, 4, cyc_cnt);
-    _mav_put_uint8_t_array(buf, 6, man_name, 20);
-    _mav_put_uint8_t_array(buf, 26, model_name, 20);
-    _mav_put_uint8_t_array(buf, 46, sn_id, 20);
-    _mav_put_uint8_t_array(buf, 66, hw_ver, 10);
-    _mav_put_uint8_t_array(buf, 76, fw_ver, 10);
-        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VK_BMS_INFO_LEN);
-#else
-    mavlink_vk_bms_info_t packet;
-    packet.time_boot_ms = time_boot_ms;
-    packet.cyc_cnt = cyc_cnt;
-    mav_array_memcpy(packet.man_name, man_name, sizeof(uint8_t)*20);
-    mav_array_memcpy(packet.model_name, model_name, sizeof(uint8_t)*20);
-    mav_array_memcpy(packet.sn_id, sn_id, sizeof(uint8_t)*20);
-    mav_array_memcpy(packet.hw_ver, hw_ver, sizeof(uint8_t)*10);
-    mav_array_memcpy(packet.fw_ver, fw_ver, sizeof(uint8_t)*10);
-        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VK_BMS_INFO_LEN);
-#endif
-
-    msg->msgid = MAVLINK_MSG_ID_VK_BMS_INFO;
-#if MAVLINK_CRC_EXTRA
-    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_VK_BMS_INFO_MIN_LEN, MAVLINK_MSG_ID_VK_BMS_INFO_LEN, MAVLINK_MSG_ID_VK_BMS_INFO_CRC);
-#else
-    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_VK_BMS_INFO_MIN_LEN, MAVLINK_MSG_ID_VK_BMS_INFO_LEN);
-#endif
-}
-
-/**
- * @brief Pack a vk_bms_info 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 time_boot_ms [ms] Timestamp in ms from system boot.
- * @param man_name  BMS manufactor string
- * @param model_name  BMS equpment model name string
- * @param sn_id  BMS SN id string
- * @param hw_ver  BMS hardware version string
- * @param fw_ver  BMS firmware version string
- * @param cyc_cnt  BMS change and discharge
-        cycle times
- * @return length of the message in bytes (excluding serial stream start sign)
- */
-static inline uint16_t mavlink_msg_vk_bms_info_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
-                               mavlink_message_t* msg,
-                                   uint32_t time_boot_ms,const uint8_t *man_name,const uint8_t *model_name,const uint8_t *sn_id,const uint8_t *hw_ver,const uint8_t *fw_ver,uint16_t cyc_cnt)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
-    char buf[MAVLINK_MSG_ID_VK_BMS_INFO_LEN];
-    _mav_put_uint32_t(buf, 0, time_boot_ms);
-    _mav_put_uint16_t(buf, 4, cyc_cnt);
-    _mav_put_uint8_t_array(buf, 6, man_name, 20);
-    _mav_put_uint8_t_array(buf, 26, model_name, 20);
-    _mav_put_uint8_t_array(buf, 46, sn_id, 20);
-    _mav_put_uint8_t_array(buf, 66, hw_ver, 10);
-    _mav_put_uint8_t_array(buf, 76, fw_ver, 10);
-        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VK_BMS_INFO_LEN);
-#else
-    mavlink_vk_bms_info_t packet;
-    packet.time_boot_ms = time_boot_ms;
-    packet.cyc_cnt = cyc_cnt;
-    mav_array_memcpy(packet.man_name, man_name, sizeof(uint8_t)*20);
-    mav_array_memcpy(packet.model_name, model_name, sizeof(uint8_t)*20);
-    mav_array_memcpy(packet.sn_id, sn_id, sizeof(uint8_t)*20);
-    mav_array_memcpy(packet.hw_ver, hw_ver, sizeof(uint8_t)*10);
-    mav_array_memcpy(packet.fw_ver, fw_ver, sizeof(uint8_t)*10);
-        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VK_BMS_INFO_LEN);
-#endif
-
-    msg->msgid = MAVLINK_MSG_ID_VK_BMS_INFO;
-    return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_VK_BMS_INFO_MIN_LEN, MAVLINK_MSG_ID_VK_BMS_INFO_LEN, MAVLINK_MSG_ID_VK_BMS_INFO_CRC);
-}
-
-/**
- * @brief Encode a vk_bms_info 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_bms_info C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_vk_bms_info_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_vk_bms_info_t* vk_bms_info)
-{
-    return mavlink_msg_vk_bms_info_pack(system_id, component_id, msg, vk_bms_info->time_boot_ms, vk_bms_info->man_name, vk_bms_info->model_name, vk_bms_info->sn_id, vk_bms_info->hw_ver, vk_bms_info->fw_ver, vk_bms_info->cyc_cnt);
-}
-
-/**
- * @brief Encode a vk_bms_info 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_bms_info C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_vk_bms_info_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_vk_bms_info_t* vk_bms_info)
-{
-    return mavlink_msg_vk_bms_info_pack_chan(system_id, component_id, chan, msg, vk_bms_info->time_boot_ms, vk_bms_info->man_name, vk_bms_info->model_name, vk_bms_info->sn_id, vk_bms_info->hw_ver, vk_bms_info->fw_ver, vk_bms_info->cyc_cnt);
-}
-
-/**
- * @brief Encode a vk_bms_info 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_bms_info C-struct to read the message contents from
- */
-static inline uint16_t mavlink_msg_vk_bms_info_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_vk_bms_info_t* vk_bms_info)
-{
-    return mavlink_msg_vk_bms_info_pack_status(system_id, component_id, _status, msg,  vk_bms_info->time_boot_ms, vk_bms_info->man_name, vk_bms_info->model_name, vk_bms_info->sn_id, vk_bms_info->hw_ver, vk_bms_info->fw_ver, vk_bms_info->cyc_cnt);
-}
-
-/**
- * @brief Send a vk_bms_info message
- * @param chan MAVLink channel to send the message
- *
- * @param time_boot_ms [ms] Timestamp in ms from system boot.
- * @param man_name  BMS manufactor string
- * @param model_name  BMS equpment model name string
- * @param sn_id  BMS SN id string
- * @param hw_ver  BMS hardware version string
- * @param fw_ver  BMS firmware version string
- * @param cyc_cnt  BMS change and discharge
-        cycle times
- */
-#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-
-static inline void mavlink_msg_vk_bms_info_send(mavlink_channel_t chan, uint32_t time_boot_ms, const uint8_t *man_name, const uint8_t *model_name, const uint8_t *sn_id, const uint8_t *hw_ver, const uint8_t *fw_ver, uint16_t cyc_cnt)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
-    char buf[MAVLINK_MSG_ID_VK_BMS_INFO_LEN];
-    _mav_put_uint32_t(buf, 0, time_boot_ms);
-    _mav_put_uint16_t(buf, 4, cyc_cnt);
-    _mav_put_uint8_t_array(buf, 6, man_name, 20);
-    _mav_put_uint8_t_array(buf, 26, model_name, 20);
-    _mav_put_uint8_t_array(buf, 46, sn_id, 20);
-    _mav_put_uint8_t_array(buf, 66, hw_ver, 10);
-    _mav_put_uint8_t_array(buf, 76, fw_ver, 10);
-    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VK_BMS_INFO, buf, MAVLINK_MSG_ID_VK_BMS_INFO_MIN_LEN, MAVLINK_MSG_ID_VK_BMS_INFO_LEN, MAVLINK_MSG_ID_VK_BMS_INFO_CRC);
-#else
-    mavlink_vk_bms_info_t packet;
-    packet.time_boot_ms = time_boot_ms;
-    packet.cyc_cnt = cyc_cnt;
-    mav_array_memcpy(packet.man_name, man_name, sizeof(uint8_t)*20);
-    mav_array_memcpy(packet.model_name, model_name, sizeof(uint8_t)*20);
-    mav_array_memcpy(packet.sn_id, sn_id, sizeof(uint8_t)*20);
-    mav_array_memcpy(packet.hw_ver, hw_ver, sizeof(uint8_t)*10);
-    mav_array_memcpy(packet.fw_ver, fw_ver, sizeof(uint8_t)*10);
-    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VK_BMS_INFO, (const char *)&packet, MAVLINK_MSG_ID_VK_BMS_INFO_MIN_LEN, MAVLINK_MSG_ID_VK_BMS_INFO_LEN, MAVLINK_MSG_ID_VK_BMS_INFO_CRC);
-#endif
-}
-
-/**
- * @brief Send a vk_bms_info message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
-static inline void mavlink_msg_vk_bms_info_send_struct(mavlink_channel_t chan, const mavlink_vk_bms_info_t* vk_bms_info)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
-    mavlink_msg_vk_bms_info_send(chan, vk_bms_info->time_boot_ms, vk_bms_info->man_name, vk_bms_info->model_name, vk_bms_info->sn_id, vk_bms_info->hw_ver, vk_bms_info->fw_ver, vk_bms_info->cyc_cnt);
-#else
-    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VK_BMS_INFO, (const char *)vk_bms_info, MAVLINK_MSG_ID_VK_BMS_INFO_MIN_LEN, MAVLINK_MSG_ID_VK_BMS_INFO_LEN, MAVLINK_MSG_ID_VK_BMS_INFO_CRC);
-#endif
-}
-
-#if MAVLINK_MSG_ID_VK_BMS_INFO_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_bms_info_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint32_t time_boot_ms, const uint8_t *man_name, const uint8_t *model_name, const uint8_t *sn_id, const uint8_t *hw_ver, const uint8_t *fw_ver, uint16_t cyc_cnt)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
-    char *buf = (char *)msgbuf;
-    _mav_put_uint32_t(buf, 0, time_boot_ms);
-    _mav_put_uint16_t(buf, 4, cyc_cnt);
-    _mav_put_uint8_t_array(buf, 6, man_name, 20);
-    _mav_put_uint8_t_array(buf, 26, model_name, 20);
-    _mav_put_uint8_t_array(buf, 46, sn_id, 20);
-    _mav_put_uint8_t_array(buf, 66, hw_ver, 10);
-    _mav_put_uint8_t_array(buf, 76, fw_ver, 10);
-    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VK_BMS_INFO, buf, MAVLINK_MSG_ID_VK_BMS_INFO_MIN_LEN, MAVLINK_MSG_ID_VK_BMS_INFO_LEN, MAVLINK_MSG_ID_VK_BMS_INFO_CRC);
-#else
-    mavlink_vk_bms_info_t *packet = (mavlink_vk_bms_info_t *)msgbuf;
-    packet->time_boot_ms = time_boot_ms;
-    packet->cyc_cnt = cyc_cnt;
-    mav_array_memcpy(packet->man_name, man_name, sizeof(uint8_t)*20);
-    mav_array_memcpy(packet->model_name, model_name, sizeof(uint8_t)*20);
-    mav_array_memcpy(packet->sn_id, sn_id, sizeof(uint8_t)*20);
-    mav_array_memcpy(packet->hw_ver, hw_ver, sizeof(uint8_t)*10);
-    mav_array_memcpy(packet->fw_ver, fw_ver, sizeof(uint8_t)*10);
-    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VK_BMS_INFO, (const char *)packet, MAVLINK_MSG_ID_VK_BMS_INFO_MIN_LEN, MAVLINK_MSG_ID_VK_BMS_INFO_LEN, MAVLINK_MSG_ID_VK_BMS_INFO_CRC);
-#endif
-}
-#endif
-
-#endif
-
-// MESSAGE VK_BMS_INFO UNPACKING
-
-
-/**
- * @brief Get field time_boot_ms from vk_bms_info message
- *
- * @return [ms] Timestamp in ms from system boot.
- */
-static inline uint32_t mavlink_msg_vk_bms_info_get_time_boot_ms(const mavlink_message_t* msg)
-{
-    return _MAV_RETURN_uint32_t(msg,  0);
-}
-
-/**
- * @brief Get field man_name from vk_bms_info message
- *
- * @return  BMS manufactor string
- */
-static inline uint16_t mavlink_msg_vk_bms_info_get_man_name(const mavlink_message_t* msg, uint8_t *man_name)
-{
-    return _MAV_RETURN_uint8_t_array(msg, man_name, 20,  6);
-}
-
-/**
- * @brief Get field model_name from vk_bms_info message
- *
- * @return  BMS equpment model name string
- */
-static inline uint16_t mavlink_msg_vk_bms_info_get_model_name(const mavlink_message_t* msg, uint8_t *model_name)
-{
-    return _MAV_RETURN_uint8_t_array(msg, model_name, 20,  26);
-}
-
-/**
- * @brief Get field sn_id from vk_bms_info message
- *
- * @return  BMS SN id string
- */
-static inline uint16_t mavlink_msg_vk_bms_info_get_sn_id(const mavlink_message_t* msg, uint8_t *sn_id)
-{
-    return _MAV_RETURN_uint8_t_array(msg, sn_id, 20,  46);
-}
-
-/**
- * @brief Get field hw_ver from vk_bms_info message
- *
- * @return  BMS hardware version string
- */
-static inline uint16_t mavlink_msg_vk_bms_info_get_hw_ver(const mavlink_message_t* msg, uint8_t *hw_ver)
-{
-    return _MAV_RETURN_uint8_t_array(msg, hw_ver, 10,  66);
-}
-
-/**
- * @brief Get field fw_ver from vk_bms_info message
- *
- * @return  BMS firmware version string
- */
-static inline uint16_t mavlink_msg_vk_bms_info_get_fw_ver(const mavlink_message_t* msg, uint8_t *fw_ver)
-{
-    return _MAV_RETURN_uint8_t_array(msg, fw_ver, 10,  76);
-}
-
-/**
- * @brief Get field cyc_cnt from vk_bms_info message
- *
- * @return  BMS change and discharge
-        cycle times
- */
-static inline uint16_t mavlink_msg_vk_bms_info_get_cyc_cnt(const mavlink_message_t* msg)
-{
-    return _MAV_RETURN_uint16_t(msg,  4);
-}
-
-/**
- * @brief Decode a vk_bms_info message into a struct
- *
- * @param msg The message to decode
- * @param vk_bms_info C-struct to decode the message contents into
- */
-static inline void mavlink_msg_vk_bms_info_decode(const mavlink_message_t* msg, mavlink_vk_bms_info_t* vk_bms_info)
-{
-#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
-    vk_bms_info->time_boot_ms = mavlink_msg_vk_bms_info_get_time_boot_ms(msg);
-    vk_bms_info->cyc_cnt = mavlink_msg_vk_bms_info_get_cyc_cnt(msg);
-    mavlink_msg_vk_bms_info_get_man_name(msg, vk_bms_info->man_name);
-    mavlink_msg_vk_bms_info_get_model_name(msg, vk_bms_info->model_name);
-    mavlink_msg_vk_bms_info_get_sn_id(msg, vk_bms_info->sn_id);
-    mavlink_msg_vk_bms_info_get_hw_ver(msg, vk_bms_info->hw_ver);
-    mavlink_msg_vk_bms_info_get_fw_ver(msg, vk_bms_info->fw_ver);
-#else
-        uint8_t len = msg->len < MAVLINK_MSG_ID_VK_BMS_INFO_LEN? msg->len : MAVLINK_MSG_ID_VK_BMS_INFO_LEN;
-        memset(vk_bms_info, 0, MAVLINK_MSG_ID_VK_BMS_INFO_LEN);
-    memcpy(vk_bms_info, _MAV_PAYLOAD(msg), len);
-#endif
-}

+ 195 - 154
v2.0/VKFly/mavlink_msg_vk_digi_esc_status.h

@@ -1,54 +1,60 @@
 #pragma once
 // MESSAGE VK_DIGI_ESC_STATUS PACKING
 
-#define MAVLINK_MSG_ID_VK_DIGI_ESC_STATUS 53005
+#define MAVLINK_MSG_ID_VK_DIGI_ESC_STATUS 53008
 
 
 typedef struct __mavlink_vk_digi_esc_status_t {
- uint32_t time_boot_ms; /*< [ms] Timestamp in ms from system boot.*/
- uint16_t rot_spd; /*<  BMS manufactor string*/
- uint8_t model_name[20]; /*<  BMS equpment model name string*/
- uint8_t sn_id[20]; /*<  BMS SN id string*/
- uint8_t hw_ver[10]; /*<  BMS hardware version string*/
- uint8_t fw_ver[10]; /*<  BMS firmware version string*/
+ uint32_t timestamp; /*< [ms] Timestamp from system boot.*/
+ int32_t rpm[4]; /*< [rpm] Reported motor RPM from each ESC (negative for
+        reverse rotation).*/
+ float voltage[4]; /*< [V] Voltage measured from each ESC.*/
+ float current[4]; /*< [A] Current measured from each ESC.*/
+ uint32_t status[4]; /*<  Status data from each ESC.*/
+ int16_t temperature[4]; /*< [degC] Temperature measured from each ESC.*/
+ uint8_t index; /*<  Index of the first ESC in this message.
+        minValue = 0, maxValue = 60, increment = 4.*/
 } mavlink_vk_digi_esc_status_t;
 
-#define MAVLINK_MSG_ID_VK_DIGI_ESC_STATUS_LEN 66
-#define MAVLINK_MSG_ID_VK_DIGI_ESC_STATUS_MIN_LEN 66
-#define MAVLINK_MSG_ID_53005_LEN 66
-#define MAVLINK_MSG_ID_53005_MIN_LEN 66
+#define MAVLINK_MSG_ID_VK_DIGI_ESC_STATUS_LEN 77
+#define MAVLINK_MSG_ID_VK_DIGI_ESC_STATUS_MIN_LEN 77
+#define MAVLINK_MSG_ID_53008_LEN 77
+#define MAVLINK_MSG_ID_53008_MIN_LEN 77
 
-#define MAVLINK_MSG_ID_VK_DIGI_ESC_STATUS_CRC 25
-#define MAVLINK_MSG_ID_53005_CRC 25
+#define MAVLINK_MSG_ID_VK_DIGI_ESC_STATUS_CRC 110
+#define MAVLINK_MSG_ID_53008_CRC 110
 
-#define MAVLINK_MSG_VK_DIGI_ESC_STATUS_FIELD_MODEL_NAME_LEN 20
-#define MAVLINK_MSG_VK_DIGI_ESC_STATUS_FIELD_SN_ID_LEN 20
-#define MAVLINK_MSG_VK_DIGI_ESC_STATUS_FIELD_HW_VER_LEN 10
-#define MAVLINK_MSG_VK_DIGI_ESC_STATUS_FIELD_FW_VER_LEN 10
+#define MAVLINK_MSG_VK_DIGI_ESC_STATUS_FIELD_RPM_LEN 4
+#define MAVLINK_MSG_VK_DIGI_ESC_STATUS_FIELD_VOLTAGE_LEN 4
+#define MAVLINK_MSG_VK_DIGI_ESC_STATUS_FIELD_CURRENT_LEN 4
+#define MAVLINK_MSG_VK_DIGI_ESC_STATUS_FIELD_STATUS_LEN 4
+#define MAVLINK_MSG_VK_DIGI_ESC_STATUS_FIELD_TEMPERATURE_LEN 4
 
 #if MAVLINK_COMMAND_24BIT
 #define MAVLINK_MESSAGE_INFO_VK_DIGI_ESC_STATUS { \
-    53005, \
+    53008, \
     "VK_DIGI_ESC_STATUS", \
-    6, \
-    {  { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_vk_digi_esc_status_t, time_boot_ms) }, \
-         { "rot_spd", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_vk_digi_esc_status_t, rot_spd) }, \
-         { "model_name", NULL, MAVLINK_TYPE_UINT8_T, 20, 6, offsetof(mavlink_vk_digi_esc_status_t, model_name) }, \
-         { "sn_id", NULL, MAVLINK_TYPE_UINT8_T, 20, 26, offsetof(mavlink_vk_digi_esc_status_t, sn_id) }, \
-         { "hw_ver", NULL, MAVLINK_TYPE_UINT8_T, 10, 46, offsetof(mavlink_vk_digi_esc_status_t, hw_ver) }, \
-         { "fw_ver", NULL, MAVLINK_TYPE_UINT8_T, 10, 56, offsetof(mavlink_vk_digi_esc_status_t, fw_ver) }, \
+    7, \
+    {  { "index", NULL, MAVLINK_TYPE_UINT8_T, 0, 76, offsetof(mavlink_vk_digi_esc_status_t, index) }, \
+         { "timestamp", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_vk_digi_esc_status_t, timestamp) }, \
+         { "rpm", NULL, MAVLINK_TYPE_INT32_T, 4, 4, offsetof(mavlink_vk_digi_esc_status_t, rpm) }, \
+         { "voltage", NULL, MAVLINK_TYPE_FLOAT, 4, 20, offsetof(mavlink_vk_digi_esc_status_t, voltage) }, \
+         { "current", NULL, MAVLINK_TYPE_FLOAT, 4, 36, offsetof(mavlink_vk_digi_esc_status_t, current) }, \
+         { "temperature", NULL, MAVLINK_TYPE_INT16_T, 4, 68, offsetof(mavlink_vk_digi_esc_status_t, temperature) }, \
+         { "status", NULL, MAVLINK_TYPE_UINT32_T, 4, 52, offsetof(mavlink_vk_digi_esc_status_t, status) }, \
          } \
 }
 #else
 #define MAVLINK_MESSAGE_INFO_VK_DIGI_ESC_STATUS { \
     "VK_DIGI_ESC_STATUS", \
-    6, \
-    {  { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_vk_digi_esc_status_t, time_boot_ms) }, \
-         { "rot_spd", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_vk_digi_esc_status_t, rot_spd) }, \
-         { "model_name", NULL, MAVLINK_TYPE_UINT8_T, 20, 6, offsetof(mavlink_vk_digi_esc_status_t, model_name) }, \
-         { "sn_id", NULL, MAVLINK_TYPE_UINT8_T, 20, 26, offsetof(mavlink_vk_digi_esc_status_t, sn_id) }, \
-         { "hw_ver", NULL, MAVLINK_TYPE_UINT8_T, 10, 46, offsetof(mavlink_vk_digi_esc_status_t, hw_ver) }, \
-         { "fw_ver", NULL, MAVLINK_TYPE_UINT8_T, 10, 56, offsetof(mavlink_vk_digi_esc_status_t, fw_ver) }, \
+    7, \
+    {  { "index", NULL, MAVLINK_TYPE_UINT8_T, 0, 76, offsetof(mavlink_vk_digi_esc_status_t, index) }, \
+         { "timestamp", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_vk_digi_esc_status_t, timestamp) }, \
+         { "rpm", NULL, MAVLINK_TYPE_INT32_T, 4, 4, offsetof(mavlink_vk_digi_esc_status_t, rpm) }, \
+         { "voltage", NULL, MAVLINK_TYPE_FLOAT, 4, 20, offsetof(mavlink_vk_digi_esc_status_t, voltage) }, \
+         { "current", NULL, MAVLINK_TYPE_FLOAT, 4, 36, offsetof(mavlink_vk_digi_esc_status_t, current) }, \
+         { "temperature", NULL, MAVLINK_TYPE_INT16_T, 4, 68, offsetof(mavlink_vk_digi_esc_status_t, temperature) }, \
+         { "status", NULL, MAVLINK_TYPE_UINT32_T, 4, 52, offsetof(mavlink_vk_digi_esc_status_t, status) }, \
          } \
 }
 #endif
@@ -59,34 +65,39 @@ typedef struct __mavlink_vk_digi_esc_status_t {
  * @param component_id ID of this component (e.g. 200 for IMU)
  * @param msg The MAVLink message to compress the data into
  *
- * @param time_boot_ms [ms] Timestamp in ms from system boot.
- * @param rot_spd  BMS manufactor string
- * @param model_name  BMS equpment model name string
- * @param sn_id  BMS SN id string
- * @param hw_ver  BMS hardware version string
- * @param fw_ver  BMS firmware version string
+ * @param index  Index of the first ESC in this message.
+        minValue = 0, maxValue = 60, increment = 4.
+ * @param timestamp [ms] Timestamp from system boot.
+ * @param rpm [rpm] Reported motor RPM from each ESC (negative for
+        reverse rotation).
+ * @param voltage [V] Voltage measured from each ESC.
+ * @param current [A] Current measured from each ESC.
+ * @param temperature [degC] Temperature measured from each ESC.
+ * @param status  Status data from each ESC.
  * @return length of the message in bytes (excluding serial stream start sign)
  */
 static inline uint16_t mavlink_msg_vk_digi_esc_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
-                               uint32_t time_boot_ms, uint16_t rot_spd, const uint8_t *model_name, const uint8_t *sn_id, const uint8_t *hw_ver, const uint8_t *fw_ver)
+                               uint8_t index, uint32_t timestamp, const int32_t *rpm, const float *voltage, const float *current, const int16_t *temperature, const uint32_t *status)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_VK_DIGI_ESC_STATUS_LEN];
-    _mav_put_uint32_t(buf, 0, time_boot_ms);
-    _mav_put_uint16_t(buf, 4, rot_spd);
-    _mav_put_uint8_t_array(buf, 6, model_name, 20);
-    _mav_put_uint8_t_array(buf, 26, sn_id, 20);
-    _mav_put_uint8_t_array(buf, 46, hw_ver, 10);
-    _mav_put_uint8_t_array(buf, 56, fw_ver, 10);
+    _mav_put_uint32_t(buf, 0, timestamp);
+    _mav_put_uint8_t(buf, 76, index);
+    _mav_put_int32_t_array(buf, 4, rpm, 4);
+    _mav_put_float_array(buf, 20, voltage, 4);
+    _mav_put_float_array(buf, 36, current, 4);
+    _mav_put_uint32_t_array(buf, 52, status, 4);
+    _mav_put_int16_t_array(buf, 68, temperature, 4);
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VK_DIGI_ESC_STATUS_LEN);
 #else
     mavlink_vk_digi_esc_status_t packet;
-    packet.time_boot_ms = time_boot_ms;
-    packet.rot_spd = rot_spd;
-    mav_array_memcpy(packet.model_name, model_name, sizeof(uint8_t)*20);
-    mav_array_memcpy(packet.sn_id, sn_id, sizeof(uint8_t)*20);
-    mav_array_memcpy(packet.hw_ver, hw_ver, sizeof(uint8_t)*10);
-    mav_array_memcpy(packet.fw_ver, fw_ver, sizeof(uint8_t)*10);
+    packet.timestamp = timestamp;
+    packet.index = index;
+    mav_array_memcpy(packet.rpm, rpm, sizeof(int32_t)*4);
+    mav_array_memcpy(packet.voltage, voltage, sizeof(float)*4);
+    mav_array_memcpy(packet.current, current, sizeof(float)*4);
+    mav_array_memcpy(packet.status, status, sizeof(uint32_t)*4);
+    mav_array_memcpy(packet.temperature, temperature, sizeof(int16_t)*4);
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VK_DIGI_ESC_STATUS_LEN);
 #endif
 
@@ -101,34 +112,39 @@ static inline uint16_t mavlink_msg_vk_digi_esc_status_pack(uint8_t system_id, ui
  * @param status MAVLink status structure
  * @param msg The MAVLink message to compress the data into
  *
- * @param time_boot_ms [ms] Timestamp in ms from system boot.
- * @param rot_spd  BMS manufactor string
- * @param model_name  BMS equpment model name string
- * @param sn_id  BMS SN id string
- * @param hw_ver  BMS hardware version string
- * @param fw_ver  BMS firmware version string
+ * @param index  Index of the first ESC in this message.
+        minValue = 0, maxValue = 60, increment = 4.
+ * @param timestamp [ms] Timestamp from system boot.
+ * @param rpm [rpm] Reported motor RPM from each ESC (negative for
+        reverse rotation).
+ * @param voltage [V] Voltage measured from each ESC.
+ * @param current [A] Current measured from each ESC.
+ * @param temperature [degC] Temperature measured from each ESC.
+ * @param status  Status data from each ESC.
  * @return length of the message in bytes (excluding serial stream start sign)
  */
 static inline uint16_t mavlink_msg_vk_digi_esc_status_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
-                               uint32_t time_boot_ms, uint16_t rot_spd, const uint8_t *model_name, const uint8_t *sn_id, const uint8_t *hw_ver, const uint8_t *fw_ver)
+                               uint8_t index, uint32_t timestamp, const int32_t *rpm, const float *voltage, const float *current, const int16_t *temperature, const uint32_t *status)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_VK_DIGI_ESC_STATUS_LEN];
-    _mav_put_uint32_t(buf, 0, time_boot_ms);
-    _mav_put_uint16_t(buf, 4, rot_spd);
-    _mav_put_uint8_t_array(buf, 6, model_name, 20);
-    _mav_put_uint8_t_array(buf, 26, sn_id, 20);
-    _mav_put_uint8_t_array(buf, 46, hw_ver, 10);
-    _mav_put_uint8_t_array(buf, 56, fw_ver, 10);
+    _mav_put_uint32_t(buf, 0, timestamp);
+    _mav_put_uint8_t(buf, 76, index);
+    _mav_put_int32_t_array(buf, 4, rpm, 4);
+    _mav_put_float_array(buf, 20, voltage, 4);
+    _mav_put_float_array(buf, 36, current, 4);
+    _mav_put_uint32_t_array(buf, 52, status, 4);
+    _mav_put_int16_t_array(buf, 68, temperature, 4);
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VK_DIGI_ESC_STATUS_LEN);
 #else
     mavlink_vk_digi_esc_status_t packet;
-    packet.time_boot_ms = time_boot_ms;
-    packet.rot_spd = rot_spd;
-    mav_array_memcpy(packet.model_name, model_name, sizeof(uint8_t)*20);
-    mav_array_memcpy(packet.sn_id, sn_id, sizeof(uint8_t)*20);
-    mav_array_memcpy(packet.hw_ver, hw_ver, sizeof(uint8_t)*10);
-    mav_array_memcpy(packet.fw_ver, fw_ver, sizeof(uint8_t)*10);
+    packet.timestamp = timestamp;
+    packet.index = index;
+    mav_array_memcpy(packet.rpm, rpm, sizeof(int32_t)*4);
+    mav_array_memcpy(packet.voltage, voltage, sizeof(float)*4);
+    mav_array_memcpy(packet.current, current, sizeof(float)*4);
+    mav_array_memcpy(packet.status, status, sizeof(uint32_t)*4);
+    mav_array_memcpy(packet.temperature, temperature, sizeof(int16_t)*4);
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VK_DIGI_ESC_STATUS_LEN);
 #endif
 
@@ -146,35 +162,40 @@ static inline uint16_t mavlink_msg_vk_digi_esc_status_pack_status(uint8_t 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 time_boot_ms [ms] Timestamp in ms from system boot.
- * @param rot_spd  BMS manufactor string
- * @param model_name  BMS equpment model name string
- * @param sn_id  BMS SN id string
- * @param hw_ver  BMS hardware version string
- * @param fw_ver  BMS firmware version string
+ * @param index  Index of the first ESC in this message.
+        minValue = 0, maxValue = 60, increment = 4.
+ * @param timestamp [ms] Timestamp from system boot.
+ * @param rpm [rpm] Reported motor RPM from each ESC (negative for
+        reverse rotation).
+ * @param voltage [V] Voltage measured from each ESC.
+ * @param current [A] Current measured from each ESC.
+ * @param temperature [degC] Temperature measured from each ESC.
+ * @param status  Status data from each ESC.
  * @return length of the message in bytes (excluding serial stream start sign)
  */
 static inline uint16_t mavlink_msg_vk_digi_esc_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
                                mavlink_message_t* msg,
-                                   uint32_t time_boot_ms,uint16_t rot_spd,const uint8_t *model_name,const uint8_t *sn_id,const uint8_t *hw_ver,const uint8_t *fw_ver)
+                                   uint8_t index,uint32_t timestamp,const int32_t *rpm,const float *voltage,const float *current,const int16_t *temperature,const uint32_t *status)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_VK_DIGI_ESC_STATUS_LEN];
-    _mav_put_uint32_t(buf, 0, time_boot_ms);
-    _mav_put_uint16_t(buf, 4, rot_spd);
-    _mav_put_uint8_t_array(buf, 6, model_name, 20);
-    _mav_put_uint8_t_array(buf, 26, sn_id, 20);
-    _mav_put_uint8_t_array(buf, 46, hw_ver, 10);
-    _mav_put_uint8_t_array(buf, 56, fw_ver, 10);
+    _mav_put_uint32_t(buf, 0, timestamp);
+    _mav_put_uint8_t(buf, 76, index);
+    _mav_put_int32_t_array(buf, 4, rpm, 4);
+    _mav_put_float_array(buf, 20, voltage, 4);
+    _mav_put_float_array(buf, 36, current, 4);
+    _mav_put_uint32_t_array(buf, 52, status, 4);
+    _mav_put_int16_t_array(buf, 68, temperature, 4);
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VK_DIGI_ESC_STATUS_LEN);
 #else
     mavlink_vk_digi_esc_status_t packet;
-    packet.time_boot_ms = time_boot_ms;
-    packet.rot_spd = rot_spd;
-    mav_array_memcpy(packet.model_name, model_name, sizeof(uint8_t)*20);
-    mav_array_memcpy(packet.sn_id, sn_id, sizeof(uint8_t)*20);
-    mav_array_memcpy(packet.hw_ver, hw_ver, sizeof(uint8_t)*10);
-    mav_array_memcpy(packet.fw_ver, fw_ver, sizeof(uint8_t)*10);
+    packet.timestamp = timestamp;
+    packet.index = index;
+    mav_array_memcpy(packet.rpm, rpm, sizeof(int32_t)*4);
+    mav_array_memcpy(packet.voltage, voltage, sizeof(float)*4);
+    mav_array_memcpy(packet.current, current, sizeof(float)*4);
+    mav_array_memcpy(packet.status, status, sizeof(uint32_t)*4);
+    mav_array_memcpy(packet.temperature, temperature, sizeof(int16_t)*4);
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VK_DIGI_ESC_STATUS_LEN);
 #endif
 
@@ -192,7 +213,7 @@ static inline uint16_t mavlink_msg_vk_digi_esc_status_pack_chan(uint8_t system_i
  */
 static inline uint16_t mavlink_msg_vk_digi_esc_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_vk_digi_esc_status_t* vk_digi_esc_status)
 {
-    return mavlink_msg_vk_digi_esc_status_pack(system_id, component_id, msg, vk_digi_esc_status->time_boot_ms, vk_digi_esc_status->rot_spd, vk_digi_esc_status->model_name, vk_digi_esc_status->sn_id, vk_digi_esc_status->hw_ver, vk_digi_esc_status->fw_ver);
+    return mavlink_msg_vk_digi_esc_status_pack(system_id, component_id, msg, vk_digi_esc_status->index, vk_digi_esc_status->timestamp, vk_digi_esc_status->rpm, vk_digi_esc_status->voltage, vk_digi_esc_status->current, vk_digi_esc_status->temperature, vk_digi_esc_status->status);
 }
 
 /**
@@ -206,7 +227,7 @@ static inline uint16_t mavlink_msg_vk_digi_esc_status_encode(uint8_t system_id,
  */
 static inline uint16_t mavlink_msg_vk_digi_esc_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_vk_digi_esc_status_t* vk_digi_esc_status)
 {
-    return mavlink_msg_vk_digi_esc_status_pack_chan(system_id, component_id, chan, msg, vk_digi_esc_status->time_boot_ms, vk_digi_esc_status->rot_spd, vk_digi_esc_status->model_name, vk_digi_esc_status->sn_id, vk_digi_esc_status->hw_ver, vk_digi_esc_status->fw_ver);
+    return mavlink_msg_vk_digi_esc_status_pack_chan(system_id, component_id, chan, msg, vk_digi_esc_status->index, vk_digi_esc_status->timestamp, vk_digi_esc_status->rpm, vk_digi_esc_status->voltage, vk_digi_esc_status->current, vk_digi_esc_status->temperature, vk_digi_esc_status->status);
 }
 
 /**
@@ -220,41 +241,46 @@ static inline uint16_t mavlink_msg_vk_digi_esc_status_encode_chan(uint8_t system
  */
 static inline uint16_t mavlink_msg_vk_digi_esc_status_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_vk_digi_esc_status_t* vk_digi_esc_status)
 {
-    return mavlink_msg_vk_digi_esc_status_pack_status(system_id, component_id, _status, msg,  vk_digi_esc_status->time_boot_ms, vk_digi_esc_status->rot_spd, vk_digi_esc_status->model_name, vk_digi_esc_status->sn_id, vk_digi_esc_status->hw_ver, vk_digi_esc_status->fw_ver);
+    return mavlink_msg_vk_digi_esc_status_pack_status(system_id, component_id, _status, msg,  vk_digi_esc_status->index, vk_digi_esc_status->timestamp, vk_digi_esc_status->rpm, vk_digi_esc_status->voltage, vk_digi_esc_status->current, vk_digi_esc_status->temperature, vk_digi_esc_status->status);
 }
 
 /**
  * @brief Send a vk_digi_esc_status message
  * @param chan MAVLink channel to send the message
  *
- * @param time_boot_ms [ms] Timestamp in ms from system boot.
- * @param rot_spd  BMS manufactor string
- * @param model_name  BMS equpment model name string
- * @param sn_id  BMS SN id string
- * @param hw_ver  BMS hardware version string
- * @param fw_ver  BMS firmware version string
+ * @param index  Index of the first ESC in this message.
+        minValue = 0, maxValue = 60, increment = 4.
+ * @param timestamp [ms] Timestamp from system boot.
+ * @param rpm [rpm] Reported motor RPM from each ESC (negative for
+        reverse rotation).
+ * @param voltage [V] Voltage measured from each ESC.
+ * @param current [A] Current measured from each ESC.
+ * @param temperature [degC] Temperature measured from each ESC.
+ * @param status  Status data from each ESC.
  */
 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
-static inline void mavlink_msg_vk_digi_esc_status_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint16_t rot_spd, const uint8_t *model_name, const uint8_t *sn_id, const uint8_t *hw_ver, const uint8_t *fw_ver)
+static inline void mavlink_msg_vk_digi_esc_status_send(mavlink_channel_t chan, uint8_t index, uint32_t timestamp, const int32_t *rpm, const float *voltage, const float *current, const int16_t *temperature, const uint32_t *status)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_VK_DIGI_ESC_STATUS_LEN];
-    _mav_put_uint32_t(buf, 0, time_boot_ms);
-    _mav_put_uint16_t(buf, 4, rot_spd);
-    _mav_put_uint8_t_array(buf, 6, model_name, 20);
-    _mav_put_uint8_t_array(buf, 26, sn_id, 20);
-    _mav_put_uint8_t_array(buf, 46, hw_ver, 10);
-    _mav_put_uint8_t_array(buf, 56, fw_ver, 10);
+    _mav_put_uint32_t(buf, 0, timestamp);
+    _mav_put_uint8_t(buf, 76, index);
+    _mav_put_int32_t_array(buf, 4, rpm, 4);
+    _mav_put_float_array(buf, 20, voltage, 4);
+    _mav_put_float_array(buf, 36, current, 4);
+    _mav_put_uint32_t_array(buf, 52, status, 4);
+    _mav_put_int16_t_array(buf, 68, temperature, 4);
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VK_DIGI_ESC_STATUS, buf, MAVLINK_MSG_ID_VK_DIGI_ESC_STATUS_MIN_LEN, MAVLINK_MSG_ID_VK_DIGI_ESC_STATUS_LEN, MAVLINK_MSG_ID_VK_DIGI_ESC_STATUS_CRC);
 #else
     mavlink_vk_digi_esc_status_t packet;
-    packet.time_boot_ms = time_boot_ms;
-    packet.rot_spd = rot_spd;
-    mav_array_memcpy(packet.model_name, model_name, sizeof(uint8_t)*20);
-    mav_array_memcpy(packet.sn_id, sn_id, sizeof(uint8_t)*20);
-    mav_array_memcpy(packet.hw_ver, hw_ver, sizeof(uint8_t)*10);
-    mav_array_memcpy(packet.fw_ver, fw_ver, sizeof(uint8_t)*10);
+    packet.timestamp = timestamp;
+    packet.index = index;
+    mav_array_memcpy(packet.rpm, rpm, sizeof(int32_t)*4);
+    mav_array_memcpy(packet.voltage, voltage, sizeof(float)*4);
+    mav_array_memcpy(packet.current, current, sizeof(float)*4);
+    mav_array_memcpy(packet.status, status, sizeof(uint32_t)*4);
+    mav_array_memcpy(packet.temperature, temperature, sizeof(int16_t)*4);
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VK_DIGI_ESC_STATUS, (const char *)&packet, MAVLINK_MSG_ID_VK_DIGI_ESC_STATUS_MIN_LEN, MAVLINK_MSG_ID_VK_DIGI_ESC_STATUS_LEN, MAVLINK_MSG_ID_VK_DIGI_ESC_STATUS_CRC);
 #endif
 }
@@ -267,7 +293,7 @@ static inline void mavlink_msg_vk_digi_esc_status_send(mavlink_channel_t chan, u
 static inline void mavlink_msg_vk_digi_esc_status_send_struct(mavlink_channel_t chan, const mavlink_vk_digi_esc_status_t* vk_digi_esc_status)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
-    mavlink_msg_vk_digi_esc_status_send(chan, vk_digi_esc_status->time_boot_ms, vk_digi_esc_status->rot_spd, vk_digi_esc_status->model_name, vk_digi_esc_status->sn_id, vk_digi_esc_status->hw_ver, vk_digi_esc_status->fw_ver);
+    mavlink_msg_vk_digi_esc_status_send(chan, vk_digi_esc_status->index, vk_digi_esc_status->timestamp, vk_digi_esc_status->rpm, vk_digi_esc_status->voltage, vk_digi_esc_status->current, vk_digi_esc_status->temperature, vk_digi_esc_status->status);
 #else
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VK_DIGI_ESC_STATUS, (const char *)vk_digi_esc_status, MAVLINK_MSG_ID_VK_DIGI_ESC_STATUS_MIN_LEN, MAVLINK_MSG_ID_VK_DIGI_ESC_STATUS_LEN, MAVLINK_MSG_ID_VK_DIGI_ESC_STATUS_CRC);
 #endif
@@ -281,25 +307,27 @@ static inline void mavlink_msg_vk_digi_esc_status_send_struct(mavlink_channel_t
   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_digi_esc_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint32_t time_boot_ms, uint16_t rot_spd, const uint8_t *model_name, const uint8_t *sn_id, const uint8_t *hw_ver, const uint8_t *fw_ver)
+static inline void mavlink_msg_vk_digi_esc_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint8_t index, uint32_t timestamp, const int32_t *rpm, const float *voltage, const float *current, const int16_t *temperature, const uint32_t *status)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char *buf = (char *)msgbuf;
-    _mav_put_uint32_t(buf, 0, time_boot_ms);
-    _mav_put_uint16_t(buf, 4, rot_spd);
-    _mav_put_uint8_t_array(buf, 6, model_name, 20);
-    _mav_put_uint8_t_array(buf, 26, sn_id, 20);
-    _mav_put_uint8_t_array(buf, 46, hw_ver, 10);
-    _mav_put_uint8_t_array(buf, 56, fw_ver, 10);
+    _mav_put_uint32_t(buf, 0, timestamp);
+    _mav_put_uint8_t(buf, 76, index);
+    _mav_put_int32_t_array(buf, 4, rpm, 4);
+    _mav_put_float_array(buf, 20, voltage, 4);
+    _mav_put_float_array(buf, 36, current, 4);
+    _mav_put_uint32_t_array(buf, 52, status, 4);
+    _mav_put_int16_t_array(buf, 68, temperature, 4);
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VK_DIGI_ESC_STATUS, buf, MAVLINK_MSG_ID_VK_DIGI_ESC_STATUS_MIN_LEN, MAVLINK_MSG_ID_VK_DIGI_ESC_STATUS_LEN, MAVLINK_MSG_ID_VK_DIGI_ESC_STATUS_CRC);
 #else
     mavlink_vk_digi_esc_status_t *packet = (mavlink_vk_digi_esc_status_t *)msgbuf;
-    packet->time_boot_ms = time_boot_ms;
-    packet->rot_spd = rot_spd;
-    mav_array_memcpy(packet->model_name, model_name, sizeof(uint8_t)*20);
-    mav_array_memcpy(packet->sn_id, sn_id, sizeof(uint8_t)*20);
-    mav_array_memcpy(packet->hw_ver, hw_ver, sizeof(uint8_t)*10);
-    mav_array_memcpy(packet->fw_ver, fw_ver, sizeof(uint8_t)*10);
+    packet->timestamp = timestamp;
+    packet->index = index;
+    mav_array_memcpy(packet->rpm, rpm, sizeof(int32_t)*4);
+    mav_array_memcpy(packet->voltage, voltage, sizeof(float)*4);
+    mav_array_memcpy(packet->current, current, sizeof(float)*4);
+    mav_array_memcpy(packet->status, status, sizeof(uint32_t)*4);
+    mav_array_memcpy(packet->temperature, temperature, sizeof(int16_t)*4);
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VK_DIGI_ESC_STATUS, (const char *)packet, MAVLINK_MSG_ID_VK_DIGI_ESC_STATUS_MIN_LEN, MAVLINK_MSG_ID_VK_DIGI_ESC_STATUS_LEN, MAVLINK_MSG_ID_VK_DIGI_ESC_STATUS_CRC);
 #endif
 }
@@ -311,63 +339,75 @@ static inline void mavlink_msg_vk_digi_esc_status_send_buf(mavlink_message_t *ms
 
 
 /**
- * @brief Get field time_boot_ms from vk_digi_esc_status message
+ * @brief Get field index from vk_digi_esc_status message
  *
- * @return [ms] Timestamp in ms from system boot.
+ * @return  Index of the first ESC in this message.
+        minValue = 0, maxValue = 60, increment = 4.
  */
-static inline uint32_t mavlink_msg_vk_digi_esc_status_get_time_boot_ms(const mavlink_message_t* msg)
+static inline uint8_t mavlink_msg_vk_digi_esc_status_get_index(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint8_t(msg,  76);
+}
+
+/**
+ * @brief Get field timestamp from vk_digi_esc_status message
+ *
+ * @return [ms] Timestamp from system boot.
+ */
+static inline uint32_t mavlink_msg_vk_digi_esc_status_get_timestamp(const mavlink_message_t* msg)
 {
     return _MAV_RETURN_uint32_t(msg,  0);
 }
 
 /**
- * @brief Get field rot_spd from vk_digi_esc_status message
+ * @brief Get field rpm from vk_digi_esc_status message
  *
- * @return  BMS manufactor string
+ * @return [rpm] Reported motor RPM from each ESC (negative for
+        reverse rotation).
  */
-static inline uint16_t mavlink_msg_vk_digi_esc_status_get_rot_spd(const mavlink_message_t* msg)
+static inline uint16_t mavlink_msg_vk_digi_esc_status_get_rpm(const mavlink_message_t* msg, int32_t *rpm)
 {
-    return _MAV_RETURN_uint16_t(msg,  4);
+    return _MAV_RETURN_int32_t_array(msg, rpm, 4,  4);
 }
 
 /**
- * @brief Get field model_name from vk_digi_esc_status message
+ * @brief Get field voltage from vk_digi_esc_status message
  *
- * @return  BMS equpment model name string
+ * @return [V] Voltage measured from each ESC.
  */
-static inline uint16_t mavlink_msg_vk_digi_esc_status_get_model_name(const mavlink_message_t* msg, uint8_t *model_name)
+static inline uint16_t mavlink_msg_vk_digi_esc_status_get_voltage(const mavlink_message_t* msg, float *voltage)
 {
-    return _MAV_RETURN_uint8_t_array(msg, model_name, 20,  6);
+    return _MAV_RETURN_float_array(msg, voltage, 4,  20);
 }
 
 /**
- * @brief Get field sn_id from vk_digi_esc_status message
+ * @brief Get field current from vk_digi_esc_status message
  *
- * @return  BMS SN id string
+ * @return [A] Current measured from each ESC.
  */
-static inline uint16_t mavlink_msg_vk_digi_esc_status_get_sn_id(const mavlink_message_t* msg, uint8_t *sn_id)
+static inline uint16_t mavlink_msg_vk_digi_esc_status_get_current(const mavlink_message_t* msg, float *current)
 {
-    return _MAV_RETURN_uint8_t_array(msg, sn_id, 20,  26);
+    return _MAV_RETURN_float_array(msg, current, 4,  36);
 }
 
 /**
- * @brief Get field hw_ver from vk_digi_esc_status message
+ * @brief Get field temperature from vk_digi_esc_status message
  *
- * @return  BMS hardware version string
+ * @return [degC] Temperature measured from each ESC.
  */
-static inline uint16_t mavlink_msg_vk_digi_esc_status_get_hw_ver(const mavlink_message_t* msg, uint8_t *hw_ver)
+static inline uint16_t mavlink_msg_vk_digi_esc_status_get_temperature(const mavlink_message_t* msg, int16_t *temperature)
 {
-    return _MAV_RETURN_uint8_t_array(msg, hw_ver, 10,  46);
+    return _MAV_RETURN_int16_t_array(msg, temperature, 4,  68);
 }
 
 /**
- * @brief Get field fw_ver from vk_digi_esc_status message
+ * @brief Get field status from vk_digi_esc_status message
  *
- * @return  BMS firmware version string
+ * @return  Status data from each ESC.
  */
-static inline uint16_t mavlink_msg_vk_digi_esc_status_get_fw_ver(const mavlink_message_t* msg, uint8_t *fw_ver)
+static inline uint16_t mavlink_msg_vk_digi_esc_status_get_status(const mavlink_message_t* msg, uint32_t *status)
 {
-    return _MAV_RETURN_uint8_t_array(msg, fw_ver, 10,  56);
+    return _MAV_RETURN_uint32_t_array(msg, status, 4,  52);
 }
 
 /**
@@ -379,12 +419,13 @@ static inline uint16_t mavlink_msg_vk_digi_esc_status_get_fw_ver(const mavlink_m
 static inline void mavlink_msg_vk_digi_esc_status_decode(const mavlink_message_t* msg, mavlink_vk_digi_esc_status_t* vk_digi_esc_status)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
-    vk_digi_esc_status->time_boot_ms = mavlink_msg_vk_digi_esc_status_get_time_boot_ms(msg);
-    vk_digi_esc_status->rot_spd = mavlink_msg_vk_digi_esc_status_get_rot_spd(msg);
-    mavlink_msg_vk_digi_esc_status_get_model_name(msg, vk_digi_esc_status->model_name);
-    mavlink_msg_vk_digi_esc_status_get_sn_id(msg, vk_digi_esc_status->sn_id);
-    mavlink_msg_vk_digi_esc_status_get_hw_ver(msg, vk_digi_esc_status->hw_ver);
-    mavlink_msg_vk_digi_esc_status_get_fw_ver(msg, vk_digi_esc_status->fw_ver);
+    vk_digi_esc_status->timestamp = mavlink_msg_vk_digi_esc_status_get_timestamp(msg);
+    mavlink_msg_vk_digi_esc_status_get_rpm(msg, vk_digi_esc_status->rpm);
+    mavlink_msg_vk_digi_esc_status_get_voltage(msg, vk_digi_esc_status->voltage);
+    mavlink_msg_vk_digi_esc_status_get_current(msg, vk_digi_esc_status->current);
+    mavlink_msg_vk_digi_esc_status_get_status(msg, vk_digi_esc_status->status);
+    mavlink_msg_vk_digi_esc_status_get_temperature(msg, vk_digi_esc_status->temperature);
+    vk_digi_esc_status->index = mavlink_msg_vk_digi_esc_status_get_index(msg);
 #else
         uint8_t len = msg->len < MAVLINK_MSG_ID_VK_DIGI_ESC_STATUS_LEN? msg->len : MAVLINK_MSG_ID_VK_DIGI_ESC_STATUS_LEN;
         memset(vk_digi_esc_status, 0, MAVLINK_MSG_ID_VK_DIGI_ESC_STATUS_LEN);

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

@@ -7,7 +7,7 @@
 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*/
+ uint16_t spd_rpm; /*<  rotational speed in rpm*/
  int16_t cylinderA_temp; /*< [degC] CylinderA head temperature*/
  int16_t cylinderB_temp; /*< [degC] CylinderB head temperature*/
  int16_t coolant_temp; /*< [degC] coolant head temperature*/
@@ -95,7 +95,7 @@ typedef struct __mavlink_vk_engine_ecu_staus_t {
  * @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 spd_rpm  rotational speed in rpm
  * @param thr_pos [%] throttle
         position 
  * @param fuel_pos [%] fuel
@@ -175,7 +175,7 @@ static inline uint16_t mavlink_msg_vk_engine_ecu_staus_pack(uint8_t system_id, u
  * @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 spd_rpm  rotational speed in rpm
  * @param thr_pos [%] throttle
         position 
  * @param fuel_pos [%] fuel
@@ -258,7 +258,7 @@ static inline uint16_t mavlink_msg_vk_engine_ecu_staus_pack_status(uint8_t syste
  * @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 spd_rpm  rotational speed in rpm
  * @param thr_pos [%] throttle
         position 
  * @param fuel_pos [%] fuel
@@ -377,7 +377,7 @@ static inline uint16_t mavlink_msg_vk_engine_ecu_staus_encode_status(uint8_t sys
  * @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 spd_rpm  rotational speed in rpm
  * @param thr_pos [%] throttle
         position 
  * @param fuel_pos [%] fuel
@@ -534,7 +534,7 @@ static inline uint32_t mavlink_msg_vk_engine_ecu_staus_get_timestamp(const mavli
 /**
  * @brief Get field spd_rpm from vk_engine_ecu_staus message
  *
- * @return  formation leader drone state bitmap
+ * @return  rotational speed in rpm
  */
 static inline uint16_t mavlink_msg_vk_engine_ecu_staus_get_spd_rpm(const mavlink_message_t* msg)
 {

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

@@ -591,6 +591,71 @@ static void mavlink_test_vk_mosaich_gps_raw(uint8_t system_id, uint8_t component
 #endif
 }
 
+static void mavlink_test_vk_digi_esc_status(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_DIGI_ESC_STATUS >= 256) {
+            return;
+        }
+#endif
+    mavlink_message_t msg;
+        uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+        uint16_t i;
+    mavlink_vk_digi_esc_status_t packet_in = {
+        963497464,{ 963497672, 963497673, 963497674, 963497675 },{ 157.0, 158.0, 159.0, 160.0 },{ 269.0, 270.0, 271.0, 272.0 },{ 963500168, 963500169, 963500170, 963500171 },{ 20771, 20772, 20773, 20774 },233
+    };
+    mavlink_vk_digi_esc_status_t packet1, packet2;
+        memset(&packet1, 0, sizeof(packet1));
+        packet1.timestamp = packet_in.timestamp;
+        packet1.index = packet_in.index;
+        
+        mav_array_memcpy(packet1.rpm, packet_in.rpm, sizeof(int32_t)*4);
+        mav_array_memcpy(packet1.voltage, packet_in.voltage, sizeof(float)*4);
+        mav_array_memcpy(packet1.current, packet_in.current, sizeof(float)*4);
+        mav_array_memcpy(packet1.status, packet_in.status, sizeof(uint32_t)*4);
+        mav_array_memcpy(packet1.temperature, packet_in.temperature, sizeof(int16_t)*4);
+        
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+        if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+           // cope with extensions
+           memset(MAVLINK_MSG_ID_VK_DIGI_ESC_STATUS_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_VK_DIGI_ESC_STATUS_MIN_LEN);
+        }
+#endif
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_vk_digi_esc_status_encode(system_id, component_id, &msg, &packet1);
+    mavlink_msg_vk_digi_esc_status_decode(&msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_vk_digi_esc_status_pack(system_id, component_id, &msg , packet1.index , packet1.timestamp , packet1.rpm , packet1.voltage , packet1.current , packet1.temperature , packet1.status );
+    mavlink_msg_vk_digi_esc_status_decode(&msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_vk_digi_esc_status_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.index , packet1.timestamp , packet1.rpm , packet1.voltage , packet1.current , packet1.temperature , packet1.status );
+    mavlink_msg_vk_digi_esc_status_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_digi_esc_status_decode(last_msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+        
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_vk_digi_esc_status_send(MAVLINK_COMM_1 , packet1.index , packet1.timestamp , packet1.rpm , packet1.voltage , packet1.current , packet1.temperature , packet1.status );
+    mavlink_msg_vk_digi_esc_status_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_DIGI_ESC_STATUS") != NULL);
+    MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_VK_DIGI_ESC_STATUS) != NULL);
+#endif
+}
+
 static void mavlink_test_vk_parachute_status(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
 {
 #ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
@@ -1100,6 +1165,7 @@ static void mavlink_test_VKFly(uint8_t system_id, uint8_t component_id, mavlink_
     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_mosaich_gps_raw(system_id, component_id, last_msg);
+    mavlink_test_vk_digi_esc_status(system_id, component_id, last_msg);
     mavlink_test_vk_parachute_status(system_id, component_id, last_msg);
     mavlink_test_vk_weigher_state(system_id, component_id, last_msg);
     mavlink_test_vk_fw_update_begin(system_id, component_id, last_msg);

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

@@ -7,7 +7,7 @@
 #ifndef MAVLINK_VERSION_H
 #define MAVLINK_VERSION_H
 
-#define MAVLINK_BUILD_DATE "Wed Jan 15 2025"
+#define MAVLINK_BUILD_DATE "Thu Jan 16 2025"
 #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 1329280358369995956
+#define MAVLINK_COMMON_XML_HASH -6681941826931752784
 
 #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 1329280358369995956
+#define MAVLINK_PRIMARY_XML_HASH -6681941826931752784
 
 #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 "Wed Jan 15 2025"
+#define MAVLINK_BUILD_DATE "Thu Jan 16 2025"
 #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 -8194162153814049090
+#define MAVLINK_PRIMARY_XML_HASH 5124769176504212225
 
 #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 -8194162153814049090
+#define MAVLINK_MINIMAL_XML_HASH 5124769176504212225
 
 #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 "Wed Jan 15 2025"
+#define MAVLINK_BUILD_DATE "Thu Jan 16 2025"
 #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 5877102512431502813
+#define MAVLINK_PRIMARY_XML_HASH -362910411080345871
 
 #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 5877102512431502813
+#define MAVLINK_STANDARD_XML_HASH -362910411080345871
 
 #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 "Wed Jan 15 2025"
+#define MAVLINK_BUILD_DATE "Thu Jan 16 2025"
 #define MAVLINK_WIRE_PROTOCOL_VERSION "2.0"
 #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 22
  

Algúns arquivos non se mostraron porque demasiados arquivos cambiaron neste cambio