Browse Source

智能电池数据增加循环次数和健康度

Liu Yang 10 months ago
parent
commit
77ac7528a9
5 changed files with 99 additions and 202 deletions
  1. 2 22
      msg_definitions/VKFly.xml
  2. 2 12
      readme.md
  3. 0 0
      v2.0/VKFly/VKFly.h
  4. 89 33
      v2.0/VKFly/mavlink_msg_vk_bms_status.h
  5. 6 135
      v2.0/VKFly/testsuite.h

+ 2 - 22
msg_definitions/VKFly.xml

@@ -674,30 +674,10 @@
         0 means no error</field>
       <field type="uint16_t" name="cell_num" minValue="0" maxValue="100">BMS cell numbers</field>
       <field type="uint16_t[30]" name="cell_volt" units="mV">BMS cell voltage in mV</field>
+      <field type="uint16_t" name="cyc_cnt" minValue="0" increment="1"> charge and discharge times </field>
+      <field type="uint8_t" name="health" minValue="0" maxValue="100">battery healthiness in percentage</field>
     </message>
 
-    <message id="53004" name="VK_BMS_INFO">
-      <description> battery bms information message, this message can be required by
-        MAV_CMD_REQUEST_MESSAGE with param1 ad bms id </description>
-      <field type="uint32_t" name="time_boot_ms" units="ms">Timestamp in ms from system boot.</field>
-      <field type="uint8_t[20]" name="man_name">BMS manufactor string</field>
-      <field type="uint8_t[20]" name="model_name">BMS equpment model name string</field>
-      <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">
-      <description> digital esc status with can or serial interface</description>
-      <field type="uint32_t" name="time_boot_ms" units="ms">Timestamp in ms from system boot.</field>
-      <field type="uint16_t" name="rot_spd">BMS manufactor string</field>
-      <field type="uint8_t[20]" name="model_name">BMS equpment model name string</field>
-      <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>
-    </message>
 
     <message id="53006" name="VK_COMP_VERSION">
       <description>vkfly gps version</description>

+ 2 - 12
readme.md

@@ -1174,18 +1174,8 @@ mavlink common 标准消息集中主要由 MAVLINK_MSG_ID_COMMAND_INT 和 MAVLIN
   | err_code     | 故障码, 0为无故障            |
   | cell_num     | 电芯数                       |
   | cell_volt    | 电芯电压 mV                  |
-
-- **MAVLINK_VK_BMS_INFO**
-  智能电池 info 数据, 本数据可以通过 MAV_CMD_REQUEST_MESSAGE 进行读取, param2 是电池的 bat_id.
-
-  | 字段         | 说明             |
-  | ------------ | ---------------- |
-  | time_boot_ms | 系统本地时间戳ms |
-  | man_name     | 制造商名         |
-  | model_name   | 型号名           |
-  | sn_id        | 序列号           |
-  | hw_ver       | 硬件号           |
-  | fw_ver       | 软件号           |
+  | cyc_cnt      | 循环次数                     |
+  | heath        | 电池健康度 1%                |
 
 - **MAVLINK_VK_COMP_VERSION**
   设备版本信息, 本消息可以通过 MAV_CMD_REQUEST_MESSAGE 进行读取, param2 是设备的 comp_id. comp_id 为 0 时, 飞控将回复多个消息逐个返回所有可获取设备的版本信息

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


+ 89 - 33
v2.0/VKFly/mavlink_msg_vk_bms_status.h

@@ -14,18 +14,20 @@ typedef struct __mavlink_vk_bms_status_t {
  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*/
+ uint16_t cyc_cnt; /*<   charge and discharge times */
  int8_t cap_percent; /*< [%] BMS remaining power in percentage*/
  uint8_t bat_id; /*<  BMS id, start from
         0*/
+ uint8_t health; /*<  battery healthiness in percentage*/
 } mavlink_vk_bms_status_t;
 
-#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_LEN 83
+#define MAVLINK_MSG_ID_VK_BMS_STATUS_MIN_LEN 83
+#define MAVLINK_MSG_ID_53003_LEN 83
+#define MAVLINK_MSG_ID_53003_MIN_LEN 83
 
-#define MAVLINK_MSG_ID_VK_BMS_STATUS_CRC 43
-#define MAVLINK_MSG_ID_53003_CRC 43
+#define MAVLINK_MSG_ID_VK_BMS_STATUS_CRC 200
+#define MAVLINK_MSG_ID_53003_CRC 200
 
 #define MAVLINK_MSG_VK_BMS_STATUS_FIELD_CELL_VOLT_LEN 30
 
@@ -33,31 +35,35 @@ typedef struct __mavlink_vk_bms_status_t {
 #define MAVLINK_MESSAGE_INFO_VK_BMS_STATUS { \
     53003, \
     "VK_BMS_STATUS", \
-    9, \
+    11, \
     {  { "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) }, \
          { "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) }, \
+         { "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) }, \
          { "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, 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) }, \
+         { "cyc_cnt", NULL, MAVLINK_TYPE_UINT16_T, 0, 78, offsetof(mavlink_vk_bms_status_t, cyc_cnt) }, \
+         { "health", NULL, MAVLINK_TYPE_UINT8_T, 0, 82, offsetof(mavlink_vk_bms_status_t, health) }, \
          } \
 }
 #else
 #define MAVLINK_MESSAGE_INFO_VK_BMS_STATUS { \
     "VK_BMS_STATUS", \
-    9, \
+    11, \
     {  { "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) }, \
          { "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) }, \
+         { "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) }, \
          { "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, 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) }, \
+         { "cyc_cnt", NULL, MAVLINK_TYPE_UINT16_T, 0, 78, offsetof(mavlink_vk_bms_status_t, cyc_cnt) }, \
+         { "health", NULL, MAVLINK_TYPE_UINT8_T, 0, 82, offsetof(mavlink_vk_bms_status_t, health) }, \
          } \
 }
 #endif
@@ -80,10 +86,12 @@ typedef struct __mavlink_vk_bms_status_t {
         0 means no error
  * @param cell_num  BMS cell numbers
  * @param cell_volt [mV] BMS cell voltage in mV
+ * @param cyc_cnt   charge and discharge times 
+ * @param health  battery healthiness in percentage
  * @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, 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, uint16_t cyc_cnt, uint8_t health)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_VK_BMS_STATUS_LEN];
@@ -93,8 +101,10 @@ static inline uint16_t mavlink_msg_vk_bms_status_pack(uint8_t system_id, uint8_t
     _mav_put_int16_t(buf, 12, current);
     _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(buf, 78, cyc_cnt);
+    _mav_put_int8_t(buf, 80, cap_percent);
+    _mav_put_uint8_t(buf, 81, bat_id);
+    _mav_put_uint8_t(buf, 82, health);
     _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
@@ -105,8 +115,10 @@ static inline uint16_t mavlink_msg_vk_bms_status_pack(uint8_t system_id, uint8_t
     packet.current = current;
     packet.temperature = temperature;
     packet.cell_num = cell_num;
+    packet.cyc_cnt = cyc_cnt;
     packet.cap_percent = cap_percent;
     packet.bat_id = bat_id;
+    packet.health = health;
     mav_array_memcpy(packet.cell_volt, cell_volt, sizeof(uint16_t)*30);
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VK_BMS_STATUS_LEN);
 #endif
@@ -134,10 +146,12 @@ static inline uint16_t mavlink_msg_vk_bms_status_pack(uint8_t system_id, uint8_t
         0 means no error
  * @param cell_num  BMS cell numbers
  * @param cell_volt [mV] BMS cell voltage in mV
+ * @param cyc_cnt   charge and discharge times 
+ * @param health  battery healthiness in percentage
  * @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, 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, uint16_t cyc_cnt, uint8_t health)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_VK_BMS_STATUS_LEN];
@@ -147,8 +161,10 @@ static inline uint16_t mavlink_msg_vk_bms_status_pack_status(uint8_t system_id,
     _mav_put_int16_t(buf, 12, current);
     _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(buf, 78, cyc_cnt);
+    _mav_put_int8_t(buf, 80, cap_percent);
+    _mav_put_uint8_t(buf, 81, bat_id);
+    _mav_put_uint8_t(buf, 82, health);
     _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
@@ -159,8 +175,10 @@ static inline uint16_t mavlink_msg_vk_bms_status_pack_status(uint8_t system_id,
     packet.current = current;
     packet.temperature = temperature;
     packet.cell_num = cell_num;
+    packet.cyc_cnt = cyc_cnt;
     packet.cap_percent = cap_percent;
     packet.bat_id = bat_id;
+    packet.health = health;
     mav_array_memcpy(packet.cell_volt, cell_volt, sizeof(uint16_t)*30);
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VK_BMS_STATUS_LEN);
 #endif
@@ -191,11 +209,13 @@ static inline uint16_t mavlink_msg_vk_bms_status_pack_status(uint8_t system_id,
         0 means no error
  * @param cell_num  BMS cell numbers
  * @param cell_volt [mV] BMS cell voltage in mV
+ * @param cyc_cnt   charge and discharge times 
+ * @param health  battery healthiness in percentage
  * @return length of the message in bytes (excluding serial stream start sign)
  */
 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,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,uint16_t cyc_cnt,uint8_t health)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_VK_BMS_STATUS_LEN];
@@ -205,8 +225,10 @@ static inline uint16_t mavlink_msg_vk_bms_status_pack_chan(uint8_t system_id, ui
     _mav_put_int16_t(buf, 12, current);
     _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(buf, 78, cyc_cnt);
+    _mav_put_int8_t(buf, 80, cap_percent);
+    _mav_put_uint8_t(buf, 81, bat_id);
+    _mav_put_uint8_t(buf, 82, health);
     _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
@@ -217,8 +239,10 @@ static inline uint16_t mavlink_msg_vk_bms_status_pack_chan(uint8_t system_id, ui
     packet.current = current;
     packet.temperature = temperature;
     packet.cell_num = cell_num;
+    packet.cyc_cnt = cyc_cnt;
     packet.cap_percent = cap_percent;
     packet.bat_id = bat_id;
+    packet.health = health;
     mav_array_memcpy(packet.cell_volt, cell_volt, sizeof(uint16_t)*30);
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VK_BMS_STATUS_LEN);
 #endif
@@ -237,7 +261,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->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, vk_bms_status->cyc_cnt, vk_bms_status->health);
 }
 
 /**
@@ -251,7 +275,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->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, vk_bms_status->cyc_cnt, vk_bms_status->health);
 }
 
 /**
@@ -265,7 +289,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->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, vk_bms_status->cyc_cnt, vk_bms_status->health);
 }
 
 /**
@@ -284,10 +308,12 @@ static inline uint16_t mavlink_msg_vk_bms_status_encode_status(uint8_t system_id
         0 means no error
  * @param cell_num  BMS cell numbers
  * @param cell_volt [mV] BMS cell voltage in mV
+ * @param cyc_cnt   charge and discharge times 
+ * @param health  battery healthiness in percentage
  */
 #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, 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, uint16_t cyc_cnt, uint8_t health)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_VK_BMS_STATUS_LEN];
@@ -297,8 +323,10 @@ static inline void mavlink_msg_vk_bms_status_send(mavlink_channel_t chan, uint32
     _mav_put_int16_t(buf, 12, current);
     _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(buf, 78, cyc_cnt);
+    _mav_put_int8_t(buf, 80, cap_percent);
+    _mav_put_uint8_t(buf, 81, bat_id);
+    _mav_put_uint8_t(buf, 82, health);
     _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
@@ -309,8 +337,10 @@ static inline void mavlink_msg_vk_bms_status_send(mavlink_channel_t chan, uint32
     packet.current = current;
     packet.temperature = temperature;
     packet.cell_num = cell_num;
+    packet.cyc_cnt = cyc_cnt;
     packet.cap_percent = cap_percent;
     packet.bat_id = bat_id;
+    packet.health = health;
     mav_array_memcpy(packet.cell_volt, cell_volt, sizeof(uint16_t)*30);
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VK_BMS_STATUS, (const char *)&packet, MAVLINK_MSG_ID_VK_BMS_STATUS_MIN_LEN, MAVLINK_MSG_ID_VK_BMS_STATUS_LEN, MAVLINK_MSG_ID_VK_BMS_STATUS_CRC);
 #endif
@@ -324,7 +354,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->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, vk_bms_status->cyc_cnt, vk_bms_status->health);
 #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
@@ -338,7 +368,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, 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, uint16_t cyc_cnt, uint8_t health)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char *buf = (char *)msgbuf;
@@ -348,8 +378,10 @@ static inline void mavlink_msg_vk_bms_status_send_buf(mavlink_message_t *msgbuf,
     _mav_put_int16_t(buf, 12, current);
     _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(buf, 78, cyc_cnt);
+    _mav_put_int8_t(buf, 80, cap_percent);
+    _mav_put_uint8_t(buf, 81, bat_id);
+    _mav_put_uint8_t(buf, 82, health);
     _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
@@ -360,8 +392,10 @@ static inline void mavlink_msg_vk_bms_status_send_buf(mavlink_message_t *msgbuf,
     packet->current = current;
     packet->temperature = temperature;
     packet->cell_num = cell_num;
+    packet->cyc_cnt = cyc_cnt;
     packet->cap_percent = cap_percent;
     packet->bat_id = bat_id;
+    packet->health = health;
     mav_array_memcpy(packet->cell_volt, cell_volt, sizeof(uint16_t)*30);
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VK_BMS_STATUS, (const char *)packet, MAVLINK_MSG_ID_VK_BMS_STATUS_MIN_LEN, MAVLINK_MSG_ID_VK_BMS_STATUS_LEN, MAVLINK_MSG_ID_VK_BMS_STATUS_CRC);
 #endif
@@ -421,7 +455,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,  78);
+    return _MAV_RETURN_int8_t(msg,  80);
 }
 
 /**
@@ -432,7 +466,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,  79);
+    return _MAV_RETURN_uint8_t(msg,  81);
 }
 
 /**
@@ -466,6 +500,26 @@ static inline uint16_t mavlink_msg_vk_bms_status_get_cell_volt(const mavlink_mes
     return _MAV_RETURN_uint16_t_array(msg, cell_volt, 30,  18);
 }
 
+/**
+ * @brief Get field cyc_cnt from vk_bms_status message
+ *
+ * @return   charge and discharge times 
+ */
+static inline uint16_t mavlink_msg_vk_bms_status_get_cyc_cnt(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint16_t(msg,  78);
+}
+
+/**
+ * @brief Get field health from vk_bms_status message
+ *
+ * @return  battery healthiness in percentage
+ */
+static inline uint8_t mavlink_msg_vk_bms_status_get_health(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint8_t(msg,  82);
+}
+
 /**
  * @brief Decode a vk_bms_status message into a struct
  *
@@ -482,8 +536,10 @@ static inline void mavlink_msg_vk_bms_status_decode(const mavlink_message_t* 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);
+    vk_bms_status->cyc_cnt = mavlink_msg_vk_bms_status_get_cyc_cnt(msg);
     vk_bms_status->cap_percent = mavlink_msg_vk_bms_status_get_cap_percent(msg);
     vk_bms_status->bat_id = mavlink_msg_vk_bms_status_get_bat_id(msg);
+    vk_bms_status->health = mavlink_msg_vk_bms_status_get_health(msg);
 #else
         uint8_t len = msg->len < MAVLINK_MSG_ID_VK_BMS_STATUS_LEN? msg->len : MAVLINK_MSG_ID_VK_BMS_STATUS_LEN;
         memset(vk_bms_status, 0, MAVLINK_MSG_ID_VK_BMS_STATUS_LEN);

+ 6 - 135
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, 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
+        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 },21291,245,56,123
     };
     mavlink_vk_bms_status_t packet1, packet2;
         memset(&packet1, 0, sizeof(packet1));
@@ -252,8 +252,10 @@ static void mavlink_test_vk_bms_status(uint8_t system_id, uint8_t component_id,
         packet1.current = packet_in.current;
         packet1.temperature = packet_in.temperature;
         packet1.cell_num = packet_in.cell_num;
+        packet1.cyc_cnt = packet_in.cyc_cnt;
         packet1.cap_percent = packet_in.cap_percent;
         packet1.bat_id = packet_in.bat_id;
+        packet1.health = packet_in.health;
         
         mav_array_memcpy(packet1.cell_volt, packet_in.cell_volt, sizeof(uint16_t)*30);
         
@@ -269,12 +271,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.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 , packet1.cyc_cnt , packet1.health );
     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.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 , packet1.cyc_cnt , packet1.health );
     mavlink_msg_vk_bms_status_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
@@ -287,7 +289,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.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 , packet1.cyc_cnt , packet1.health );
     mavlink_msg_vk_bms_status_decode(last_msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
@@ -297,135 +299,6 @@ static void mavlink_test_vk_bms_status(uint8_t system_id, uint8_t component_id,
 #endif
 }
 
-static void mavlink_test_vk_bms_info(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_BMS_INFO >= 256) {
-            return;
-        }
-#endif
-    mavlink_message_t msg;
-        uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
-        uint16_t i;
-    mavlink_vk_bms_info_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, 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);
-        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_BMS_INFO_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_VK_BMS_INFO_MIN_LEN);
-        }
-#endif
-        memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_vk_bms_info_encode(system_id, component_id, &msg, &packet1);
-    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(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 , 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_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_bms_info_decode(last_msg, &packet2);
-        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 , packet1.cyc_cnt );
-    mavlink_msg_vk_bms_info_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_BMS_INFO") != NULL);
-    MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_VK_BMS_INFO) != NULL);
-#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_comp_version(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
 {
 #ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
@@ -798,8 +671,6 @@ static void mavlink_test_VKFly(uint8_t system_id, uint8_t component_id, mavlink_
     mavlink_test_vkfmu_status(system_id, component_id, last_msg);
     mavlink_test_vk_roi_target(system_id, component_id, last_msg);
     mavlink_test_vk_bms_status(system_id, component_id, last_msg);
-    mavlink_test_vk_bms_info(system_id, component_id, last_msg);
-    mavlink_test_vk_digi_esc_status(system_id, component_id, last_msg);
     mavlink_test_vk_comp_version(system_id, component_id, last_msg);
     mavlink_test_vk_fw_update_begin(system_id, component_id, last_msg);
     mavlink_test_vk_fw_update_ack(system_id, component_id, last_msg);

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