Browse Source

增加部分反向机型定义, vkfmu_status 扩展抛投舵机状态

LiuYang 1 month ago
parent
commit
32b20254ae

+ 19 - 1
msg_definitions/VKFly.xml

@@ -19,6 +19,9 @@
       <entry value="43" name="VKFLY_AP_TYPE_X4R">
         <description>Quadrotor X4 reverse</description>
       </entry>
+      <entry value="44" name="VKFLY_AP_TYPE_I4R">
+        <description>Quadrotor I4 reverse</description>
+      </entry>
       <entry value="61" name="VKFLY_AP_TYPE_I6">
         <description>Hexarotor I6</description>
       </entry>
@@ -34,6 +37,12 @@
       <entry value="65" name="VKFLY_AP_TYPE_H6">
         <description>Hexarotor H6</description>
       </entry>
+      <entry value="66" name="VKFLY_AP_TYPE_I6R">
+        <description>Hexarotor I6 reverse</description>
+      </entry>
+      <entry value="67" name="VKFLY_AP_TYPE_X6R">
+        <description>Hexarotor X6 reverse</description>
+      </entry>
       <entry value="81" name="VKFLY_AP_TYPE_I8">
         <description>Octorotor I8</description>
       </entry>
@@ -52,6 +61,12 @@
       <entry value="86" name="VKFLY_AP_TYPE_4X8DR">
         <description>Four axis octorotor, all rotors are opposite of 4X8M.</description>
       </entry>
+      <entry value="87" name="VKFLY_AP_TYPE_I8R">
+        <description>Octorotor I8 reverse</description>
+      </entry>
+      <entry value="88" name="VKFLY_AP_TYPE_X8R">
+        <description>Octorotor X8 reverse</description>
+      </entry>
       <entry value="121" name="VKFLY_AP_TYPE_6I12">
         <description>Six axis twelve rotor, upper level I6, lower lever opposite with I6.</description>
       </entry>
@@ -899,6 +914,8 @@
       <field type="uint32_t" name="dist_to_tar" units="cm">distance to target position in cm</field>
       <field type="uint16_t" name="servo_state">bitmap for servo state</field>
       <field type="float" name="flight_dist" units="m">flight distance since this power up</field>
+      <extensions />
+      <field type="uint16_t" name="servo_state2">bitmap for servo state2</field>
     </message>
 
     <message id="53002" name="VK_ROI_TARGET">
@@ -1207,7 +1224,8 @@
       <field type="int32_t" name="ins_flag"></field>
       <field type="uint16_t" name="throttle" min="0" max="100" increment="1">throttle output.</field>
       <field type="uint8_t" name="flight_mode">flight mode.</field>
-      <field type="uint8_t" name="btake_status" min="0" max="1" increment="1">backup takeover status.</field>
+      <field type="uint8_t" name="btake_status" min="0" max="1" increment="1">backup takeover
+        status.</field>
     </message>
 
     <message id="53300" name="QINGXIE_BMS">

+ 5 - 0
readme.md

@@ -18,17 +18,22 @@ typedef enum VKFLY_AP_TYPE
     VKFLY_AP_TYPE_I4=41, /* I4 | */
     VKFLY_AP_TYPE_X4=42, /* X4 | */
     VKFLY_AP_TYPE_X4R=43, /* 反向X4 */
+    VKFLY_AP_TYPE_I4R=44, /* 反向I4 */
     VKFLY_AP_TYPE_I6=61, /* I6 | */
     VKFLY_AP_TYPE_X6=62, /* X6 | */
     VKFLY_AP_TYPE_YI6D=63, /* YI6D | */
     VKFLY_AP_TYPE_Y6D=64, /*  Y6D | */
     VKFLY_AP_TYPE_H6=65, /* H6 | */
+    VKFLY_AP_TYPE_I6R=66, /* 反向I6 */
+    VKFLY_AP_TYPE_X6R=67, /* 反向X6 */
     VKFLY_AP_TYPE_I8=81, /* I8 | */
     VKFLY_AP_TYPE_X8=82, /*  X8 | */
     VKFLY_AP_TYPE_4X8M=83, /* 4轴8桨 | */
     VKFLY_AP_TYPE_4X8D=84, /* 4轴8桨 */
     VKFLY_AP_TYPE_4X8MR=85, /* 4轴8桨  */
     VKFLY_AP_TYPE_4X8DR=86, /* 4轴8桨*/
+    VKFLY_AP_TYPE_I8R=87, /* 反向I8 */
+    VKFLY_AP_TYPE_X8R=88, /* 反向X8 */
     VKFLY_AP_TYPE_6I12=121, /* 6轴12桨, 十字布局 */
     VKFLY_AP_TYPE_6X12=122, /* 6轴12桨, X字布局 */
     VKFLY_AP_TYPE_6H12=123, /* 6轴12桨, H字布局 */

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 6608795056306455779
+#define MAVLINK_PRIMARY_XML_HASH 2270673811792067145
 
 #ifndef MAVLINK_STX
 #define MAVLINK_STX 253

+ 12 - 6
v2.0/VKFly/mavlink_msg_fmub_status.h

@@ -25,7 +25,8 @@ typedef struct __mavlink_fmub_status_t {
  int32_t ins_flag; /*<  */
  uint16_t throttle; /*<  throttle output.*/
  uint8_t flight_mode; /*<  flight mode.*/
- uint8_t btake_status; /*<  backup takeover status.*/
+ uint8_t btake_status; /*<  backup takeover
+        status.*/
 } mavlink_fmub_status_t;
 
 #define MAVLINK_MSG_ID_FMUB_STATUS_LEN 76
@@ -121,7 +122,8 @@ typedef struct __mavlink_fmub_status_t {
  * @param ins_flag  
  * @param throttle  throttle output.
  * @param flight_mode  flight mode.
- * @param btake_status  backup takeover status.
+ * @param btake_status  backup takeover
+        status.
  * @return length of the message in bytes (excluding serial stream start sign)
  */
 static inline uint16_t mavlink_msg_fmub_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
@@ -210,7 +212,8 @@ static inline uint16_t mavlink_msg_fmub_status_pack(uint8_t system_id, uint8_t c
  * @param ins_flag  
  * @param throttle  throttle output.
  * @param flight_mode  flight mode.
- * @param btake_status  backup takeover status.
+ * @param btake_status  backup takeover
+        status.
  * @return length of the message in bytes (excluding serial stream start sign)
  */
 static inline uint16_t mavlink_msg_fmub_status_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
@@ -302,7 +305,8 @@ static inline uint16_t mavlink_msg_fmub_status_pack_status(uint8_t system_id, ui
  * @param ins_flag  
  * @param throttle  throttle output.
  * @param flight_mode  flight mode.
- * @param btake_status  backup takeover status.
+ * @param btake_status  backup takeover
+        status.
  * @return length of the message in bytes (excluding serial stream start sign)
  */
 static inline uint16_t mavlink_msg_fmub_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
@@ -430,7 +434,8 @@ static inline uint16_t mavlink_msg_fmub_status_encode_status(uint8_t system_id,
  * @param ins_flag  
  * @param throttle  throttle output.
  * @param flight_mode  flight mode.
- * @param btake_status  backup takeover status.
+ * @param btake_status  backup takeover
+        status.
  */
 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
@@ -775,7 +780,8 @@ static inline uint8_t mavlink_msg_fmub_status_get_flight_mode(const mavlink_mess
 /**
  * @brief Get field btake_status from fmub_status message
  *
- * @return  backup takeover status.
+ * @return  backup takeover
+        status.
  */
 static inline uint8_t mavlink_msg_fmub_status_get_btake_status(const mavlink_message_t* msg)
 {

+ 43 - 15
v2.0/VKFly/mavlink_msg_vkfmu_status.h

@@ -3,7 +3,7 @@
 
 #define MAVLINK_MSG_ID_VKFMU_STATUS 53001
 
-
+MAVPACKED(
 typedef struct __mavlink_vkfmu_status_t {
  uint32_t time_boot_ms; /*< [ms] Timestamp in ms from system boot.*/
  uint32_t flight_time; /*< [s] flight time in seconds*/
@@ -15,11 +15,12 @@ typedef struct __mavlink_vkfmu_status_t {
  uint8_t rtl_reason; /*<  return to launch reason.*/
  uint8_t loiter_reason; /*<  Loiter reason */
  uint8_t s_flag3; /*<  fmu sflag3*/
-} mavlink_vkfmu_status_t;
+ uint16_t servo_state2; /*<  bitmap for servo state2*/
+}) mavlink_vkfmu_status_t;
 
-#define MAVLINK_MSG_ID_VKFMU_STATUS_LEN 25
+#define MAVLINK_MSG_ID_VKFMU_STATUS_LEN 27
 #define MAVLINK_MSG_ID_VKFMU_STATUS_MIN_LEN 25
-#define MAVLINK_MSG_ID_53001_LEN 25
+#define MAVLINK_MSG_ID_53001_LEN 27
 #define MAVLINK_MSG_ID_53001_MIN_LEN 25
 
 #define MAVLINK_MSG_ID_VKFMU_STATUS_CRC 136
@@ -31,7 +32,7 @@ typedef struct __mavlink_vkfmu_status_t {
 #define MAVLINK_MESSAGE_INFO_VKFMU_STATUS { \
     53001, \
     "VKFMU_STATUS", \
-    10, \
+    11, \
     {  { "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, 22, offsetof(mavlink_vkfmu_status_t, rtl_reason) }, \
          { "loiter_reason", NULL, MAVLINK_TYPE_UINT8_T, 0, 23, offsetof(mavlink_vkfmu_status_t, loiter_reason) }, \
@@ -42,12 +43,13 @@ typedef struct __mavlink_vkfmu_status_t {
          { "dist_to_tar", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_vkfmu_status_t, dist_to_tar) }, \
          { "servo_state", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_vkfmu_status_t, servo_state) }, \
          { "flight_dist", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_vkfmu_status_t, flight_dist) }, \
+         { "servo_state2", NULL, MAVLINK_TYPE_UINT16_T, 0, 25, offsetof(mavlink_vkfmu_status_t, servo_state2) }, \
          } \
 }
 #else
 #define MAVLINK_MESSAGE_INFO_VKFMU_STATUS { \
     "VKFMU_STATUS", \
-    10, \
+    11, \
     {  { "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, 22, offsetof(mavlink_vkfmu_status_t, rtl_reason) }, \
          { "loiter_reason", NULL, MAVLINK_TYPE_UINT8_T, 0, 23, offsetof(mavlink_vkfmu_status_t, loiter_reason) }, \
@@ -58,6 +60,7 @@ typedef struct __mavlink_vkfmu_status_t {
          { "dist_to_tar", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_vkfmu_status_t, dist_to_tar) }, \
          { "servo_state", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_vkfmu_status_t, servo_state) }, \
          { "flight_dist", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_vkfmu_status_t, flight_dist) }, \
+         { "servo_state2", NULL, MAVLINK_TYPE_UINT16_T, 0, 25, offsetof(mavlink_vkfmu_status_t, servo_state2) }, \
          } \
 }
 #endif
@@ -78,10 +81,11 @@ typedef struct __mavlink_vkfmu_status_t {
  * @param dist_to_tar [cm] distance to target position in cm
  * @param servo_state  bitmap for servo state
  * @param flight_dist [m] flight distance since this power up
+ * @param servo_state2  bitmap for servo state2
  * @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 loiter_reason, uint8_t s_flag3, uint16_t ups_volt, uint16_t adc_volt, uint32_t flight_time, uint32_t dist_to_tar, uint16_t servo_state, float flight_dist)
+                               uint32_t time_boot_ms, uint8_t rtl_reason, uint8_t loiter_reason, uint8_t s_flag3, uint16_t ups_volt, uint16_t adc_volt, uint32_t flight_time, uint32_t dist_to_tar, uint16_t servo_state, float flight_dist, uint16_t servo_state2)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_VKFMU_STATUS_LEN];
@@ -95,6 +99,7 @@ static inline uint16_t mavlink_msg_vkfmu_status_pack(uint8_t system_id, uint8_t
     _mav_put_uint8_t(buf, 22, rtl_reason);
     _mav_put_uint8_t(buf, 23, loiter_reason);
     _mav_put_uint8_t(buf, 24, s_flag3);
+    _mav_put_uint16_t(buf, 25, servo_state2);
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VKFMU_STATUS_LEN);
 #else
@@ -109,6 +114,7 @@ static inline uint16_t mavlink_msg_vkfmu_status_pack(uint8_t system_id, uint8_t
     packet.rtl_reason = rtl_reason;
     packet.loiter_reason = loiter_reason;
     packet.s_flag3 = s_flag3;
+    packet.servo_state2 = servo_state2;
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VKFMU_STATUS_LEN);
 #endif
@@ -134,10 +140,11 @@ static inline uint16_t mavlink_msg_vkfmu_status_pack(uint8_t system_id, uint8_t
  * @param dist_to_tar [cm] distance to target position in cm
  * @param servo_state  bitmap for servo state
  * @param flight_dist [m] flight distance since this power up
+ * @param servo_state2  bitmap for servo state2
  * @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 loiter_reason, uint8_t s_flag3, uint16_t ups_volt, uint16_t adc_volt, uint32_t flight_time, uint32_t dist_to_tar, uint16_t servo_state, float flight_dist)
+                               uint32_t time_boot_ms, uint8_t rtl_reason, uint8_t loiter_reason, uint8_t s_flag3, uint16_t ups_volt, uint16_t adc_volt, uint32_t flight_time, uint32_t dist_to_tar, uint16_t servo_state, float flight_dist, uint16_t servo_state2)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_VKFMU_STATUS_LEN];
@@ -151,6 +158,7 @@ static inline uint16_t mavlink_msg_vkfmu_status_pack_status(uint8_t system_id, u
     _mav_put_uint8_t(buf, 22, rtl_reason);
     _mav_put_uint8_t(buf, 23, loiter_reason);
     _mav_put_uint8_t(buf, 24, s_flag3);
+    _mav_put_uint16_t(buf, 25, servo_state2);
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VKFMU_STATUS_LEN);
 #else
@@ -165,6 +173,7 @@ static inline uint16_t mavlink_msg_vkfmu_status_pack_status(uint8_t system_id, u
     packet.rtl_reason = rtl_reason;
     packet.loiter_reason = loiter_reason;
     packet.s_flag3 = s_flag3;
+    packet.servo_state2 = servo_state2;
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VKFMU_STATUS_LEN);
 #endif
@@ -193,11 +202,12 @@ static inline uint16_t mavlink_msg_vkfmu_status_pack_status(uint8_t system_id, u
  * @param dist_to_tar [cm] distance to target position in cm
  * @param servo_state  bitmap for servo state
  * @param flight_dist [m] flight distance since this power up
+ * @param servo_state2  bitmap for servo state2
  * @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 loiter_reason,uint8_t s_flag3,uint16_t ups_volt,uint16_t adc_volt,uint32_t flight_time,uint32_t dist_to_tar,uint16_t servo_state,float flight_dist)
+                                   uint32_t time_boot_ms,uint8_t rtl_reason,uint8_t loiter_reason,uint8_t s_flag3,uint16_t ups_volt,uint16_t adc_volt,uint32_t flight_time,uint32_t dist_to_tar,uint16_t servo_state,float flight_dist,uint16_t servo_state2)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_VKFMU_STATUS_LEN];
@@ -211,6 +221,7 @@ static inline uint16_t mavlink_msg_vkfmu_status_pack_chan(uint8_t system_id, uin
     _mav_put_uint8_t(buf, 22, rtl_reason);
     _mav_put_uint8_t(buf, 23, loiter_reason);
     _mav_put_uint8_t(buf, 24, s_flag3);
+    _mav_put_uint16_t(buf, 25, servo_state2);
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VKFMU_STATUS_LEN);
 #else
@@ -225,6 +236,7 @@ static inline uint16_t mavlink_msg_vkfmu_status_pack_chan(uint8_t system_id, uin
     packet.rtl_reason = rtl_reason;
     packet.loiter_reason = loiter_reason;
     packet.s_flag3 = s_flag3;
+    packet.servo_state2 = servo_state2;
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VKFMU_STATUS_LEN);
 #endif
@@ -243,7 +255,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->loiter_reason, vkfmu_status->s_flag3, vkfmu_status->ups_volt, vkfmu_status->adc_volt, vkfmu_status->flight_time, vkfmu_status->dist_to_tar, vkfmu_status->servo_state, vkfmu_status->flight_dist);
+    return mavlink_msg_vkfmu_status_pack(system_id, component_id, msg, vkfmu_status->time_boot_ms, vkfmu_status->rtl_reason, vkfmu_status->loiter_reason, vkfmu_status->s_flag3, vkfmu_status->ups_volt, vkfmu_status->adc_volt, vkfmu_status->flight_time, vkfmu_status->dist_to_tar, vkfmu_status->servo_state, vkfmu_status->flight_dist, vkfmu_status->servo_state2);
 }
 
 /**
@@ -257,7 +269,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->loiter_reason, vkfmu_status->s_flag3, vkfmu_status->ups_volt, vkfmu_status->adc_volt, vkfmu_status->flight_time, vkfmu_status->dist_to_tar, vkfmu_status->servo_state, vkfmu_status->flight_dist);
+    return mavlink_msg_vkfmu_status_pack_chan(system_id, component_id, chan, msg, vkfmu_status->time_boot_ms, vkfmu_status->rtl_reason, vkfmu_status->loiter_reason, vkfmu_status->s_flag3, vkfmu_status->ups_volt, vkfmu_status->adc_volt, vkfmu_status->flight_time, vkfmu_status->dist_to_tar, vkfmu_status->servo_state, vkfmu_status->flight_dist, vkfmu_status->servo_state2);
 }
 
 /**
@@ -271,7 +283,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->loiter_reason, vkfmu_status->s_flag3, vkfmu_status->ups_volt, vkfmu_status->adc_volt, vkfmu_status->flight_time, vkfmu_status->dist_to_tar, vkfmu_status->servo_state, vkfmu_status->flight_dist);
+    return mavlink_msg_vkfmu_status_pack_status(system_id, component_id, _status, msg,  vkfmu_status->time_boot_ms, vkfmu_status->rtl_reason, vkfmu_status->loiter_reason, vkfmu_status->s_flag3, vkfmu_status->ups_volt, vkfmu_status->adc_volt, vkfmu_status->flight_time, vkfmu_status->dist_to_tar, vkfmu_status->servo_state, vkfmu_status->flight_dist, vkfmu_status->servo_state2);
 }
 
 /**
@@ -288,10 +300,11 @@ static inline uint16_t mavlink_msg_vkfmu_status_encode_status(uint8_t system_id,
  * @param dist_to_tar [cm] distance to target position in cm
  * @param servo_state  bitmap for servo state
  * @param flight_dist [m] flight distance since this power up
+ * @param servo_state2  bitmap for servo state2
  */
 #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 loiter_reason, uint8_t s_flag3, uint16_t ups_volt, uint16_t adc_volt, uint32_t flight_time, uint32_t dist_to_tar, uint16_t servo_state, float flight_dist)
+static inline void mavlink_msg_vkfmu_status_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t rtl_reason, uint8_t loiter_reason, uint8_t s_flag3, uint16_t ups_volt, uint16_t adc_volt, uint32_t flight_time, uint32_t dist_to_tar, uint16_t servo_state, float flight_dist, uint16_t servo_state2)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_VKFMU_STATUS_LEN];
@@ -305,6 +318,7 @@ static inline void mavlink_msg_vkfmu_status_send(mavlink_channel_t chan, uint32_
     _mav_put_uint8_t(buf, 22, rtl_reason);
     _mav_put_uint8_t(buf, 23, loiter_reason);
     _mav_put_uint8_t(buf, 24, s_flag3);
+    _mav_put_uint16_t(buf, 25, servo_state2);
 
     _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
@@ -319,6 +333,7 @@ static inline void mavlink_msg_vkfmu_status_send(mavlink_channel_t chan, uint32_
     packet.rtl_reason = rtl_reason;
     packet.loiter_reason = loiter_reason;
     packet.s_flag3 = s_flag3;
+    packet.servo_state2 = servo_state2;
 
     _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
@@ -332,7 +347,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->loiter_reason, vkfmu_status->s_flag3, vkfmu_status->ups_volt, vkfmu_status->adc_volt, vkfmu_status->flight_time, vkfmu_status->dist_to_tar, vkfmu_status->servo_state, vkfmu_status->flight_dist);
+    mavlink_msg_vkfmu_status_send(chan, vkfmu_status->time_boot_ms, vkfmu_status->rtl_reason, vkfmu_status->loiter_reason, vkfmu_status->s_flag3, vkfmu_status->ups_volt, vkfmu_status->adc_volt, vkfmu_status->flight_time, vkfmu_status->dist_to_tar, vkfmu_status->servo_state, vkfmu_status->flight_dist, vkfmu_status->servo_state2);
 #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
@@ -346,7 +361,7 @@ 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 loiter_reason, uint8_t s_flag3, uint16_t ups_volt, uint16_t adc_volt, uint32_t flight_time, uint32_t dist_to_tar, uint16_t servo_state, float flight_dist)
+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 loiter_reason, uint8_t s_flag3, uint16_t ups_volt, uint16_t adc_volt, uint32_t flight_time, uint32_t dist_to_tar, uint16_t servo_state, float flight_dist, uint16_t servo_state2)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char *buf = (char *)msgbuf;
@@ -360,6 +375,7 @@ static inline void mavlink_msg_vkfmu_status_send_buf(mavlink_message_t *msgbuf,
     _mav_put_uint8_t(buf, 22, rtl_reason);
     _mav_put_uint8_t(buf, 23, loiter_reason);
     _mav_put_uint8_t(buf, 24, s_flag3);
+    _mav_put_uint16_t(buf, 25, servo_state2);
 
     _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
@@ -374,6 +390,7 @@ static inline void mavlink_msg_vkfmu_status_send_buf(mavlink_message_t *msgbuf,
     packet->rtl_reason = rtl_reason;
     packet->loiter_reason = loiter_reason;
     packet->s_flag3 = s_flag3;
+    packet->servo_state2 = servo_state2;
 
     _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
@@ -485,6 +502,16 @@ static inline float mavlink_msg_vkfmu_status_get_flight_dist(const mavlink_messa
     return _MAV_RETURN_float(msg,  12);
 }
 
+/**
+ * @brief Get field servo_state2 from vkfmu_status message
+ *
+ * @return  bitmap for servo state2
+ */
+static inline uint16_t mavlink_msg_vkfmu_status_get_servo_state2(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint16_t(msg,  25);
+}
+
 /**
  * @brief Decode a vkfmu_status message into a struct
  *
@@ -504,6 +531,7 @@ static inline void mavlink_msg_vkfmu_status_decode(const mavlink_message_t* msg,
     vkfmu_status->rtl_reason = mavlink_msg_vkfmu_status_get_rtl_reason(msg);
     vkfmu_status->loiter_reason = mavlink_msg_vkfmu_status_get_loiter_reason(msg);
     vkfmu_status->s_flag3 = mavlink_msg_vkfmu_status_get_s_flag3(msg);
+    vkfmu_status->servo_state2 = mavlink_msg_vkfmu_status_get_servo_state2(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);

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

@@ -113,7 +113,7 @@ 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,963497672,963497880,101.0,18067,18171,18275,199,10,77
+        963497464,963497672,963497880,101.0,18067,18171,18275,199,10,77,18535
     };
     mavlink_vkfmu_status_t packet1, packet2;
         memset(&packet1, 0, sizeof(packet1));
@@ -127,6 +127,7 @@ static void mavlink_test_vkfmu_status(uint8_t system_id, uint8_t component_id, m
         packet1.rtl_reason = packet_in.rtl_reason;
         packet1.loiter_reason = packet_in.loiter_reason;
         packet1.s_flag3 = packet_in.s_flag3;
+        packet1.servo_state2 = packet_in.servo_state2;
         
         
 #ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
@@ -141,12 +142,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.loiter_reason , packet1.s_flag3 , packet1.ups_volt , packet1.adc_volt , packet1.flight_time , packet1.dist_to_tar , packet1.servo_state , packet1.flight_dist );
+    mavlink_msg_vkfmu_status_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.rtl_reason , packet1.loiter_reason , packet1.s_flag3 , packet1.ups_volt , packet1.adc_volt , packet1.flight_time , packet1.dist_to_tar , packet1.servo_state , packet1.flight_dist , packet1.servo_state2 );
     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.loiter_reason , packet1.s_flag3 , packet1.ups_volt , packet1.adc_volt , packet1.flight_time , packet1.dist_to_tar , packet1.servo_state , packet1.flight_dist );
+    mavlink_msg_vkfmu_status_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.rtl_reason , packet1.loiter_reason , packet1.s_flag3 , packet1.ups_volt , packet1.adc_volt , packet1.flight_time , packet1.dist_to_tar , packet1.servo_state , packet1.flight_dist , packet1.servo_state2 );
     mavlink_msg_vkfmu_status_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
@@ -159,7 +160,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.loiter_reason , packet1.s_flag3 , packet1.ups_volt , packet1.adc_volt , packet1.flight_time , packet1.dist_to_tar , packet1.servo_state , packet1.flight_dist );
+    mavlink_msg_vkfmu_status_send(MAVLINK_COMM_1 , packet1.time_boot_ms , packet1.rtl_reason , packet1.loiter_reason , packet1.s_flag3 , packet1.ups_volt , packet1.adc_volt , packet1.flight_time , packet1.dist_to_tar , packet1.servo_state , packet1.flight_dist , packet1.servo_state2 );
     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 "Mon Nov 03 2025"
+#define MAVLINK_BUILD_DATE "Wed Nov 12 2025"
 #define MAVLINK_WIRE_PROTOCOL_VERSION "2.0"
 #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255
  

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

@@ -10,7 +10,7 @@
     #error Wrong include order: MAVLINK_COMMON.H MUST NOT BE DIRECTLY USED. Include mavlink.h from the same directory instead or set ALL AND EVERY defines from MAVLINK.H manually accordingly, including the #define MAVLINK_H call.
 #endif
 
-#define MAVLINK_COMMON_XML_HASH 532765549818708498
+#define MAVLINK_COMMON_XML_HASH 7763006194309922345
 
 #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 532765549818708498
+#define MAVLINK_PRIMARY_XML_HASH 7763006194309922345
 
 #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 "Mon Nov 03 2025"
+#define MAVLINK_BUILD_DATE "Wed Nov 12 2025"
 #define MAVLINK_WIRE_PROTOCOL_VERSION "2.0"
 #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255
  

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

@@ -6,7 +6,7 @@
 #ifndef MAVLINK_H
 #define MAVLINK_H
 
-#define MAVLINK_PRIMARY_XML_HASH 5963857039924111572
+#define MAVLINK_PRIMARY_XML_HASH -5149160763940711746
 
 #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 5963857039924111572
+#define MAVLINK_MINIMAL_XML_HASH -5149160763940711746
 
 #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 "Mon Nov 03 2025"
+#define MAVLINK_BUILD_DATE "Wed Nov 12 2025"
 #define MAVLINK_WIRE_PROTOCOL_VERSION "2.0"
 #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 22
  

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

@@ -6,7 +6,7 @@
 #ifndef MAVLINK_H
 #define MAVLINK_H
 
-#define MAVLINK_PRIMARY_XML_HASH 7619114681092820353
+#define MAVLINK_PRIMARY_XML_HASH 3194772301987425103
 
 #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 7619114681092820353
+#define MAVLINK_STANDARD_XML_HASH 3194772301987425103
 
 #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 "Mon Nov 03 2025"
+#define MAVLINK_BUILD_DATE "Wed Nov 12 2025"
 #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