Explorar o código

抛投增加状态展示字段及相关状态清除指令

karo lee hai 1 mes
pai
achega
17d258cc4a

+ 13 - 0
msg_definitions/VKFly.xml

@@ -916,6 +916,17 @@
         <param index="7" label="Altitude" units="m"> </param>
       </entry>
 
+      <entry value="44073" name="VKFLY_CMD_CLEAR_SERVO_DISPALY" hasLocation="false"
+        isDestination="false">
+        <description>Vehicle act</description>
+        <param index="1" label="clear dispaly" minValue="0" maxValue="1">NAN means ignore. 1 means clear servo status dispaly</param>
+        <param index="2" label=""></param>
+        <param index="3" label=""></param>
+        <param index="4" label=""></param>
+        <param index="5" label=""></param>
+        <param index="6" label=""></param>
+        <param index="7" label=""></param>
+      </entry>
     </enum>
   </enums>
 
@@ -957,6 +968,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_display">bitmap for servo state display</field>
     </message>
 
     <message id="53002" name="VK_ROI_TARGET">

+ 7 - 2
readme.md

@@ -1752,6 +1752,9 @@ param2 = (float)(颜色 + (闪烁 << 4) +(电调编号<<8))
 
 ### 5.43 跟随飞行 MAV_CMD_DO_FOLLOW
 
+* param1
+0停止跟随, 1跟随吊舱目标
+
 ### 5.44 指点开伞指令 VKFLY_CMD_DO_REPOSITION_THAN_DO_PARACHUTE
 
 | 参数   | 说明                               |
@@ -1762,8 +1765,9 @@ param2 = (float)(颜色 + (闪烁 << 4) +(电调编号<<8))
 | y      | 经度                               |
 | z      | 高度                               |
 
-* param1
-0停止跟随, 1跟随吊舱目标
+### 5.45 清除抛投状态显示 VKFLY_CMD_CLEAR_SERVO_DISPALY
+* param1 
+1-重置全部抛投状态显示为关闭
 
 ## 6 飞控数据 LOG 读取
 
@@ -1919,6 +1923,7 @@ VKins 系统的状态数据自定义消息, 主要用于一些自定状态的传
 | dist_t_tar    | 目标距离, cm                                                          |
 | servo_state   | 舵机状态, 每位对应一个舵机, 1-开 0-关                                 |
 | flight_dist   | 飞行距离, m, 本次上电开始飞行的总距离                                 |
+| servo_display | 舵机状态展示, 每位对应一个舵机, 1-开 0-关,仅用作展示                    |
 
 ## 9 飞控参数说明
 

A diferenza do arquivo foi suprimida porque é demasiado grande
+ 1 - 1
v2.0/VKFly/VKFly.h


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

@@ -6,7 +6,7 @@
 #ifndef MAVLINK_H
 #define MAVLINK_H
 
-#define MAVLINK_PRIMARY_XML_HASH -1473904325831651581
+#define MAVLINK_PRIMARY_XML_HASH -992509777465783844
 
 #ifndef MAVLINK_STX
 #define MAVLINK_STX 253

+ 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_display; /*<  bitmap for servo state display*/
+}) 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_display", NULL, MAVLINK_TYPE_UINT16_T, 0, 25, offsetof(mavlink_vkfmu_status_t, servo_display) }, \
          } \
 }
 #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_display", NULL, MAVLINK_TYPE_UINT16_T, 0, 25, offsetof(mavlink_vkfmu_status_t, servo_display) }, \
          } \
 }
 #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_display  bitmap for servo state display
  * @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_display)
 {
 #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_display);
 
         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_display = servo_display;
 
         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_display  bitmap for servo state display
  * @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_display)
 {
 #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_display);
 
         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_display = servo_display;
 
         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_display  bitmap for servo state display
  * @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_display)
 {
 #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_display);
 
         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_display = servo_display;
 
         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_display);
 }
 
 /**
@@ -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_display);
 }
 
 /**
@@ -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_display);
 }
 
 /**
@@ -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_display  bitmap for servo state display
  */
 #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_display)
 {
 #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_display);
 
     _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_display = servo_display;
 
     _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_display);
 #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_display)
 {
 #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_display);
 
     _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_display = servo_display;
 
     _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_display from vkfmu_status message
+ *
+ * @return  bitmap for servo state display
+ */
+static inline uint16_t mavlink_msg_vkfmu_status_get_servo_display(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_display = mavlink_msg_vkfmu_status_get_servo_display(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_display = packet_in.servo_display;
         
         
 #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_display );
     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_display );
     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_display );
     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 Feb 02 2026"
+#define MAVLINK_BUILD_DATE "Thu Feb 26 2026"
 #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 -3706868761101684576
+#define MAVLINK_COMMON_XML_HASH -6447195062229904136
 
 #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 -3706868761101684576
+#define MAVLINK_PRIMARY_XML_HASH -6447195062229904136
 
 #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 Feb 02 2026"
+#define MAVLINK_BUILD_DATE "Thu Feb 26 2026"
 #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 -3071747296240045658
+#define MAVLINK_PRIMARY_XML_HASH 8869005500997421512
 
 #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 -3071747296240045658
+#define MAVLINK_MINIMAL_XML_HASH 8869005500997421512
 
 #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 Feb 02 2026"
+#define MAVLINK_BUILD_DATE "Thu Feb 26 2026"
 #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 8181879447612882476
+#define MAVLINK_PRIMARY_XML_HASH -7535397402208776511
 
 #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 8181879447612882476
+#define MAVLINK_STANDARD_XML_HASH -7535397402208776511
 
 #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 Feb 02 2026"
+#define MAVLINK_BUILD_DATE "Thu Feb 26 2026"
 #define MAVLINK_WIRE_PROTOCOL_VERSION "2.0"
 #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 22
  

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