Browse Source

增加 ups adc 电压数据

Liu Yang 1 year ago
parent
commit
8759e8b41e

+ 3 - 3
msg_definitions/VKFly.xml

@@ -507,7 +507,8 @@
       <field type="uint8_t" name="rtl_reason" enum="VKFLY_RTL_REASON">return to launch reason.</field>
       <field type="uint8_t" name="s_flag2">fmu sflag2</field>
       <field type="uint8_t" name="s_flag3">fmu sflag3</field>
-      <field type="uint8_t" name="s_flag4">fmu sflag4</field>
+      <field type="uint16_t" name="ups_volt">ups voltage in 0.1V</field>
+      <field type="uint16_t" name="adc_volt">adc voltage in 0.1V</field>
     </message>
 
     <message id="53100" name="VK_FW_UPDATE_BEGIN">
@@ -539,7 +540,6 @@
       <field type="uint8_t" name="target_comp">Target compid id.</field>
     </message>
 
-
   </messages>
 
-</mavlink>
+</mavlink>

+ 3 - 1
readme.md

@@ -915,7 +915,9 @@ mavlink common 标准消息集中主要由 MAVLINK_MSG_ID_COMMAND_INT 和 MAVLIN
   | rtl_reasong  | 返航原因, 参考 VKFLY_RTL_REASON |
   | s_flag2      | 预留                            |
   | s_flag3      | 预留                            |
-  | s_flag4      | ups电压, 0.1V                   |
+  | ups_volt     | ups电压, 0.1V                   |
+  | adc_volt     | adc电压, 0.1V                   |
+
 
 ## 飞控参数说明
 

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 -1458142097593788960
+#define MAVLINK_PRIMARY_XML_HASH -4486976657258493475
 
 #ifndef MAVLINK_STX
 #define MAVLINK_STX 253

+ 91 - 63
v2.0/VKFly/mavlink_msg_vkfmu_status.h

@@ -6,19 +6,20 @@
 
 typedef struct __mavlink_vkfmu_status_t {
  uint32_t time_boot_ms; /*< [ms] Timestamp in ms from system boot.*/
+ uint16_t ups_volt; /*<  ups voltage in 0.1V*/
+ uint16_t adc_volt; /*<  adc voltage in 0.1V*/
  uint8_t rtl_reason; /*<  return to launch reason.*/
  uint8_t s_flag2; /*<  fmu sflag2*/
  uint8_t s_flag3; /*<  fmu sflag3*/
- uint8_t s_flag4; /*<  fmu sflag4*/
 } mavlink_vkfmu_status_t;
 
-#define MAVLINK_MSG_ID_VKFMU_STATUS_LEN 8
-#define MAVLINK_MSG_ID_VKFMU_STATUS_MIN_LEN 8
-#define MAVLINK_MSG_ID_53001_LEN 8
-#define MAVLINK_MSG_ID_53001_MIN_LEN 8
+#define MAVLINK_MSG_ID_VKFMU_STATUS_LEN 11
+#define MAVLINK_MSG_ID_VKFMU_STATUS_MIN_LEN 11
+#define MAVLINK_MSG_ID_53001_LEN 11
+#define MAVLINK_MSG_ID_53001_MIN_LEN 11
 
-#define MAVLINK_MSG_ID_VKFMU_STATUS_CRC 81
-#define MAVLINK_MSG_ID_53001_CRC 81
+#define MAVLINK_MSG_ID_VKFMU_STATUS_CRC 31
+#define MAVLINK_MSG_ID_53001_CRC 31
 
 
 
@@ -26,23 +27,25 @@ typedef struct __mavlink_vkfmu_status_t {
 #define MAVLINK_MESSAGE_INFO_VKFMU_STATUS { \
     53001, \
     "VKFMU_STATUS", \
-    5, \
+    6, \
     {  { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_vkfmu_status_t, time_boot_ms) }, \
-         { "rtl_reason", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_vkfmu_status_t, rtl_reason) }, \
-         { "s_flag2", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_vkfmu_status_t, s_flag2) }, \
-         { "s_flag3", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_vkfmu_status_t, s_flag3) }, \
-         { "s_flag4", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_vkfmu_status_t, s_flag4) }, \
+         { "rtl_reason", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_vkfmu_status_t, rtl_reason) }, \
+         { "s_flag2", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_vkfmu_status_t, s_flag2) }, \
+         { "s_flag3", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_vkfmu_status_t, s_flag3) }, \
+         { "ups_volt", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_vkfmu_status_t, ups_volt) }, \
+         { "adc_volt", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_vkfmu_status_t, adc_volt) }, \
          } \
 }
 #else
 #define MAVLINK_MESSAGE_INFO_VKFMU_STATUS { \
     "VKFMU_STATUS", \
-    5, \
+    6, \
     {  { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_vkfmu_status_t, time_boot_ms) }, \
-         { "rtl_reason", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_vkfmu_status_t, rtl_reason) }, \
-         { "s_flag2", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_vkfmu_status_t, s_flag2) }, \
-         { "s_flag3", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_vkfmu_status_t, s_flag3) }, \
-         { "s_flag4", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_vkfmu_status_t, s_flag4) }, \
+         { "rtl_reason", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_vkfmu_status_t, rtl_reason) }, \
+         { "s_flag2", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_vkfmu_status_t, s_flag2) }, \
+         { "s_flag3", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_vkfmu_status_t, s_flag3) }, \
+         { "ups_volt", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_vkfmu_status_t, ups_volt) }, \
+         { "adc_volt", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_vkfmu_status_t, adc_volt) }, \
          } \
 }
 #endif
@@ -57,28 +60,31 @@ typedef struct __mavlink_vkfmu_status_t {
  * @param rtl_reason  return to launch reason.
  * @param s_flag2  fmu sflag2
  * @param s_flag3  fmu sflag3
- * @param s_flag4  fmu sflag4
+ * @param ups_volt  ups voltage in 0.1V
+ * @param adc_volt  adc voltage in 0.1V
  * @return length of the message in bytes (excluding serial stream start sign)
  */
 static inline uint16_t mavlink_msg_vkfmu_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
-                               uint32_t time_boot_ms, uint8_t rtl_reason, uint8_t s_flag2, uint8_t s_flag3, uint8_t s_flag4)
+                               uint32_t time_boot_ms, uint8_t rtl_reason, uint8_t s_flag2, uint8_t s_flag3, uint16_t ups_volt, uint16_t adc_volt)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_VKFMU_STATUS_LEN];
     _mav_put_uint32_t(buf, 0, time_boot_ms);
-    _mav_put_uint8_t(buf, 4, rtl_reason);
-    _mav_put_uint8_t(buf, 5, s_flag2);
-    _mav_put_uint8_t(buf, 6, s_flag3);
-    _mav_put_uint8_t(buf, 7, s_flag4);
+    _mav_put_uint16_t(buf, 4, ups_volt);
+    _mav_put_uint16_t(buf, 6, adc_volt);
+    _mav_put_uint8_t(buf, 8, rtl_reason);
+    _mav_put_uint8_t(buf, 9, s_flag2);
+    _mav_put_uint8_t(buf, 10, s_flag3);
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VKFMU_STATUS_LEN);
 #else
     mavlink_vkfmu_status_t packet;
     packet.time_boot_ms = time_boot_ms;
+    packet.ups_volt = ups_volt;
+    packet.adc_volt = adc_volt;
     packet.rtl_reason = rtl_reason;
     packet.s_flag2 = s_flag2;
     packet.s_flag3 = s_flag3;
-    packet.s_flag4 = s_flag4;
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VKFMU_STATUS_LEN);
 #endif
@@ -98,28 +104,31 @@ static inline uint16_t mavlink_msg_vkfmu_status_pack(uint8_t system_id, uint8_t
  * @param rtl_reason  return to launch reason.
  * @param s_flag2  fmu sflag2
  * @param s_flag3  fmu sflag3
- * @param s_flag4  fmu sflag4
+ * @param ups_volt  ups voltage in 0.1V
+ * @param adc_volt  adc voltage in 0.1V
  * @return length of the message in bytes (excluding serial stream start sign)
  */
 static inline uint16_t mavlink_msg_vkfmu_status_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
-                               uint32_t time_boot_ms, uint8_t rtl_reason, uint8_t s_flag2, uint8_t s_flag3, uint8_t s_flag4)
+                               uint32_t time_boot_ms, uint8_t rtl_reason, uint8_t s_flag2, uint8_t s_flag3, uint16_t ups_volt, uint16_t adc_volt)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_VKFMU_STATUS_LEN];
     _mav_put_uint32_t(buf, 0, time_boot_ms);
-    _mav_put_uint8_t(buf, 4, rtl_reason);
-    _mav_put_uint8_t(buf, 5, s_flag2);
-    _mav_put_uint8_t(buf, 6, s_flag3);
-    _mav_put_uint8_t(buf, 7, s_flag4);
+    _mav_put_uint16_t(buf, 4, ups_volt);
+    _mav_put_uint16_t(buf, 6, adc_volt);
+    _mav_put_uint8_t(buf, 8, rtl_reason);
+    _mav_put_uint8_t(buf, 9, s_flag2);
+    _mav_put_uint8_t(buf, 10, s_flag3);
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VKFMU_STATUS_LEN);
 #else
     mavlink_vkfmu_status_t packet;
     packet.time_boot_ms = time_boot_ms;
+    packet.ups_volt = ups_volt;
+    packet.adc_volt = adc_volt;
     packet.rtl_reason = rtl_reason;
     packet.s_flag2 = s_flag2;
     packet.s_flag3 = s_flag3;
-    packet.s_flag4 = s_flag4;
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VKFMU_STATUS_LEN);
 #endif
@@ -142,29 +151,32 @@ static inline uint16_t mavlink_msg_vkfmu_status_pack_status(uint8_t system_id, u
  * @param rtl_reason  return to launch reason.
  * @param s_flag2  fmu sflag2
  * @param s_flag3  fmu sflag3
- * @param s_flag4  fmu sflag4
+ * @param ups_volt  ups voltage in 0.1V
+ * @param adc_volt  adc voltage in 0.1V
  * @return length of the message in bytes (excluding serial stream start sign)
  */
 static inline uint16_t mavlink_msg_vkfmu_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
                                mavlink_message_t* msg,
-                                   uint32_t time_boot_ms,uint8_t rtl_reason,uint8_t s_flag2,uint8_t s_flag3,uint8_t s_flag4)
+                                   uint32_t time_boot_ms,uint8_t rtl_reason,uint8_t s_flag2,uint8_t s_flag3,uint16_t ups_volt,uint16_t adc_volt)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_VKFMU_STATUS_LEN];
     _mav_put_uint32_t(buf, 0, time_boot_ms);
-    _mav_put_uint8_t(buf, 4, rtl_reason);
-    _mav_put_uint8_t(buf, 5, s_flag2);
-    _mav_put_uint8_t(buf, 6, s_flag3);
-    _mav_put_uint8_t(buf, 7, s_flag4);
+    _mav_put_uint16_t(buf, 4, ups_volt);
+    _mav_put_uint16_t(buf, 6, adc_volt);
+    _mav_put_uint8_t(buf, 8, rtl_reason);
+    _mav_put_uint8_t(buf, 9, s_flag2);
+    _mav_put_uint8_t(buf, 10, s_flag3);
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VKFMU_STATUS_LEN);
 #else
     mavlink_vkfmu_status_t packet;
     packet.time_boot_ms = time_boot_ms;
+    packet.ups_volt = ups_volt;
+    packet.adc_volt = adc_volt;
     packet.rtl_reason = rtl_reason;
     packet.s_flag2 = s_flag2;
     packet.s_flag3 = s_flag3;
-    packet.s_flag4 = s_flag4;
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VKFMU_STATUS_LEN);
 #endif
@@ -183,7 +195,7 @@ static inline uint16_t mavlink_msg_vkfmu_status_pack_chan(uint8_t system_id, uin
  */
 static inline uint16_t mavlink_msg_vkfmu_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_vkfmu_status_t* vkfmu_status)
 {
-    return mavlink_msg_vkfmu_status_pack(system_id, component_id, msg, vkfmu_status->time_boot_ms, vkfmu_status->rtl_reason, vkfmu_status->s_flag2, vkfmu_status->s_flag3, vkfmu_status->s_flag4);
+    return mavlink_msg_vkfmu_status_pack(system_id, component_id, msg, vkfmu_status->time_boot_ms, vkfmu_status->rtl_reason, vkfmu_status->s_flag2, vkfmu_status->s_flag3, vkfmu_status->ups_volt, vkfmu_status->adc_volt);
 }
 
 /**
@@ -197,7 +209,7 @@ static inline uint16_t mavlink_msg_vkfmu_status_encode(uint8_t system_id, uint8_
  */
 static inline uint16_t mavlink_msg_vkfmu_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_vkfmu_status_t* vkfmu_status)
 {
-    return mavlink_msg_vkfmu_status_pack_chan(system_id, component_id, chan, msg, vkfmu_status->time_boot_ms, vkfmu_status->rtl_reason, vkfmu_status->s_flag2, vkfmu_status->s_flag3, vkfmu_status->s_flag4);
+    return mavlink_msg_vkfmu_status_pack_chan(system_id, component_id, chan, msg, vkfmu_status->time_boot_ms, vkfmu_status->rtl_reason, vkfmu_status->s_flag2, vkfmu_status->s_flag3, vkfmu_status->ups_volt, vkfmu_status->adc_volt);
 }
 
 /**
@@ -211,7 +223,7 @@ static inline uint16_t mavlink_msg_vkfmu_status_encode_chan(uint8_t system_id, u
  */
 static inline uint16_t mavlink_msg_vkfmu_status_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_vkfmu_status_t* vkfmu_status)
 {
-    return mavlink_msg_vkfmu_status_pack_status(system_id, component_id, _status, msg,  vkfmu_status->time_boot_ms, vkfmu_status->rtl_reason, vkfmu_status->s_flag2, vkfmu_status->s_flag3, vkfmu_status->s_flag4);
+    return mavlink_msg_vkfmu_status_pack_status(system_id, component_id, _status, msg,  vkfmu_status->time_boot_ms, vkfmu_status->rtl_reason, vkfmu_status->s_flag2, vkfmu_status->s_flag3, vkfmu_status->ups_volt, vkfmu_status->adc_volt);
 }
 
 /**
@@ -222,28 +234,31 @@ static inline uint16_t mavlink_msg_vkfmu_status_encode_status(uint8_t system_id,
  * @param rtl_reason  return to launch reason.
  * @param s_flag2  fmu sflag2
  * @param s_flag3  fmu sflag3
- * @param s_flag4  fmu sflag4
+ * @param ups_volt  ups voltage in 0.1V
+ * @param adc_volt  adc voltage in 0.1V
  */
 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
-static inline void mavlink_msg_vkfmu_status_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t rtl_reason, uint8_t s_flag2, uint8_t s_flag3, uint8_t s_flag4)
+static inline void mavlink_msg_vkfmu_status_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t rtl_reason, uint8_t s_flag2, uint8_t s_flag3, uint16_t ups_volt, uint16_t adc_volt)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_VKFMU_STATUS_LEN];
     _mav_put_uint32_t(buf, 0, time_boot_ms);
-    _mav_put_uint8_t(buf, 4, rtl_reason);
-    _mav_put_uint8_t(buf, 5, s_flag2);
-    _mav_put_uint8_t(buf, 6, s_flag3);
-    _mav_put_uint8_t(buf, 7, s_flag4);
+    _mav_put_uint16_t(buf, 4, ups_volt);
+    _mav_put_uint16_t(buf, 6, adc_volt);
+    _mav_put_uint8_t(buf, 8, rtl_reason);
+    _mav_put_uint8_t(buf, 9, s_flag2);
+    _mav_put_uint8_t(buf, 10, s_flag3);
 
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VKFMU_STATUS, buf, MAVLINK_MSG_ID_VKFMU_STATUS_MIN_LEN, MAVLINK_MSG_ID_VKFMU_STATUS_LEN, MAVLINK_MSG_ID_VKFMU_STATUS_CRC);
 #else
     mavlink_vkfmu_status_t packet;
     packet.time_boot_ms = time_boot_ms;
+    packet.ups_volt = ups_volt;
+    packet.adc_volt = adc_volt;
     packet.rtl_reason = rtl_reason;
     packet.s_flag2 = s_flag2;
     packet.s_flag3 = s_flag3;
-    packet.s_flag4 = s_flag4;
 
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VKFMU_STATUS, (const char *)&packet, MAVLINK_MSG_ID_VKFMU_STATUS_MIN_LEN, MAVLINK_MSG_ID_VKFMU_STATUS_LEN, MAVLINK_MSG_ID_VKFMU_STATUS_CRC);
 #endif
@@ -257,7 +272,7 @@ static inline void mavlink_msg_vkfmu_status_send(mavlink_channel_t chan, uint32_
 static inline void mavlink_msg_vkfmu_status_send_struct(mavlink_channel_t chan, const mavlink_vkfmu_status_t* vkfmu_status)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
-    mavlink_msg_vkfmu_status_send(chan, vkfmu_status->time_boot_ms, vkfmu_status->rtl_reason, vkfmu_status->s_flag2, vkfmu_status->s_flag3, vkfmu_status->s_flag4);
+    mavlink_msg_vkfmu_status_send(chan, vkfmu_status->time_boot_ms, vkfmu_status->rtl_reason, vkfmu_status->s_flag2, vkfmu_status->s_flag3, vkfmu_status->ups_volt, vkfmu_status->adc_volt);
 #else
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VKFMU_STATUS, (const char *)vkfmu_status, MAVLINK_MSG_ID_VKFMU_STATUS_MIN_LEN, MAVLINK_MSG_ID_VKFMU_STATUS_LEN, MAVLINK_MSG_ID_VKFMU_STATUS_CRC);
 #endif
@@ -271,24 +286,26 @@ static inline void mavlink_msg_vkfmu_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_vkfmu_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint32_t time_boot_ms, uint8_t rtl_reason, uint8_t s_flag2, uint8_t s_flag3, uint8_t s_flag4)
+static inline void mavlink_msg_vkfmu_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint32_t time_boot_ms, uint8_t rtl_reason, uint8_t s_flag2, uint8_t s_flag3, uint16_t ups_volt, uint16_t adc_volt)
 {
 #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(buf, 4, rtl_reason);
-    _mav_put_uint8_t(buf, 5, s_flag2);
-    _mav_put_uint8_t(buf, 6, s_flag3);
-    _mav_put_uint8_t(buf, 7, s_flag4);
+    _mav_put_uint16_t(buf, 4, ups_volt);
+    _mav_put_uint16_t(buf, 6, adc_volt);
+    _mav_put_uint8_t(buf, 8, rtl_reason);
+    _mav_put_uint8_t(buf, 9, s_flag2);
+    _mav_put_uint8_t(buf, 10, s_flag3);
 
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VKFMU_STATUS, buf, MAVLINK_MSG_ID_VKFMU_STATUS_MIN_LEN, MAVLINK_MSG_ID_VKFMU_STATUS_LEN, MAVLINK_MSG_ID_VKFMU_STATUS_CRC);
 #else
     mavlink_vkfmu_status_t *packet = (mavlink_vkfmu_status_t *)msgbuf;
     packet->time_boot_ms = time_boot_ms;
+    packet->ups_volt = ups_volt;
+    packet->adc_volt = adc_volt;
     packet->rtl_reason = rtl_reason;
     packet->s_flag2 = s_flag2;
     packet->s_flag3 = s_flag3;
-    packet->s_flag4 = s_flag4;
 
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VKFMU_STATUS, (const char *)packet, MAVLINK_MSG_ID_VKFMU_STATUS_MIN_LEN, MAVLINK_MSG_ID_VKFMU_STATUS_LEN, MAVLINK_MSG_ID_VKFMU_STATUS_CRC);
 #endif
@@ -317,7 +334,7 @@ static inline uint32_t mavlink_msg_vkfmu_status_get_time_boot_ms(const mavlink_m
  */
 static inline uint8_t mavlink_msg_vkfmu_status_get_rtl_reason(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint8_t(msg,  4);
+    return _MAV_RETURN_uint8_t(msg,  8);
 }
 
 /**
@@ -327,7 +344,7 @@ static inline uint8_t mavlink_msg_vkfmu_status_get_rtl_reason(const mavlink_mess
  */
 static inline uint8_t mavlink_msg_vkfmu_status_get_s_flag2(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint8_t(msg,  5);
+    return _MAV_RETURN_uint8_t(msg,  9);
 }
 
 /**
@@ -337,17 +354,27 @@ static inline uint8_t mavlink_msg_vkfmu_status_get_s_flag2(const mavlink_message
  */
 static inline uint8_t mavlink_msg_vkfmu_status_get_s_flag3(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint8_t(msg,  6);
+    return _MAV_RETURN_uint8_t(msg,  10);
 }
 
 /**
- * @brief Get field s_flag4 from vkfmu_status message
+ * @brief Get field ups_volt from vkfmu_status message
  *
- * @return  fmu sflag4
+ * @return  ups voltage in 0.1V
  */
-static inline uint8_t mavlink_msg_vkfmu_status_get_s_flag4(const mavlink_message_t* msg)
+static inline uint16_t mavlink_msg_vkfmu_status_get_ups_volt(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint8_t(msg,  7);
+    return _MAV_RETURN_uint16_t(msg,  4);
+}
+
+/**
+ * @brief Get field adc_volt from vkfmu_status message
+ *
+ * @return  adc voltage in 0.1V
+ */
+static inline uint16_t mavlink_msg_vkfmu_status_get_adc_volt(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint16_t(msg,  6);
 }
 
 /**
@@ -360,10 +387,11 @@ static inline void mavlink_msg_vkfmu_status_decode(const mavlink_message_t* msg,
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     vkfmu_status->time_boot_ms = mavlink_msg_vkfmu_status_get_time_boot_ms(msg);
+    vkfmu_status->ups_volt = mavlink_msg_vkfmu_status_get_ups_volt(msg);
+    vkfmu_status->adc_volt = mavlink_msg_vkfmu_status_get_adc_volt(msg);
     vkfmu_status->rtl_reason = mavlink_msg_vkfmu_status_get_rtl_reason(msg);
     vkfmu_status->s_flag2 = mavlink_msg_vkfmu_status_get_s_flag2(msg);
     vkfmu_status->s_flag3 = mavlink_msg_vkfmu_status_get_s_flag3(msg);
-    vkfmu_status->s_flag4 = mavlink_msg_vkfmu_status_get_s_flag4(msg);
 #else
         uint8_t len = msg->len < MAVLINK_MSG_ID_VKFMU_STATUS_LEN? msg->len : MAVLINK_MSG_ID_VKFMU_STATUS_LEN;
         memset(vkfmu_status, 0, MAVLINK_MSG_ID_VKFMU_STATUS_LEN);

+ 6 - 5
v2.0/VKFly/testsuite.h

@@ -113,15 +113,16 @@ static void mavlink_test_vkfmu_status(uint8_t system_id, uint8_t component_id, m
         uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
         uint16_t i;
     mavlink_vkfmu_status_t packet_in = {
-        963497464,17,84,151,218
+        963497464,17443,17547,29,96,163
     };
     mavlink_vkfmu_status_t packet1, packet2;
         memset(&packet1, 0, sizeof(packet1));
         packet1.time_boot_ms = packet_in.time_boot_ms;
+        packet1.ups_volt = packet_in.ups_volt;
+        packet1.adc_volt = packet_in.adc_volt;
         packet1.rtl_reason = packet_in.rtl_reason;
         packet1.s_flag2 = packet_in.s_flag2;
         packet1.s_flag3 = packet_in.s_flag3;
-        packet1.s_flag4 = packet_in.s_flag4;
         
         
 #ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
@@ -136,12 +137,12 @@ static void mavlink_test_vkfmu_status(uint8_t system_id, uint8_t component_id, m
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_vkfmu_status_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.rtl_reason , packet1.s_flag2 , packet1.s_flag3 , packet1.s_flag4 );
+    mavlink_msg_vkfmu_status_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.rtl_reason , packet1.s_flag2 , packet1.s_flag3 , packet1.ups_volt , packet1.adc_volt );
     mavlink_msg_vkfmu_status_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_vkfmu_status_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.rtl_reason , packet1.s_flag2 , packet1.s_flag3 , packet1.s_flag4 );
+    mavlink_msg_vkfmu_status_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.rtl_reason , packet1.s_flag2 , packet1.s_flag3 , packet1.ups_volt , packet1.adc_volt );
     mavlink_msg_vkfmu_status_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
@@ -154,7 +155,7 @@ static void mavlink_test_vkfmu_status(uint8_t system_id, uint8_t component_id, m
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
         
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_vkfmu_status_send(MAVLINK_COMM_1 , packet1.time_boot_ms , packet1.rtl_reason , packet1.s_flag2 , packet1.s_flag3 , packet1.s_flag4 );
+    mavlink_msg_vkfmu_status_send(MAVLINK_COMM_1 , packet1.time_boot_ms , packet1.rtl_reason , packet1.s_flag2 , packet1.s_flag3 , packet1.ups_volt , packet1.adc_volt );
     mavlink_msg_vkfmu_status_decode(last_msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 

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

@@ -7,7 +7,7 @@
 #ifndef MAVLINK_VERSION_H
 #define MAVLINK_VERSION_H
 
-#define MAVLINK_BUILD_DATE "Thu May 02 2024"
+#define MAVLINK_BUILD_DATE "Thu May 09 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 -7254152029833598995
+#define MAVLINK_COMMON_XML_HASH 1473955373237606900
 
 #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 -7254152029833598995
+#define MAVLINK_PRIMARY_XML_HASH 1473955373237606900
 
 #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 "Thu May 02 2024"
+#define MAVLINK_BUILD_DATE "Thu May 09 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 -8211725683581581752
+#define MAVLINK_PRIMARY_XML_HASH 3452106970252623375
 
 #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 -8211725683581581752
+#define MAVLINK_MINIMAL_XML_HASH 3452106970252623375
 
 #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 "Thu May 02 2024"
+#define MAVLINK_BUILD_DATE "Thu May 09 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 -7981410192942262563
+#define MAVLINK_PRIMARY_XML_HASH -4305367162763529627
 
 #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 -7981410192942262563
+#define MAVLINK_STANDARD_XML_HASH -4305367162763529627
 
 #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 "Thu May 02 2024"
+#define MAVLINK_BUILD_DATE "Thu May 09 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