Browse Source

增加电调配置自定义 command

Liu Yang 1 year ago
parent
commit
4fe425b780

+ 14 - 2
msg_definitions/VKFly.xml

@@ -485,6 +485,18 @@
         <param index="6" label="Longitude">Longitude</param>
         <param index="7" label="Altitude" units="m">Altitude</param>
       </entry>
+
+      <entry value="44050" name="VKFLY_CMD_ESC_CONFIG" hasLocation="false"
+        isDestination="true">
+        <description>esc </description>
+        <param index="1" label="Set ID"> Set Esc id, min=1, max=16 </param>
+        <param index="2" label=""> </param>
+        <param index="3" label=""> </param>
+        <param index="4" label=""> </param>
+        <param index="5" label=""> </param>
+        <param index="6" label=""> </param>
+        <param index="7" label=""> </param>
+      </entry>
     </enum>
   </enums>
 
@@ -540,8 +552,6 @@
       <field type="uint32_t" name="time_boot_ms" units="ms">Timestamp in ms from system boot.</field>
       <field type="uint32_t" name="voltage" units="mV">BMS voltage in mV</field>
       <field type="int16_t" name="current" units="cA">BMS current in cA, negative value means in charging</field>
-      <field type="uint16_t" name="cyc_cnt" minValue="0" increment="1">BMS change and discharge
-        cycle times</field>
       <field type="int16_t" name="temperature" units="degC">BMS temperature in degC</field>
       <field type="int8_t" name="cap_percent" units="%">BMS remaining power in percentage</field>
       <field type="uint8_t" name="bat_id" minValue="0" maxValue="1" increment="1">BMS id, start from
@@ -561,6 +571,8 @@
       <field type="uint8_t[20]" name="sn_id">BMS SN id string</field>
       <field type="uint8_t[10]" name="hw_ver">BMS hardware version string</field>
       <field type="uint8_t[10]" name="fw_ver">BMS firmware version string</field>
+      <field type="uint16_t" name="cyc_cnt" minValue="0" increment="1">BMS change and discharge
+        cycle times</field>
     </message>
 
     <message id="53005" name="VK_DIGI_ESC_STATUS">

+ 8 - 1
readme.md

@@ -932,6 +932,14 @@ mavlink common 标准消息集中主要由 MAVLINK_MSG_ID_COMMAND_INT 和 MAVLIN
   | param6 | 经度 1e-7deg                                                                                                                                                                                                                                                                                                        |
   | param7 | 高度 m                                                                                                                                                                                                                                                                                                              |
 
+其它的自定义 command
+
+- VKFLY_CMD_ESC_CONFIG
+  电调设置
+  | 参数   | 说明                                  |
+  | ------ | ------------------------------------- |
+  | param1 | 设置电调编号, 1~16, NAN表示忽略该指令 |
+
 ### 自定义消息
 
 - MAVLINK_VKINS_STATUS
@@ -974,7 +982,6 @@ mavlink common 标准消息集中主要由 MAVLINK_MSG_ID_COMMAND_INT 和 MAVLIN
   | time_boot_ms | 系统本地时间戳ms             |
   | voltage      | 电压 mV                      |
   | current      | 电流 cA(0.01A), 负数表示充电 |
-  | cyc_cnt      | 充放电次数                   |
   | temperature  | 温度 1度                     |
   | cap_percent  | 电量 1%                      |
   | bat_id       | 电池编号, 0~5                |

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 -1336360527562923858
+#define MAVLINK_PRIMARY_XML_HASH 6152512023245993175
 
 #ifndef MAVLINK_STX
 #define MAVLINK_STX 253

+ 91 - 57
v2.0/VKFly/mavlink_msg_vk_bms_info.h

@@ -6,6 +6,8 @@
 
 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*/
@@ -13,13 +15,13 @@ typedef struct __mavlink_vk_bms_info_t {
  uint8_t fw_ver[10]; /*<  BMS firmware version string*/
 } mavlink_vk_bms_info_t;
 
-#define MAVLINK_MSG_ID_VK_BMS_INFO_LEN 84
-#define MAVLINK_MSG_ID_VK_BMS_INFO_MIN_LEN 84
-#define MAVLINK_MSG_ID_53004_LEN 84
-#define MAVLINK_MSG_ID_53004_MIN_LEN 84
+#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 205
-#define MAVLINK_MSG_ID_53004_CRC 205
+#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
@@ -31,25 +33,27 @@ typedef struct __mavlink_vk_bms_info_t {
 #define MAVLINK_MESSAGE_INFO_VK_BMS_INFO { \
     53004, \
     "VK_BMS_INFO", \
-    6, \
+    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, 4, offsetof(mavlink_vk_bms_info_t, man_name) }, \
-         { "model_name", NULL, MAVLINK_TYPE_UINT8_T, 20, 24, offsetof(mavlink_vk_bms_info_t, model_name) }, \
-         { "sn_id", NULL, MAVLINK_TYPE_UINT8_T, 20, 44, offsetof(mavlink_vk_bms_info_t, sn_id) }, \
-         { "hw_ver", NULL, MAVLINK_TYPE_UINT8_T, 10, 64, offsetof(mavlink_vk_bms_info_t, hw_ver) }, \
-         { "fw_ver", NULL, MAVLINK_TYPE_UINT8_T, 10, 74, offsetof(mavlink_vk_bms_info_t, fw_ver) }, \
+         { "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", \
-    6, \
+    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, 4, offsetof(mavlink_vk_bms_info_t, man_name) }, \
-         { "model_name", NULL, MAVLINK_TYPE_UINT8_T, 20, 24, offsetof(mavlink_vk_bms_info_t, model_name) }, \
-         { "sn_id", NULL, MAVLINK_TYPE_UINT8_T, 20, 44, offsetof(mavlink_vk_bms_info_t, sn_id) }, \
-         { "hw_ver", NULL, MAVLINK_TYPE_UINT8_T, 10, 64, offsetof(mavlink_vk_bms_info_t, hw_ver) }, \
-         { "fw_ver", NULL, MAVLINK_TYPE_UINT8_T, 10, 74, offsetof(mavlink_vk_bms_info_t, fw_ver) }, \
+         { "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
@@ -66,23 +70,27 @@ typedef struct __mavlink_vk_bms_info_t {
  * @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)
+                               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_uint8_t_array(buf, 4, man_name, 20);
-    _mav_put_uint8_t_array(buf, 24, model_name, 20);
-    _mav_put_uint8_t_array(buf, 44, sn_id, 20);
-    _mav_put_uint8_t_array(buf, 64, hw_ver, 10);
-    _mav_put_uint8_t_array(buf, 74, fw_ver, 10);
+    _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);
@@ -108,23 +116,27 @@ static inline uint16_t mavlink_msg_vk_bms_info_pack(uint8_t system_id, uint8_t c
  * @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)
+                               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_uint8_t_array(buf, 4, man_name, 20);
-    _mav_put_uint8_t_array(buf, 24, model_name, 20);
-    _mav_put_uint8_t_array(buf, 44, sn_id, 20);
-    _mav_put_uint8_t_array(buf, 64, hw_ver, 10);
-    _mav_put_uint8_t_array(buf, 74, fw_ver, 10);
+    _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);
@@ -153,24 +165,28 @@ static inline uint16_t mavlink_msg_vk_bms_info_pack_status(uint8_t system_id, ui
  * @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)
+                                   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_uint8_t_array(buf, 4, man_name, 20);
-    _mav_put_uint8_t_array(buf, 24, model_name, 20);
-    _mav_put_uint8_t_array(buf, 44, sn_id, 20);
-    _mav_put_uint8_t_array(buf, 64, hw_ver, 10);
-    _mav_put_uint8_t_array(buf, 74, fw_ver, 10);
+    _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);
@@ -193,7 +209,7 @@ static inline uint16_t mavlink_msg_vk_bms_info_pack_chan(uint8_t system_id, uint
  */
 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);
+    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);
 }
 
 /**
@@ -207,7 +223,7 @@ static inline uint16_t mavlink_msg_vk_bms_info_encode(uint8_t system_id, uint8_t
  */
 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);
+    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);
 }
 
 /**
@@ -221,7 +237,7 @@ static inline uint16_t mavlink_msg_vk_bms_info_encode_chan(uint8_t system_id, ui
  */
 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);
+    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);
 }
 
 /**
@@ -234,23 +250,27 @@ static inline uint16_t mavlink_msg_vk_bms_info_encode_status(uint8_t system_id,
  * @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)
+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_uint8_t_array(buf, 4, man_name, 20);
-    _mav_put_uint8_t_array(buf, 24, model_name, 20);
-    _mav_put_uint8_t_array(buf, 44, sn_id, 20);
-    _mav_put_uint8_t_array(buf, 64, hw_ver, 10);
-    _mav_put_uint8_t_array(buf, 74, fw_ver, 10);
+    _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);
@@ -268,7 +288,7 @@ static inline void mavlink_msg_vk_bms_info_send(mavlink_channel_t chan, uint32_t
 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);
+    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
@@ -282,20 +302,22 @@ static inline void mavlink_msg_vk_bms_info_send_struct(mavlink_channel_t chan, c
   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)
+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_uint8_t_array(buf, 4, man_name, 20);
-    _mav_put_uint8_t_array(buf, 24, model_name, 20);
-    _mav_put_uint8_t_array(buf, 44, sn_id, 20);
-    _mav_put_uint8_t_array(buf, 64, hw_ver, 10);
-    _mav_put_uint8_t_array(buf, 74, fw_ver, 10);
+    _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);
@@ -328,7 +350,7 @@ static inline uint32_t mavlink_msg_vk_bms_info_get_time_boot_ms(const mavlink_me
  */
 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,  4);
+    return _MAV_RETURN_uint8_t_array(msg, man_name, 20,  6);
 }
 
 /**
@@ -338,7 +360,7 @@ static inline uint16_t mavlink_msg_vk_bms_info_get_man_name(const mavlink_messag
  */
 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,  24);
+    return _MAV_RETURN_uint8_t_array(msg, model_name, 20,  26);
 }
 
 /**
@@ -348,7 +370,7 @@ static inline uint16_t mavlink_msg_vk_bms_info_get_model_name(const mavlink_mess
  */
 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,  44);
+    return _MAV_RETURN_uint8_t_array(msg, sn_id, 20,  46);
 }
 
 /**
@@ -358,7 +380,7 @@ static inline uint16_t mavlink_msg_vk_bms_info_get_sn_id(const mavlink_message_t
  */
 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,  64);
+    return _MAV_RETURN_uint8_t_array(msg, hw_ver, 10,  66);
 }
 
 /**
@@ -368,7 +390,18 @@ static inline uint16_t mavlink_msg_vk_bms_info_get_hw_ver(const mavlink_message_
  */
 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,  74);
+    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);
 }
 
 /**
@@ -381,6 +414,7 @@ static inline void mavlink_msg_vk_bms_info_decode(const mavlink_message_t* msg,
 {
 #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);

+ 57 - 91
v2.0/VKFly/mavlink_msg_vk_bms_status.h

@@ -10,8 +10,6 @@ typedef struct __mavlink_vk_bms_status_t {
  uint32_t err_code; /*<  BMS error code,
         0 means no error*/
  int16_t current; /*< [cA] BMS current in cA, negative value means in charging*/
- uint16_t cyc_cnt; /*<  BMS change and discharge
-        cycle times*/
  int16_t temperature; /*< [degC] BMS temperature in degC*/
  uint16_t cell_num; /*<  BMS cell numbers*/
  uint16_t cell_volt[30]; /*< [mV] BMS cell voltage in mV*/
@@ -20,13 +18,13 @@ typedef struct __mavlink_vk_bms_status_t {
         0*/
 } mavlink_vk_bms_status_t;
 
-#define MAVLINK_MSG_ID_VK_BMS_STATUS_LEN 82
-#define MAVLINK_MSG_ID_VK_BMS_STATUS_MIN_LEN 82
-#define MAVLINK_MSG_ID_53003_LEN 82
-#define MAVLINK_MSG_ID_53003_MIN_LEN 82
+#define MAVLINK_MSG_ID_VK_BMS_STATUS_LEN 80
+#define MAVLINK_MSG_ID_VK_BMS_STATUS_MIN_LEN 80
+#define MAVLINK_MSG_ID_53003_LEN 80
+#define MAVLINK_MSG_ID_53003_MIN_LEN 80
 
-#define MAVLINK_MSG_ID_VK_BMS_STATUS_CRC 13
-#define MAVLINK_MSG_ID_53003_CRC 13
+#define MAVLINK_MSG_ID_VK_BMS_STATUS_CRC 43
+#define MAVLINK_MSG_ID_53003_CRC 43
 
 #define MAVLINK_MSG_VK_BMS_STATUS_FIELD_CELL_VOLT_LEN 30
 
@@ -34,33 +32,31 @@ typedef struct __mavlink_vk_bms_status_t {
 #define MAVLINK_MESSAGE_INFO_VK_BMS_STATUS { \
     53003, \
     "VK_BMS_STATUS", \
-    10, \
+    9, \
     {  { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_vk_bms_status_t, time_boot_ms) }, \
          { "voltage", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_vk_bms_status_t, voltage) }, \
          { "current", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_vk_bms_status_t, current) }, \
-         { "cyc_cnt", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_vk_bms_status_t, cyc_cnt) }, \
-         { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_vk_bms_status_t, temperature) }, \
-         { "cap_percent", NULL, MAVLINK_TYPE_INT8_T, 0, 80, offsetof(mavlink_vk_bms_status_t, cap_percent) }, \
-         { "bat_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 81, offsetof(mavlink_vk_bms_status_t, bat_id) }, \
+         { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_vk_bms_status_t, temperature) }, \
+         { "cap_percent", NULL, MAVLINK_TYPE_INT8_T, 0, 78, offsetof(mavlink_vk_bms_status_t, cap_percent) }, \
+         { "bat_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 79, offsetof(mavlink_vk_bms_status_t, bat_id) }, \
          { "err_code", "0x%04x", MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_vk_bms_status_t, err_code) }, \
-         { "cell_num", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_vk_bms_status_t, cell_num) }, \
-         { "cell_volt", NULL, MAVLINK_TYPE_UINT16_T, 30, 20, offsetof(mavlink_vk_bms_status_t, cell_volt) }, \
+         { "cell_num", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_vk_bms_status_t, cell_num) }, \
+         { "cell_volt", NULL, MAVLINK_TYPE_UINT16_T, 30, 18, offsetof(mavlink_vk_bms_status_t, cell_volt) }, \
          } \
 }
 #else
 #define MAVLINK_MESSAGE_INFO_VK_BMS_STATUS { \
     "VK_BMS_STATUS", \
-    10, \
+    9, \
     {  { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_vk_bms_status_t, time_boot_ms) }, \
          { "voltage", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_vk_bms_status_t, voltage) }, \
          { "current", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_vk_bms_status_t, current) }, \
-         { "cyc_cnt", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_vk_bms_status_t, cyc_cnt) }, \
-         { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_vk_bms_status_t, temperature) }, \
-         { "cap_percent", NULL, MAVLINK_TYPE_INT8_T, 0, 80, offsetof(mavlink_vk_bms_status_t, cap_percent) }, \
-         { "bat_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 81, offsetof(mavlink_vk_bms_status_t, bat_id) }, \
+         { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_vk_bms_status_t, temperature) }, \
+         { "cap_percent", NULL, MAVLINK_TYPE_INT8_T, 0, 78, offsetof(mavlink_vk_bms_status_t, cap_percent) }, \
+         { "bat_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 79, offsetof(mavlink_vk_bms_status_t, bat_id) }, \
          { "err_code", "0x%04x", MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_vk_bms_status_t, err_code) }, \
-         { "cell_num", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_vk_bms_status_t, cell_num) }, \
-         { "cell_volt", NULL, MAVLINK_TYPE_UINT16_T, 30, 20, offsetof(mavlink_vk_bms_status_t, cell_volt) }, \
+         { "cell_num", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_vk_bms_status_t, cell_num) }, \
+         { "cell_volt", NULL, MAVLINK_TYPE_UINT16_T, 30, 18, offsetof(mavlink_vk_bms_status_t, cell_volt) }, \
          } \
 }
 #endif
@@ -74,8 +70,6 @@ typedef struct __mavlink_vk_bms_status_t {
  * @param time_boot_ms [ms] Timestamp in ms from system boot.
  * @param voltage [mV] BMS voltage in mV
  * @param current [cA] BMS current in cA, negative value means in charging
- * @param cyc_cnt  BMS change and discharge
-        cycle times
  * @param temperature [degC] BMS temperature in degC
  * @param cap_percent [%] BMS remaining power in percentage
  * @param bat_id  BMS id, start from
@@ -87,7 +81,7 @@ typedef struct __mavlink_vk_bms_status_t {
  * @return length of the message in bytes (excluding serial stream start sign)
  */
 static inline uint16_t mavlink_msg_vk_bms_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
-                               uint32_t time_boot_ms, uint32_t voltage, int16_t current, uint16_t cyc_cnt, int16_t temperature, int8_t cap_percent, uint8_t bat_id, uint32_t err_code, uint16_t cell_num, const uint16_t *cell_volt)
+                               uint32_t time_boot_ms, uint32_t voltage, int16_t current, int16_t temperature, int8_t cap_percent, uint8_t bat_id, uint32_t err_code, uint16_t cell_num, const uint16_t *cell_volt)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_VK_BMS_STATUS_LEN];
@@ -95,12 +89,11 @@ static inline uint16_t mavlink_msg_vk_bms_status_pack(uint8_t system_id, uint8_t
     _mav_put_uint32_t(buf, 4, voltage);
     _mav_put_uint32_t(buf, 8, err_code);
     _mav_put_int16_t(buf, 12, current);
-    _mav_put_uint16_t(buf, 14, cyc_cnt);
-    _mav_put_int16_t(buf, 16, temperature);
-    _mav_put_uint16_t(buf, 18, cell_num);
-    _mav_put_int8_t(buf, 80, cap_percent);
-    _mav_put_uint8_t(buf, 81, bat_id);
-    _mav_put_uint16_t_array(buf, 20, cell_volt, 30);
+    _mav_put_int16_t(buf, 14, temperature);
+    _mav_put_uint16_t(buf, 16, cell_num);
+    _mav_put_int8_t(buf, 78, cap_percent);
+    _mav_put_uint8_t(buf, 79, bat_id);
+    _mav_put_uint16_t_array(buf, 18, cell_volt, 30);
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VK_BMS_STATUS_LEN);
 #else
     mavlink_vk_bms_status_t packet;
@@ -108,7 +101,6 @@ static inline uint16_t mavlink_msg_vk_bms_status_pack(uint8_t system_id, uint8_t
     packet.voltage = voltage;
     packet.err_code = err_code;
     packet.current = current;
-    packet.cyc_cnt = cyc_cnt;
     packet.temperature = temperature;
     packet.cell_num = cell_num;
     packet.cap_percent = cap_percent;
@@ -131,8 +123,6 @@ static inline uint16_t mavlink_msg_vk_bms_status_pack(uint8_t system_id, uint8_t
  * @param time_boot_ms [ms] Timestamp in ms from system boot.
  * @param voltage [mV] BMS voltage in mV
  * @param current [cA] BMS current in cA, negative value means in charging
- * @param cyc_cnt  BMS change and discharge
-        cycle times
  * @param temperature [degC] BMS temperature in degC
  * @param cap_percent [%] BMS remaining power in percentage
  * @param bat_id  BMS id, start from
@@ -144,7 +134,7 @@ static inline uint16_t mavlink_msg_vk_bms_status_pack(uint8_t system_id, uint8_t
  * @return length of the message in bytes (excluding serial stream start sign)
  */
 static inline uint16_t mavlink_msg_vk_bms_status_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
-                               uint32_t time_boot_ms, uint32_t voltage, int16_t current, uint16_t cyc_cnt, int16_t temperature, int8_t cap_percent, uint8_t bat_id, uint32_t err_code, uint16_t cell_num, const uint16_t *cell_volt)
+                               uint32_t time_boot_ms, uint32_t voltage, int16_t current, int16_t temperature, int8_t cap_percent, uint8_t bat_id, uint32_t err_code, uint16_t cell_num, const uint16_t *cell_volt)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_VK_BMS_STATUS_LEN];
@@ -152,12 +142,11 @@ static inline uint16_t mavlink_msg_vk_bms_status_pack_status(uint8_t system_id,
     _mav_put_uint32_t(buf, 4, voltage);
     _mav_put_uint32_t(buf, 8, err_code);
     _mav_put_int16_t(buf, 12, current);
-    _mav_put_uint16_t(buf, 14, cyc_cnt);
-    _mav_put_int16_t(buf, 16, temperature);
-    _mav_put_uint16_t(buf, 18, cell_num);
-    _mav_put_int8_t(buf, 80, cap_percent);
-    _mav_put_uint8_t(buf, 81, bat_id);
-    _mav_put_uint16_t_array(buf, 20, cell_volt, 30);
+    _mav_put_int16_t(buf, 14, temperature);
+    _mav_put_uint16_t(buf, 16, cell_num);
+    _mav_put_int8_t(buf, 78, cap_percent);
+    _mav_put_uint8_t(buf, 79, bat_id);
+    _mav_put_uint16_t_array(buf, 18, cell_volt, 30);
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VK_BMS_STATUS_LEN);
 #else
     mavlink_vk_bms_status_t packet;
@@ -165,7 +154,6 @@ static inline uint16_t mavlink_msg_vk_bms_status_pack_status(uint8_t system_id,
     packet.voltage = voltage;
     packet.err_code = err_code;
     packet.current = current;
-    packet.cyc_cnt = cyc_cnt;
     packet.temperature = temperature;
     packet.cell_num = cell_num;
     packet.cap_percent = cap_percent;
@@ -191,8 +179,6 @@ static inline uint16_t mavlink_msg_vk_bms_status_pack_status(uint8_t system_id,
  * @param time_boot_ms [ms] Timestamp in ms from system boot.
  * @param voltage [mV] BMS voltage in mV
  * @param current [cA] BMS current in cA, negative value means in charging
- * @param cyc_cnt  BMS change and discharge
-        cycle times
  * @param temperature [degC] BMS temperature in degC
  * @param cap_percent [%] BMS remaining power in percentage
  * @param bat_id  BMS id, start from
@@ -205,7 +191,7 @@ static inline uint16_t mavlink_msg_vk_bms_status_pack_status(uint8_t system_id,
  */
 static inline uint16_t mavlink_msg_vk_bms_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
                                mavlink_message_t* msg,
-                                   uint32_t time_boot_ms,uint32_t voltage,int16_t current,uint16_t cyc_cnt,int16_t temperature,int8_t cap_percent,uint8_t bat_id,uint32_t err_code,uint16_t cell_num,const uint16_t *cell_volt)
+                                   uint32_t time_boot_ms,uint32_t voltage,int16_t current,int16_t temperature,int8_t cap_percent,uint8_t bat_id,uint32_t err_code,uint16_t cell_num,const uint16_t *cell_volt)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_VK_BMS_STATUS_LEN];
@@ -213,12 +199,11 @@ static inline uint16_t mavlink_msg_vk_bms_status_pack_chan(uint8_t system_id, ui
     _mav_put_uint32_t(buf, 4, voltage);
     _mav_put_uint32_t(buf, 8, err_code);
     _mav_put_int16_t(buf, 12, current);
-    _mav_put_uint16_t(buf, 14, cyc_cnt);
-    _mav_put_int16_t(buf, 16, temperature);
-    _mav_put_uint16_t(buf, 18, cell_num);
-    _mav_put_int8_t(buf, 80, cap_percent);
-    _mav_put_uint8_t(buf, 81, bat_id);
-    _mav_put_uint16_t_array(buf, 20, cell_volt, 30);
+    _mav_put_int16_t(buf, 14, temperature);
+    _mav_put_uint16_t(buf, 16, cell_num);
+    _mav_put_int8_t(buf, 78, cap_percent);
+    _mav_put_uint8_t(buf, 79, bat_id);
+    _mav_put_uint16_t_array(buf, 18, cell_volt, 30);
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VK_BMS_STATUS_LEN);
 #else
     mavlink_vk_bms_status_t packet;
@@ -226,7 +211,6 @@ static inline uint16_t mavlink_msg_vk_bms_status_pack_chan(uint8_t system_id, ui
     packet.voltage = voltage;
     packet.err_code = err_code;
     packet.current = current;
-    packet.cyc_cnt = cyc_cnt;
     packet.temperature = temperature;
     packet.cell_num = cell_num;
     packet.cap_percent = cap_percent;
@@ -249,7 +233,7 @@ static inline uint16_t mavlink_msg_vk_bms_status_pack_chan(uint8_t system_id, ui
  */
 static inline uint16_t mavlink_msg_vk_bms_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_vk_bms_status_t* vk_bms_status)
 {
-    return mavlink_msg_vk_bms_status_pack(system_id, component_id, msg, vk_bms_status->time_boot_ms, vk_bms_status->voltage, vk_bms_status->current, vk_bms_status->cyc_cnt, vk_bms_status->temperature, vk_bms_status->cap_percent, vk_bms_status->bat_id, vk_bms_status->err_code, vk_bms_status->cell_num, vk_bms_status->cell_volt);
+    return mavlink_msg_vk_bms_status_pack(system_id, component_id, msg, vk_bms_status->time_boot_ms, vk_bms_status->voltage, vk_bms_status->current, vk_bms_status->temperature, vk_bms_status->cap_percent, vk_bms_status->bat_id, vk_bms_status->err_code, vk_bms_status->cell_num, vk_bms_status->cell_volt);
 }
 
 /**
@@ -263,7 +247,7 @@ static inline uint16_t mavlink_msg_vk_bms_status_encode(uint8_t system_id, uint8
  */
 static inline uint16_t mavlink_msg_vk_bms_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_vk_bms_status_t* vk_bms_status)
 {
-    return mavlink_msg_vk_bms_status_pack_chan(system_id, component_id, chan, msg, vk_bms_status->time_boot_ms, vk_bms_status->voltage, vk_bms_status->current, vk_bms_status->cyc_cnt, vk_bms_status->temperature, vk_bms_status->cap_percent, vk_bms_status->bat_id, vk_bms_status->err_code, vk_bms_status->cell_num, vk_bms_status->cell_volt);
+    return mavlink_msg_vk_bms_status_pack_chan(system_id, component_id, chan, msg, vk_bms_status->time_boot_ms, vk_bms_status->voltage, vk_bms_status->current, vk_bms_status->temperature, vk_bms_status->cap_percent, vk_bms_status->bat_id, vk_bms_status->err_code, vk_bms_status->cell_num, vk_bms_status->cell_volt);
 }
 
 /**
@@ -277,7 +261,7 @@ static inline uint16_t mavlink_msg_vk_bms_status_encode_chan(uint8_t system_id,
  */
 static inline uint16_t mavlink_msg_vk_bms_status_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_vk_bms_status_t* vk_bms_status)
 {
-    return mavlink_msg_vk_bms_status_pack_status(system_id, component_id, _status, msg,  vk_bms_status->time_boot_ms, vk_bms_status->voltage, vk_bms_status->current, vk_bms_status->cyc_cnt, vk_bms_status->temperature, vk_bms_status->cap_percent, vk_bms_status->bat_id, vk_bms_status->err_code, vk_bms_status->cell_num, vk_bms_status->cell_volt);
+    return mavlink_msg_vk_bms_status_pack_status(system_id, component_id, _status, msg,  vk_bms_status->time_boot_ms, vk_bms_status->voltage, vk_bms_status->current, vk_bms_status->temperature, vk_bms_status->cap_percent, vk_bms_status->bat_id, vk_bms_status->err_code, vk_bms_status->cell_num, vk_bms_status->cell_volt);
 }
 
 /**
@@ -287,8 +271,6 @@ static inline uint16_t mavlink_msg_vk_bms_status_encode_status(uint8_t system_id
  * @param time_boot_ms [ms] Timestamp in ms from system boot.
  * @param voltage [mV] BMS voltage in mV
  * @param current [cA] BMS current in cA, negative value means in charging
- * @param cyc_cnt  BMS change and discharge
-        cycle times
  * @param temperature [degC] BMS temperature in degC
  * @param cap_percent [%] BMS remaining power in percentage
  * @param bat_id  BMS id, start from
@@ -300,7 +282,7 @@ static inline uint16_t mavlink_msg_vk_bms_status_encode_status(uint8_t system_id
  */
 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
-static inline void mavlink_msg_vk_bms_status_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint32_t voltage, int16_t current, uint16_t cyc_cnt, int16_t temperature, int8_t cap_percent, uint8_t bat_id, uint32_t err_code, uint16_t cell_num, const uint16_t *cell_volt)
+static inline void mavlink_msg_vk_bms_status_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint32_t voltage, int16_t current, int16_t temperature, int8_t cap_percent, uint8_t bat_id, uint32_t err_code, uint16_t cell_num, const uint16_t *cell_volt)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_VK_BMS_STATUS_LEN];
@@ -308,12 +290,11 @@ static inline void mavlink_msg_vk_bms_status_send(mavlink_channel_t chan, uint32
     _mav_put_uint32_t(buf, 4, voltage);
     _mav_put_uint32_t(buf, 8, err_code);
     _mav_put_int16_t(buf, 12, current);
-    _mav_put_uint16_t(buf, 14, cyc_cnt);
-    _mav_put_int16_t(buf, 16, temperature);
-    _mav_put_uint16_t(buf, 18, cell_num);
-    _mav_put_int8_t(buf, 80, cap_percent);
-    _mav_put_uint8_t(buf, 81, bat_id);
-    _mav_put_uint16_t_array(buf, 20, cell_volt, 30);
+    _mav_put_int16_t(buf, 14, temperature);
+    _mav_put_uint16_t(buf, 16, cell_num);
+    _mav_put_int8_t(buf, 78, cap_percent);
+    _mav_put_uint8_t(buf, 79, bat_id);
+    _mav_put_uint16_t_array(buf, 18, cell_volt, 30);
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VK_BMS_STATUS, buf, MAVLINK_MSG_ID_VK_BMS_STATUS_MIN_LEN, MAVLINK_MSG_ID_VK_BMS_STATUS_LEN, MAVLINK_MSG_ID_VK_BMS_STATUS_CRC);
 #else
     mavlink_vk_bms_status_t packet;
@@ -321,7 +302,6 @@ static inline void mavlink_msg_vk_bms_status_send(mavlink_channel_t chan, uint32
     packet.voltage = voltage;
     packet.err_code = err_code;
     packet.current = current;
-    packet.cyc_cnt = cyc_cnt;
     packet.temperature = temperature;
     packet.cell_num = cell_num;
     packet.cap_percent = cap_percent;
@@ -339,7 +319,7 @@ static inline void mavlink_msg_vk_bms_status_send(mavlink_channel_t chan, uint32
 static inline void mavlink_msg_vk_bms_status_send_struct(mavlink_channel_t chan, const mavlink_vk_bms_status_t* vk_bms_status)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
-    mavlink_msg_vk_bms_status_send(chan, vk_bms_status->time_boot_ms, vk_bms_status->voltage, vk_bms_status->current, vk_bms_status->cyc_cnt, vk_bms_status->temperature, vk_bms_status->cap_percent, vk_bms_status->bat_id, vk_bms_status->err_code, vk_bms_status->cell_num, vk_bms_status->cell_volt);
+    mavlink_msg_vk_bms_status_send(chan, vk_bms_status->time_boot_ms, vk_bms_status->voltage, vk_bms_status->current, vk_bms_status->temperature, vk_bms_status->cap_percent, vk_bms_status->bat_id, vk_bms_status->err_code, vk_bms_status->cell_num, vk_bms_status->cell_volt);
 #else
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VK_BMS_STATUS, (const char *)vk_bms_status, MAVLINK_MSG_ID_VK_BMS_STATUS_MIN_LEN, MAVLINK_MSG_ID_VK_BMS_STATUS_LEN, MAVLINK_MSG_ID_VK_BMS_STATUS_CRC);
 #endif
@@ -353,7 +333,7 @@ static inline void mavlink_msg_vk_bms_status_send_struct(mavlink_channel_t chan,
   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_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint32_t time_boot_ms, uint32_t voltage, int16_t current, uint16_t cyc_cnt, int16_t temperature, int8_t cap_percent, uint8_t bat_id, uint32_t err_code, uint16_t cell_num, const uint16_t *cell_volt)
+static inline void mavlink_msg_vk_bms_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint32_t time_boot_ms, uint32_t voltage, int16_t current, int16_t temperature, int8_t cap_percent, uint8_t bat_id, uint32_t err_code, uint16_t cell_num, const uint16_t *cell_volt)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char *buf = (char *)msgbuf;
@@ -361,12 +341,11 @@ static inline void mavlink_msg_vk_bms_status_send_buf(mavlink_message_t *msgbuf,
     _mav_put_uint32_t(buf, 4, voltage);
     _mav_put_uint32_t(buf, 8, err_code);
     _mav_put_int16_t(buf, 12, current);
-    _mav_put_uint16_t(buf, 14, cyc_cnt);
-    _mav_put_int16_t(buf, 16, temperature);
-    _mav_put_uint16_t(buf, 18, cell_num);
-    _mav_put_int8_t(buf, 80, cap_percent);
-    _mav_put_uint8_t(buf, 81, bat_id);
-    _mav_put_uint16_t_array(buf, 20, cell_volt, 30);
+    _mav_put_int16_t(buf, 14, temperature);
+    _mav_put_uint16_t(buf, 16, cell_num);
+    _mav_put_int8_t(buf, 78, cap_percent);
+    _mav_put_uint8_t(buf, 79, bat_id);
+    _mav_put_uint16_t_array(buf, 18, cell_volt, 30);
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VK_BMS_STATUS, buf, MAVLINK_MSG_ID_VK_BMS_STATUS_MIN_LEN, MAVLINK_MSG_ID_VK_BMS_STATUS_LEN, MAVLINK_MSG_ID_VK_BMS_STATUS_CRC);
 #else
     mavlink_vk_bms_status_t *packet = (mavlink_vk_bms_status_t *)msgbuf;
@@ -374,7 +353,6 @@ static inline void mavlink_msg_vk_bms_status_send_buf(mavlink_message_t *msgbuf,
     packet->voltage = voltage;
     packet->err_code = err_code;
     packet->current = current;
-    packet->cyc_cnt = cyc_cnt;
     packet->temperature = temperature;
     packet->cell_num = cell_num;
     packet->cap_percent = cap_percent;
@@ -420,17 +398,6 @@ static inline int16_t mavlink_msg_vk_bms_status_get_current(const mavlink_messag
     return _MAV_RETURN_int16_t(msg,  12);
 }
 
-/**
- * @brief Get field cyc_cnt from vk_bms_status message
- *
- * @return  BMS change and discharge
-        cycle times
- */
-static inline uint16_t mavlink_msg_vk_bms_status_get_cyc_cnt(const mavlink_message_t* msg)
-{
-    return _MAV_RETURN_uint16_t(msg,  14);
-}
-
 /**
  * @brief Get field temperature from vk_bms_status message
  *
@@ -438,7 +405,7 @@ static inline uint16_t mavlink_msg_vk_bms_status_get_cyc_cnt(const mavlink_messa
  */
 static inline int16_t mavlink_msg_vk_bms_status_get_temperature(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_int16_t(msg,  16);
+    return _MAV_RETURN_int16_t(msg,  14);
 }
 
 /**
@@ -448,7 +415,7 @@ static inline int16_t mavlink_msg_vk_bms_status_get_temperature(const mavlink_me
  */
 static inline int8_t mavlink_msg_vk_bms_status_get_cap_percent(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_int8_t(msg,  80);
+    return _MAV_RETURN_int8_t(msg,  78);
 }
 
 /**
@@ -459,7 +426,7 @@ static inline int8_t mavlink_msg_vk_bms_status_get_cap_percent(const mavlink_mes
  */
 static inline uint8_t mavlink_msg_vk_bms_status_get_bat_id(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint8_t(msg,  81);
+    return _MAV_RETURN_uint8_t(msg,  79);
 }
 
 /**
@@ -480,7 +447,7 @@ static inline uint32_t mavlink_msg_vk_bms_status_get_err_code(const mavlink_mess
  */
 static inline uint16_t mavlink_msg_vk_bms_status_get_cell_num(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint16_t(msg,  18);
+    return _MAV_RETURN_uint16_t(msg,  16);
 }
 
 /**
@@ -490,7 +457,7 @@ static inline uint16_t mavlink_msg_vk_bms_status_get_cell_num(const mavlink_mess
  */
 static inline uint16_t mavlink_msg_vk_bms_status_get_cell_volt(const mavlink_message_t* msg, uint16_t *cell_volt)
 {
-    return _MAV_RETURN_uint16_t_array(msg, cell_volt, 30,  20);
+    return _MAV_RETURN_uint16_t_array(msg, cell_volt, 30,  18);
 }
 
 /**
@@ -506,7 +473,6 @@ static inline void mavlink_msg_vk_bms_status_decode(const mavlink_message_t* msg
     vk_bms_status->voltage = mavlink_msg_vk_bms_status_get_voltage(msg);
     vk_bms_status->err_code = mavlink_msg_vk_bms_status_get_err_code(msg);
     vk_bms_status->current = mavlink_msg_vk_bms_status_get_current(msg);
-    vk_bms_status->cyc_cnt = mavlink_msg_vk_bms_status_get_cyc_cnt(msg);
     vk_bms_status->temperature = mavlink_msg_vk_bms_status_get_temperature(msg);
     vk_bms_status->cell_num = mavlink_msg_vk_bms_status_get_cell_num(msg);
     mavlink_msg_vk_bms_status_get_cell_volt(msg, vk_bms_status->cell_volt);

+ 393 - 0
v2.0/VKFly/mavlink_msg_vk_digi_esc_status.h

@@ -0,0 +1,393 @@
+#pragma once
+// MESSAGE VK_DIGI_ESC_STATUS PACKING
+
+#define MAVLINK_MSG_ID_VK_DIGI_ESC_STATUS 53005
+
+
+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*/
+} 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_CRC 25
+#define MAVLINK_MSG_ID_53005_CRC 25
+
+#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
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_VK_DIGI_ESC_STATUS { \
+    53005, \
+    "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) }, \
+         } \
+}
+#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) }, \
+         } \
+}
+#endif
+
+/**
+ * @brief Pack a vk_digi_esc_status 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 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
+ * @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)
+{
+#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);
+        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);
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VK_DIGI_ESC_STATUS_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_VK_DIGI_ESC_STATUS;
+    return mavlink_finalize_message(msg, system_id, component_id, 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);
+}
+
+/**
+ * @brief Pack a vk_digi_esc_status 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 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
+ * @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)
+{
+#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);
+        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);
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VK_DIGI_ESC_STATUS_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_VK_DIGI_ESC_STATUS;
+#if MAVLINK_CRC_EXTRA
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _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);
+#else
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_VK_DIGI_ESC_STATUS_MIN_LEN, MAVLINK_MSG_ID_VK_DIGI_ESC_STATUS_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a vk_digi_esc_status 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 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
+ * @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)
+{
+#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);
+        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);
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VK_DIGI_ESC_STATUS_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_VK_DIGI_ESC_STATUS;
+    return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 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);
+}
+
+/**
+ * @brief Encode a vk_digi_esc_status 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_digi_esc_status C-struct to read the message contents from
+ */
+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);
+}
+
+/**
+ * @brief Encode a vk_digi_esc_status 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_digi_esc_status C-struct to read the message contents from
+ */
+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);
+}
+
+/**
+ * @brief Encode a vk_digi_esc_status 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_digi_esc_status C-struct to read the message contents from
+ */
+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);
+}
+
+/**
+ * @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
+ */
+#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)
+{
+#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_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);
+    _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
+}
+
+/**
+ * @brief Send a vk_digi_esc_status message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+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);
+#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
+}
+
+#if MAVLINK_MSG_ID_VK_DIGI_ESC_STATUS_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_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)
+{
+#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_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);
+    _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
+}
+#endif
+
+#endif
+
+// MESSAGE VK_DIGI_ESC_STATUS UNPACKING
+
+
+/**
+ * @brief Get field time_boot_ms from vk_digi_esc_status message
+ *
+ * @return [ms] Timestamp in ms from system boot.
+ */
+static inline uint32_t mavlink_msg_vk_digi_esc_status_get_time_boot_ms(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint32_t(msg,  0);
+}
+
+/**
+ * @brief Get field rot_spd from vk_digi_esc_status message
+ *
+ * @return  BMS manufactor string
+ */
+static inline uint16_t mavlink_msg_vk_digi_esc_status_get_rot_spd(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint16_t(msg,  4);
+}
+
+/**
+ * @brief Get field model_name from vk_digi_esc_status message
+ *
+ * @return  BMS equpment model name string
+ */
+static inline uint16_t mavlink_msg_vk_digi_esc_status_get_model_name(const mavlink_message_t* msg, uint8_t *model_name)
+{
+    return _MAV_RETURN_uint8_t_array(msg, model_name, 20,  6);
+}
+
+/**
+ * @brief Get field sn_id from vk_digi_esc_status message
+ *
+ * @return  BMS SN id string
+ */
+static inline uint16_t mavlink_msg_vk_digi_esc_status_get_sn_id(const mavlink_message_t* msg, uint8_t *sn_id)
+{
+    return _MAV_RETURN_uint8_t_array(msg, sn_id, 20,  26);
+}
+
+/**
+ * @brief Get field hw_ver from vk_digi_esc_status message
+ *
+ * @return  BMS hardware version string
+ */
+static inline uint16_t mavlink_msg_vk_digi_esc_status_get_hw_ver(const mavlink_message_t* msg, uint8_t *hw_ver)
+{
+    return _MAV_RETURN_uint8_t_array(msg, hw_ver, 10,  46);
+}
+
+/**
+ * @brief Get field fw_ver from vk_digi_esc_status message
+ *
+ * @return  BMS firmware version string
+ */
+static inline uint16_t mavlink_msg_vk_digi_esc_status_get_fw_ver(const mavlink_message_t* msg, uint8_t *fw_ver)
+{
+    return _MAV_RETURN_uint8_t_array(msg, fw_ver, 10,  56);
+}
+
+/**
+ * @brief Decode a vk_digi_esc_status message into a struct
+ *
+ * @param msg The message to decode
+ * @param vk_digi_esc_status C-struct to decode the message contents into
+ */
+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);
+#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);
+    memcpy(vk_digi_esc_status, _MAV_PAYLOAD(msg), len);
+#endif
+}

+ 74 - 9
v2.0/VKFly/testsuite.h

@@ -242,7 +242,7 @@ static void mavlink_test_vk_bms_status(uint8_t system_id, uint8_t component_id,
         uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
         uint16_t i;
     mavlink_vk_bms_status_t packet_in = {
-        963497464,963497672,963497880,17859,17963,18067,18171,{ 18275, 18276, 18277, 18278, 18279, 18280, 18281, 18282, 18283, 18284, 18285, 18286, 18287, 18288, 18289, 18290, 18291, 18292, 18293, 18294, 18295, 18296, 18297, 18298, 18299, 18300, 18301, 18302, 18303, 18304 },245,56
+        963497464,963497672,963497880,17859,17963,18067,{ 18171, 18172, 18173, 18174, 18175, 18176, 18177, 18178, 18179, 18180, 18181, 18182, 18183, 18184, 18185, 18186, 18187, 18188, 18189, 18190, 18191, 18192, 18193, 18194, 18195, 18196, 18197, 18198, 18199, 18200 },111,178
     };
     mavlink_vk_bms_status_t packet1, packet2;
         memset(&packet1, 0, sizeof(packet1));
@@ -250,7 +250,6 @@ static void mavlink_test_vk_bms_status(uint8_t system_id, uint8_t component_id,
         packet1.voltage = packet_in.voltage;
         packet1.err_code = packet_in.err_code;
         packet1.current = packet_in.current;
-        packet1.cyc_cnt = packet_in.cyc_cnt;
         packet1.temperature = packet_in.temperature;
         packet1.cell_num = packet_in.cell_num;
         packet1.cap_percent = packet_in.cap_percent;
@@ -270,12 +269,12 @@ static void mavlink_test_vk_bms_status(uint8_t system_id, uint8_t component_id,
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_vk_bms_status_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.voltage , packet1.current , packet1.cyc_cnt , packet1.temperature , packet1.cap_percent , packet1.bat_id , packet1.err_code , packet1.cell_num , packet1.cell_volt );
+    mavlink_msg_vk_bms_status_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.voltage , packet1.current , packet1.temperature , packet1.cap_percent , packet1.bat_id , packet1.err_code , packet1.cell_num , packet1.cell_volt );
     mavlink_msg_vk_bms_status_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_vk_bms_status_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.voltage , packet1.current , packet1.cyc_cnt , packet1.temperature , packet1.cap_percent , packet1.bat_id , packet1.err_code , packet1.cell_num , packet1.cell_volt );
+    mavlink_msg_vk_bms_status_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.voltage , packet1.current , packet1.temperature , packet1.cap_percent , packet1.bat_id , packet1.err_code , packet1.cell_num , packet1.cell_volt );
     mavlink_msg_vk_bms_status_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
@@ -288,7 +287,7 @@ static void mavlink_test_vk_bms_status(uint8_t system_id, uint8_t component_id,
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
         
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_vk_bms_status_send(MAVLINK_COMM_1 , packet1.time_boot_ms , packet1.voltage , packet1.current , packet1.cyc_cnt , packet1.temperature , packet1.cap_percent , packet1.bat_id , packet1.err_code , packet1.cell_num , packet1.cell_volt );
+    mavlink_msg_vk_bms_status_send(MAVLINK_COMM_1 , packet1.time_boot_ms , packet1.voltage , packet1.current , packet1.temperature , packet1.cap_percent , packet1.bat_id , packet1.err_code , packet1.cell_num , packet1.cell_volt );
     mavlink_msg_vk_bms_status_decode(last_msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
@@ -310,11 +309,12 @@ static void mavlink_test_vk_bms_info(uint8_t system_id, uint8_t component_id, ma
         uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
         uint16_t i;
     mavlink_vk_bms_info_t packet_in = {
-        963497464,{ 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 36 },{ 77, 78, 79, 80, 81, 82, 83, 84, 85, 86, 87, 88, 89, 90, 91, 92, 93, 94, 95, 96 },{ 137, 138, 139, 140, 141, 142, 143, 144, 145, 146, 147, 148, 149, 150, 151, 152, 153, 154, 155, 156 },{ 197, 198, 199, 200, 201, 202, 203, 204, 205, 206 },{ 99, 100, 101, 102, 103, 104, 105, 106, 107, 108 }
+        963497464,17443,{ 151, 152, 153, 154, 155, 156, 157, 158, 159, 160, 161, 162, 163, 164, 165, 166, 167, 168, 169, 170 },{ 211, 212, 213, 214, 215, 216, 217, 218, 219, 220, 221, 222, 223, 224, 225, 226, 227, 228, 229, 230 },{ 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34 },{ 75, 76, 77, 78, 79, 80, 81, 82, 83, 84 },{ 233, 234, 235, 236, 237, 238, 239, 240, 241, 242 }
     };
     mavlink_vk_bms_info_t packet1, packet2;
         memset(&packet1, 0, sizeof(packet1));
         packet1.time_boot_ms = packet_in.time_boot_ms;
+        packet1.cyc_cnt = packet_in.cyc_cnt;
         
         mav_array_memcpy(packet1.man_name, packet_in.man_name, sizeof(uint8_t)*20);
         mav_array_memcpy(packet1.model_name, packet_in.model_name, sizeof(uint8_t)*20);
@@ -334,12 +334,12 @@ static void mavlink_test_vk_bms_info(uint8_t system_id, uint8_t component_id, ma
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_vk_bms_info_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.man_name , packet1.model_name , packet1.sn_id , packet1.hw_ver , packet1.fw_ver );
+    mavlink_msg_vk_bms_info_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.man_name , packet1.model_name , packet1.sn_id , packet1.hw_ver , packet1.fw_ver , packet1.cyc_cnt );
     mavlink_msg_vk_bms_info_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_vk_bms_info_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.man_name , packet1.model_name , packet1.sn_id , packet1.hw_ver , packet1.fw_ver );
+    mavlink_msg_vk_bms_info_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.man_name , packet1.model_name , packet1.sn_id , packet1.hw_ver , packet1.fw_ver , packet1.cyc_cnt );
     mavlink_msg_vk_bms_info_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
@@ -352,7 +352,7 @@ static void mavlink_test_vk_bms_info(uint8_t system_id, uint8_t component_id, ma
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
         
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_vk_bms_info_send(MAVLINK_COMM_1 , packet1.time_boot_ms , packet1.man_name , packet1.model_name , packet1.sn_id , packet1.hw_ver , packet1.fw_ver );
+    mavlink_msg_vk_bms_info_send(MAVLINK_COMM_1 , packet1.time_boot_ms , packet1.man_name , packet1.model_name , packet1.sn_id , packet1.hw_ver , packet1.fw_ver , packet1.cyc_cnt );
     mavlink_msg_vk_bms_info_decode(last_msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
@@ -362,6 +362,70 @@ static void mavlink_test_vk_bms_info(uint8_t system_id, uint8_t component_id, ma
 #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,17443,{ 151, 152, 153, 154, 155, 156, 157, 158, 159, 160, 161, 162, 163, 164, 165, 166, 167, 168, 169, 170 },{ 211, 212, 213, 214, 215, 216, 217, 218, 219, 220, 221, 222, 223, 224, 225, 226, 227, 228, 229, 230 },{ 15, 16, 17, 18, 19, 20, 21, 22, 23, 24 },{ 173, 174, 175, 176, 177, 178, 179, 180, 181, 182 }
+    };
+    mavlink_vk_digi_esc_status_t packet1, packet2;
+        memset(&packet1, 0, sizeof(packet1));
+        packet1.time_boot_ms = packet_in.time_boot_ms;
+        packet1.rot_spd = packet_in.rot_spd;
+        
+        mav_array_memcpy(packet1.model_name, packet_in.model_name, sizeof(uint8_t)*20);
+        mav_array_memcpy(packet1.sn_id, packet_in.sn_id, sizeof(uint8_t)*20);
+        mav_array_memcpy(packet1.hw_ver, packet_in.hw_ver, sizeof(uint8_t)*10);
+        mav_array_memcpy(packet1.fw_ver, packet_in.fw_ver, sizeof(uint8_t)*10);
+        
+#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.time_boot_ms , packet1.rot_spd , packet1.model_name , packet1.sn_id , packet1.hw_ver , packet1.fw_ver );
+    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.time_boot_ms , packet1.rot_spd , packet1.model_name , packet1.sn_id , packet1.hw_ver , packet1.fw_ver );
+    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.time_boot_ms , packet1.rot_spd , packet1.model_name , packet1.sn_id , packet1.hw_ver , packet1.fw_ver );
+    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_fw_update_begin(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
 {
 #ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
@@ -670,6 +734,7 @@ static void mavlink_test_VKFly(uint8_t system_id, uint8_t component_id, mavlink_
     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_bms_info(system_id, component_id, last_msg);
+    mavlink_test_vk_digi_esc_status(system_id, component_id, last_msg);
     mavlink_test_vk_fw_update_begin(system_id, component_id, last_msg);
     mavlink_test_vk_fw_update_ack(system_id, component_id, last_msg);
     mavlink_test_vk_fw_update_data_request(system_id, component_id, last_msg);

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

@@ -7,7 +7,7 @@
 #ifndef MAVLINK_VERSION_H
 #define MAVLINK_VERSION_H
 
-#define MAVLINK_BUILD_DATE "Tue Jun 18 2024"
+#define MAVLINK_BUILD_DATE "Wed Jun 19 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 106691953288040693
+#define MAVLINK_COMMON_XML_HASH -4853935762338562696
 
 #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 106691953288040693
+#define MAVLINK_PRIMARY_XML_HASH -4853935762338562696
 
 #ifndef MAVLINK_STX
 #define MAVLINK_STX 253

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

@@ -7,7 +7,7 @@
 #ifndef MAVLINK_VERSION_H
 #define MAVLINK_VERSION_H
 
-#define MAVLINK_BUILD_DATE "Tue Jun 18 2024"
+#define MAVLINK_BUILD_DATE "Wed Jun 19 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 -1082902482250457618
+#define MAVLINK_PRIMARY_XML_HASH 7502694402685973443
 
 #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 -1082902482250457618
+#define MAVLINK_MINIMAL_XML_HASH 7502694402685973443
 
 #ifdef __cplusplus
 extern "C" {

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

@@ -7,7 +7,7 @@
 #ifndef MAVLINK_VERSION_H
 #define MAVLINK_VERSION_H
 
-#define MAVLINK_BUILD_DATE "Tue Jun 18 2024"
+#define MAVLINK_BUILD_DATE "Wed Jun 19 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 1746884185192019578
+#define MAVLINK_PRIMARY_XML_HASH -133738197775166196
 
 #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 1746884185192019578
+#define MAVLINK_STANDARD_XML_HASH -133738197775166196
 
 #ifdef __cplusplus
 extern "C" {

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

@@ -7,7 +7,7 @@
 #ifndef MAVLINK_VERSION_H
 #define MAVLINK_VERSION_H
 
-#define MAVLINK_BUILD_DATE "Tue Jun 18 2024"
+#define MAVLINK_BUILD_DATE "Wed Jun 19 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