Ver código fonte

增加返航愿意枚举类型定义

Liu Yang 1 ano atrás
pai
commit
f6420e2966

+ 44 - 1
msg_definitions/VKFly.xml

@@ -298,6 +298,49 @@
       </entry>
     </enum>
 
+    <enum name="VKFLY_RTL_REASON">
+      <description>Digicam auto take photo mode.</description>
+      <entry value="0" name="VKFLY_RTL_REASON_NONE">
+        <description>Rtl mode not triggered.</description>
+      </entry>
+      <entry value="1" name="VKFLY_RTL_REASON_GCSCMD">
+        <description>Trigger rtl mode by gcs command.</description>
+      </entry>
+      <entry value="2" name="VKFLY_RTL_REASON_RCCMD">
+        <description>Trigger rtl mode by remote controller command.</description>
+      </entry>
+      <entry value="3" name="VKFLY_RTL_REASON_GCSLOST">
+        <description>Trigger rtl mode by gcs link lost.</description>
+      </entry>
+      <entry value="4" name="VKFLY_RTL_REASON_RCFAIL">
+        <description>Trigger rtl mode by remote controller signal fail.</description>
+      </entry>
+      <entry value="5" name="VKFLY_RTL_REASON_RCLOST">
+        <description>Trigger rtl mode by remote controller signal lost.</description>
+      </entry>
+      <entry value="6" name="VKFLY_RTL_REASON_LOWVOLT">
+        <description>Trigger rtl mode by battery volt low.</description>
+      </entry>
+      <entry value="7" name="VKFLY_RTL_REASON_OFFBOARD">
+        <description>Trigger rtl mode by offboard command.</description>
+      </entry>
+      <entry value="8" name="VKFLY_RTL_REASON_ALTLIM">
+        <description>Trigger rtl mode by altitude limit.</description>
+      </entry>
+      <entry value="9" name="VKFLY_RTL_REASON_OUT_FENCE">
+        <description>Trigger rtl mode by out range of fence.</description>
+      </entry>
+      <entry value="10" name="VKFLY_RTL_REASON_BMS_LOWCAP">
+        <description>Trigger rtl mode by battery manager system low capacity.</description>
+      </entry>
+      <entry value="11" name="VKFLY_RTL_REASON_BMS_LINKLOST">
+        <description>Trigger rtl mode by battery manager link lost.</description>
+      </entry>
+      <entry value="12" name="VKFLY_RTL_REASON_SERVO_FAULT">
+        <description>Trigger rtl mode by servo fault.</description>
+      </entry>
+    </enum>
+
     <enum name="VKFLY_DIGICAM_WP_ACT">
       <description>Digicam action trigger on waypoint arrive.</description>
       <entry value="0" name="VKFLY_DIGICAM_WP_ACT_NONE">
@@ -462,7 +505,7 @@
     <message id="53001" name="VKFMU_STATUS">
       <description> </description>
       <field type="uint32_t" name="time_boot_ms" units="ms">Timestamp in ms from system boot.</field>
-      <field type="uint8_t" name="s_flag1">fmu sflag1</field>
+      <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>

+ 28 - 1
readme.md

@@ -645,6 +645,27 @@ Q: 用 mavlink FTP 还是用 LOG 系列. FTP 功能更强但实现难度更大.
     VKFLY_CUSTOM_MODE_ENUM_END=28, /*  | */
   } VKFLY_CUSTOM_MODE;
   ```
+- VKFLY_RTL_REASON
+  返航原因
+  ```c
+  typedef enum VKFLY_RTL_REASON
+  {
+    VKFLY_RTL_REASON_NONE=0, /* 未触发返航给 | */
+    VKFLY_RTL_REASON_GCSCMD=1, /* 地面站指令返航 | */
+    VKFLY_RTL_REASON_RCCMD=2, /* 遥控器指令返航 | */
+    VKFLY_RTL_REASON_GCSLOST=3, /* 地面站失联返航 | */
+    VKFLY_RTL_REASON_RCFAIL=4, /* 遥控器信号FS返航 | */
+    VKFLY_RTL_REASON_RCLOST=5, /* 遥控器信号失联返航 | */
+    VKFLY_RTL_REASON_LOWVOLT=6, /* 电压低保护返航 | */
+    VKFLY_RTL_REASON_OFFBOARD=7, /* OFFBORAD控制指令返航 | */
+    VKFLY_RTL_REASON_ALTLIM=8, /* 超出高度限制保护返航 | */
+    VKFLY_RTL_REASON_OUT_FENCE=9, /* 超出电子围栏范围保护返航 | */
+    VKFLY_RTL_REASON_BMS_LOWCAP=10, /* 电池BMS电量低保护返航 | */
+    VKFLY_RTL_REASON_BMS_LINKLOST=11, /* 电池BMS通信失联保护返航 | */
+    VKFLY_RTL_REASON_SERVO_FAULT=12, /* 伺服动力故障保护返航 | */
+    VKFLY_RTL_REASON_ENUM_END=13, /*  | */
+  } VKFLY_RTL_REASON;
+```
 
 - VKFLY_VKINS_NAV_STATUS
 
@@ -823,7 +844,13 @@ Q: 用 mavlink FTP 还是用 LOG 系列. FTP 功能更强但实现难度更大.
   | raw_gps_alt     | vkins解算使用的原始海拔高度m                                                              |
 
 - MAVLINK_VKFMU_STATUS
-  待定中
+  | 字段         | 说明                            |
+  | ------------ | ------------------------------- |
+  | time_boot_ms | 系统本地时间戳ms                |
+  | rtl_reasong  | 返航原因, 参考 VKFLY_RTL_REASON |
+  | s_flag2      | 预留                            |
+  | s_flag3      | 预留                            |
+  | s_flag4      | 预留                            |
 
 ## 飞控参数说明
 

Diferenças do arquivo suprimidas por serem muito extensas
+ 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 5066305815834855140
+#define MAVLINK_PRIMARY_XML_HASH -3798323614798322597
 
 #ifndef MAVLINK_STX
 #define MAVLINK_STX 253

+ 32 - 32
v2.0/VKFly/mavlink_msg_vkfmu_status.h

@@ -6,7 +6,7 @@
 
 typedef struct __mavlink_vkfmu_status_t {
  uint32_t time_boot_ms; /*< [ms] Timestamp in ms from system boot.*/
- uint8_t s_flag1; /*<  fmu sflag1*/
+ 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*/
@@ -17,8 +17,8 @@ typedef struct __mavlink_vkfmu_status_t {
 #define MAVLINK_MSG_ID_53001_LEN 8
 #define MAVLINK_MSG_ID_53001_MIN_LEN 8
 
-#define MAVLINK_MSG_ID_VKFMU_STATUS_CRC 5
-#define MAVLINK_MSG_ID_53001_CRC 5
+#define MAVLINK_MSG_ID_VKFMU_STATUS_CRC 81
+#define MAVLINK_MSG_ID_53001_CRC 81
 
 
 
@@ -28,7 +28,7 @@ typedef struct __mavlink_vkfmu_status_t {
     "VKFMU_STATUS", \
     5, \
     {  { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_vkfmu_status_t, time_boot_ms) }, \
-         { "s_flag1", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_vkfmu_status_t, s_flag1) }, \
+         { "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) }, \
@@ -39,7 +39,7 @@ typedef struct __mavlink_vkfmu_status_t {
     "VKFMU_STATUS", \
     5, \
     {  { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_vkfmu_status_t, time_boot_ms) }, \
-         { "s_flag1", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_vkfmu_status_t, s_flag1) }, \
+         { "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) }, \
@@ -54,19 +54,19 @@ typedef struct __mavlink_vkfmu_status_t {
  * @param msg The MAVLink message to compress the data into
  *
  * @param time_boot_ms [ms] Timestamp in ms from system boot.
- * @param s_flag1  fmu sflag1
+ * @param rtl_reason  return to launch reason.
  * @param s_flag2  fmu sflag2
  * @param s_flag3  fmu sflag3
  * @param s_flag4  fmu sflag4
  * @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 s_flag1, 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, uint8_t s_flag4)
 {
 #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, s_flag1);
+    _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);
@@ -75,7 +75,7 @@ static inline uint16_t mavlink_msg_vkfmu_status_pack(uint8_t system_id, uint8_t
 #else
     mavlink_vkfmu_status_t packet;
     packet.time_boot_ms = time_boot_ms;
-    packet.s_flag1 = s_flag1;
+    packet.rtl_reason = rtl_reason;
     packet.s_flag2 = s_flag2;
     packet.s_flag3 = s_flag3;
     packet.s_flag4 = s_flag4;
@@ -95,19 +95,19 @@ static inline uint16_t mavlink_msg_vkfmu_status_pack(uint8_t system_id, uint8_t
  * @param msg The MAVLink message to compress the data into
  *
  * @param time_boot_ms [ms] Timestamp in ms from system boot.
- * @param s_flag1  fmu sflag1
+ * @param rtl_reason  return to launch reason.
  * @param s_flag2  fmu sflag2
  * @param s_flag3  fmu sflag3
  * @param s_flag4  fmu sflag4
  * @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 s_flag1, 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, uint8_t s_flag4)
 {
 #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, s_flag1);
+    _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);
@@ -116,7 +116,7 @@ static inline uint16_t mavlink_msg_vkfmu_status_pack_status(uint8_t system_id, u
 #else
     mavlink_vkfmu_status_t packet;
     packet.time_boot_ms = time_boot_ms;
-    packet.s_flag1 = s_flag1;
+    packet.rtl_reason = rtl_reason;
     packet.s_flag2 = s_flag2;
     packet.s_flag3 = s_flag3;
     packet.s_flag4 = s_flag4;
@@ -139,7 +139,7 @@ static inline uint16_t mavlink_msg_vkfmu_status_pack_status(uint8_t system_id, u
  * @param chan The MAVLink channel this message will be sent over
  * @param msg The MAVLink message to compress the data into
  * @param time_boot_ms [ms] Timestamp in ms from system boot.
- * @param s_flag1  fmu sflag1
+ * @param rtl_reason  return to launch reason.
  * @param s_flag2  fmu sflag2
  * @param s_flag3  fmu sflag3
  * @param s_flag4  fmu sflag4
@@ -147,12 +147,12 @@ static inline uint16_t mavlink_msg_vkfmu_status_pack_status(uint8_t system_id, u
  */
 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 s_flag1,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,uint8_t s_flag4)
 {
 #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, s_flag1);
+    _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);
@@ -161,7 +161,7 @@ static inline uint16_t mavlink_msg_vkfmu_status_pack_chan(uint8_t system_id, uin
 #else
     mavlink_vkfmu_status_t packet;
     packet.time_boot_ms = time_boot_ms;
-    packet.s_flag1 = s_flag1;
+    packet.rtl_reason = rtl_reason;
     packet.s_flag2 = s_flag2;
     packet.s_flag3 = s_flag3;
     packet.s_flag4 = s_flag4;
@@ -183,7 +183,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->s_flag1, 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->s_flag4);
 }
 
 /**
@@ -197,7 +197,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->s_flag1, 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->s_flag4);
 }
 
 /**
@@ -211,7 +211,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->s_flag1, 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->s_flag4);
 }
 
 /**
@@ -219,19 +219,19 @@ static inline uint16_t mavlink_msg_vkfmu_status_encode_status(uint8_t system_id,
  * @param chan MAVLink channel to send the message
  *
  * @param time_boot_ms [ms] Timestamp in ms from system boot.
- * @param s_flag1  fmu sflag1
+ * @param rtl_reason  return to launch reason.
  * @param s_flag2  fmu sflag2
  * @param s_flag3  fmu sflag3
  * @param s_flag4  fmu sflag4
  */
 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
-static inline void mavlink_msg_vkfmu_status_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t s_flag1, 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, uint8_t s_flag4)
 {
 #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, s_flag1);
+    _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);
@@ -240,7 +240,7 @@ static inline void mavlink_msg_vkfmu_status_send(mavlink_channel_t chan, uint32_
 #else
     mavlink_vkfmu_status_t packet;
     packet.time_boot_ms = time_boot_ms;
-    packet.s_flag1 = s_flag1;
+    packet.rtl_reason = rtl_reason;
     packet.s_flag2 = s_flag2;
     packet.s_flag3 = s_flag3;
     packet.s_flag4 = s_flag4;
@@ -257,7 +257,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->s_flag1, 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->s_flag4);
 #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,12 +271,12 @@ 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 s_flag1, 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, uint8_t s_flag4)
 {
 #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, s_flag1);
+    _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);
@@ -285,7 +285,7 @@ static inline void mavlink_msg_vkfmu_status_send_buf(mavlink_message_t *msgbuf,
 #else
     mavlink_vkfmu_status_t *packet = (mavlink_vkfmu_status_t *)msgbuf;
     packet->time_boot_ms = time_boot_ms;
-    packet->s_flag1 = s_flag1;
+    packet->rtl_reason = rtl_reason;
     packet->s_flag2 = s_flag2;
     packet->s_flag3 = s_flag3;
     packet->s_flag4 = s_flag4;
@@ -311,11 +311,11 @@ static inline uint32_t mavlink_msg_vkfmu_status_get_time_boot_ms(const mavlink_m
 }
 
 /**
- * @brief Get field s_flag1 from vkfmu_status message
+ * @brief Get field rtl_reason from vkfmu_status message
  *
- * @return  fmu sflag1
+ * @return  return to launch reason.
  */
-static inline uint8_t mavlink_msg_vkfmu_status_get_s_flag1(const mavlink_message_t* msg)
+static inline uint8_t mavlink_msg_vkfmu_status_get_rtl_reason(const mavlink_message_t* msg)
 {
     return _MAV_RETURN_uint8_t(msg,  4);
 }
@@ -360,7 +360,7 @@ 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->s_flag1 = mavlink_msg_vkfmu_status_get_s_flag1(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);

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

@@ -118,7 +118,7 @@ static void mavlink_test_vkfmu_status(uint8_t system_id, uint8_t component_id, m
     mavlink_vkfmu_status_t packet1, packet2;
         memset(&packet1, 0, sizeof(packet1));
         packet1.time_boot_ms = packet_in.time_boot_ms;
-        packet1.s_flag1 = packet_in.s_flag1;
+        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;
@@ -136,12 +136,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.s_flag1 , 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.s_flag4 );
     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.s_flag1 , 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.s_flag4 );
     mavlink_msg_vkfmu_status_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
@@ -154,7 +154,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.s_flag1 , 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.s_flag4 );
     mavlink_msg_vkfmu_status_decode(last_msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 

+ 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 -1596072890383032290
+#define MAVLINK_COMMON_XML_HASH -4719018905846176978
 
 #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 -1596072890383032290
+#define MAVLINK_PRIMARY_XML_HASH -4719018905846176978
 
 #ifndef MAVLINK_STX
 #define MAVLINK_STX 253

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

@@ -6,7 +6,7 @@
 #ifndef MAVLINK_H
 #define MAVLINK_H
 
-#define MAVLINK_PRIMARY_XML_HASH 1170064198007829009
+#define MAVLINK_PRIMARY_XML_HASH -936987533560736823
 
 #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 1170064198007829009
+#define MAVLINK_MINIMAL_XML_HASH -936987533560736823
 
 #ifdef __cplusplus
 extern "C" {

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

@@ -6,7 +6,7 @@
 #ifndef MAVLINK_H
 #define MAVLINK_H
 
-#define MAVLINK_PRIMARY_XML_HASH -5505972709393286088
+#define MAVLINK_PRIMARY_XML_HASH 1241976508257245799
 
 #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 -5505972709393286088
+#define MAVLINK_STANDARD_XML_HASH 1241976508257245799
 
 #ifdef __cplusplus
 extern "C" {

Alguns arquivos não foram mostrados porque muitos arquivos mudaram nesse diff