Răsfoiți Sursa

MAVLINK_VKFMU_STATUS 增加舵机开关状态

Liu Yang 10 luni în urmă
părinte
comite
931e2be848
5 a modificat fișierele cu 86 adăugiri și 55 ștergeri
  1. 1 0
      msg_definitions/VKFly.xml
  2. 11 10
      readme.md
  3. 0 0
      v2.0/VKFly/VKFly.h
  4. 69 41
      v2.0/VKFly/mavlink_msg_vkfmu_status.h
  5. 5 4
      v2.0/VKFly/testsuite.h

+ 1 - 0
msg_definitions/VKFly.xml

@@ -649,6 +649,7 @@
       <field type="uint16_t" name="adc_volt">adc voltage in 0.1V</field>
       <field type="uint32_t" name="flight_time" units="s">flight time in seconds</field>
       <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>
     </message>
 
     <message id="53002" name="VK_ROI_TARGET">

+ 11 - 10
readme.md

@@ -1148,16 +1148,17 @@ mavlink common 标准消息集中主要由 MAVLINK_MSG_ID_COMMAND_INT 和 MAVLIN
 
 - **MAVLINK_VKFMU_STATUS**
 
-  | 字段          | 说明                               |
-  | ------------- | ---------------------------------- |
-  | time_boot_ms  | 系统本地时间戳ms                   |
-  | rtl_reason    | 返航原因, 参考 VKFLY_RTL_REASON    |
-  | loiter_reason | 悬停原因, 参考 VKFLY_LOITER_REASON |
-  | s_flag3       | 预留                               |
-  | ups_volt      | ups电压, 0.1V                      |
-  | adc_volt      | adc电压, 0.1V                      |
-  | flight_time   | 飞行时间,s                         |
-  | dist_t_tar    | 目标距离, cm                       |
+  | 字段          | 说明                                  |
+  | ------------- | ------------------------------------- |
+  | time_boot_ms  | 系统本地时间戳ms                      |
+  | rtl_reason    | 返航原因, 参考 VKFLY_RTL_REASON       |
+  | loiter_reason | 悬停原因, 参考 VKFLY_LOITER_REASON    |
+  | s_flag3       | 预留                                  |
+  | ups_volt      | ups电压, 0.1V                         |
+  | adc_volt      | adc电压, 0.1V                         |
+  | flight_time   | 飞行时间,s                            |
+  | dist_t_tar    | 目标距离, cm                          |
+  | servo_state   | 舵机状态, 每位对应一个舵机, 1-开 0-关 |
 
 - **MAVLINK_VK_BMS_STATUS**
   智能电池状态数据

Fișier diff suprimat deoarece este prea mare
+ 0 - 0
v2.0/VKFly/VKFly.h


+ 69 - 41
v2.0/VKFly/mavlink_msg_vkfmu_status.h

@@ -10,18 +10,19 @@ typedef struct __mavlink_vkfmu_status_t {
  uint32_t dist_to_tar; /*< [cm] distance to target position in cm*/
  uint16_t ups_volt; /*<  ups voltage in 0.1V*/
  uint16_t adc_volt; /*<  adc voltage in 0.1V*/
+ uint16_t servo_state; /*<  bitmap for servo state*/
  uint8_t rtl_reason; /*<  return to launch reason.*/
  uint8_t loiter_reason; /*<  Loiter reason */
  uint8_t s_flag3; /*<  fmu sflag3*/
 } mavlink_vkfmu_status_t;
 
-#define MAVLINK_MSG_ID_VKFMU_STATUS_LEN 19
-#define MAVLINK_MSG_ID_VKFMU_STATUS_MIN_LEN 19
-#define MAVLINK_MSG_ID_53001_LEN 19
-#define MAVLINK_MSG_ID_53001_MIN_LEN 19
+#define MAVLINK_MSG_ID_VKFMU_STATUS_LEN 21
+#define MAVLINK_MSG_ID_VKFMU_STATUS_MIN_LEN 21
+#define MAVLINK_MSG_ID_53001_LEN 21
+#define MAVLINK_MSG_ID_53001_MIN_LEN 21
 
-#define MAVLINK_MSG_ID_VKFMU_STATUS_CRC 149
-#define MAVLINK_MSG_ID_53001_CRC 149
+#define MAVLINK_MSG_ID_VKFMU_STATUS_CRC 251
+#define MAVLINK_MSG_ID_53001_CRC 251
 
 
 
@@ -29,29 +30,31 @@ typedef struct __mavlink_vkfmu_status_t {
 #define MAVLINK_MESSAGE_INFO_VKFMU_STATUS { \
     53001, \
     "VKFMU_STATUS", \
-    8, \
+    9, \
     {  { "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, 16, offsetof(mavlink_vkfmu_status_t, rtl_reason) }, \
-         { "loiter_reason", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_vkfmu_status_t, loiter_reason) }, \
-         { "s_flag3", NULL, MAVLINK_TYPE_UINT8_T, 0, 18, offsetof(mavlink_vkfmu_status_t, s_flag3) }, \
+         { "rtl_reason", NULL, MAVLINK_TYPE_UINT8_T, 0, 18, offsetof(mavlink_vkfmu_status_t, rtl_reason) }, \
+         { "loiter_reason", NULL, MAVLINK_TYPE_UINT8_T, 0, 19, offsetof(mavlink_vkfmu_status_t, loiter_reason) }, \
+         { "s_flag3", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_vkfmu_status_t, s_flag3) }, \
          { "ups_volt", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_vkfmu_status_t, ups_volt) }, \
          { "adc_volt", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_vkfmu_status_t, adc_volt) }, \
          { "flight_time", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_vkfmu_status_t, flight_time) }, \
          { "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, 16, offsetof(mavlink_vkfmu_status_t, servo_state) }, \
          } \
 }
 #else
 #define MAVLINK_MESSAGE_INFO_VKFMU_STATUS { \
     "VKFMU_STATUS", \
-    8, \
+    9, \
     {  { "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, 16, offsetof(mavlink_vkfmu_status_t, rtl_reason) }, \
-         { "loiter_reason", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_vkfmu_status_t, loiter_reason) }, \
-         { "s_flag3", NULL, MAVLINK_TYPE_UINT8_T, 0, 18, offsetof(mavlink_vkfmu_status_t, s_flag3) }, \
+         { "rtl_reason", NULL, MAVLINK_TYPE_UINT8_T, 0, 18, offsetof(mavlink_vkfmu_status_t, rtl_reason) }, \
+         { "loiter_reason", NULL, MAVLINK_TYPE_UINT8_T, 0, 19, offsetof(mavlink_vkfmu_status_t, loiter_reason) }, \
+         { "s_flag3", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_vkfmu_status_t, s_flag3) }, \
          { "ups_volt", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_vkfmu_status_t, ups_volt) }, \
          { "adc_volt", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_vkfmu_status_t, adc_volt) }, \
          { "flight_time", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_vkfmu_status_t, flight_time) }, \
          { "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, 16, offsetof(mavlink_vkfmu_status_t, servo_state) }, \
          } \
 }
 #endif
@@ -70,10 +73,11 @@ typedef struct __mavlink_vkfmu_status_t {
  * @param adc_volt  adc voltage in 0.1V
  * @param flight_time [s] flight time in seconds
  * @param dist_to_tar [cm] distance to target position in cm
+ * @param servo_state  bitmap for servo state
  * @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)
+                               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)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_VKFMU_STATUS_LEN];
@@ -82,9 +86,10 @@ static inline uint16_t mavlink_msg_vkfmu_status_pack(uint8_t system_id, uint8_t
     _mav_put_uint32_t(buf, 8, dist_to_tar);
     _mav_put_uint16_t(buf, 12, ups_volt);
     _mav_put_uint16_t(buf, 14, adc_volt);
-    _mav_put_uint8_t(buf, 16, rtl_reason);
-    _mav_put_uint8_t(buf, 17, loiter_reason);
-    _mav_put_uint8_t(buf, 18, s_flag3);
+    _mav_put_uint16_t(buf, 16, servo_state);
+    _mav_put_uint8_t(buf, 18, rtl_reason);
+    _mav_put_uint8_t(buf, 19, loiter_reason);
+    _mav_put_uint8_t(buf, 20, s_flag3);
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VKFMU_STATUS_LEN);
 #else
@@ -94,6 +99,7 @@ static inline uint16_t mavlink_msg_vkfmu_status_pack(uint8_t system_id, uint8_t
     packet.dist_to_tar = dist_to_tar;
     packet.ups_volt = ups_volt;
     packet.adc_volt = adc_volt;
+    packet.servo_state = servo_state;
     packet.rtl_reason = rtl_reason;
     packet.loiter_reason = loiter_reason;
     packet.s_flag3 = s_flag3;
@@ -120,10 +126,11 @@ static inline uint16_t mavlink_msg_vkfmu_status_pack(uint8_t system_id, uint8_t
  * @param adc_volt  adc voltage in 0.1V
  * @param flight_time [s] flight time in seconds
  * @param dist_to_tar [cm] distance to target position in cm
+ * @param servo_state  bitmap for servo state
  * @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)
+                               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)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_VKFMU_STATUS_LEN];
@@ -132,9 +139,10 @@ static inline uint16_t mavlink_msg_vkfmu_status_pack_status(uint8_t system_id, u
     _mav_put_uint32_t(buf, 8, dist_to_tar);
     _mav_put_uint16_t(buf, 12, ups_volt);
     _mav_put_uint16_t(buf, 14, adc_volt);
-    _mav_put_uint8_t(buf, 16, rtl_reason);
-    _mav_put_uint8_t(buf, 17, loiter_reason);
-    _mav_put_uint8_t(buf, 18, s_flag3);
+    _mav_put_uint16_t(buf, 16, servo_state);
+    _mav_put_uint8_t(buf, 18, rtl_reason);
+    _mav_put_uint8_t(buf, 19, loiter_reason);
+    _mav_put_uint8_t(buf, 20, s_flag3);
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VKFMU_STATUS_LEN);
 #else
@@ -144,6 +152,7 @@ static inline uint16_t mavlink_msg_vkfmu_status_pack_status(uint8_t system_id, u
     packet.dist_to_tar = dist_to_tar;
     packet.ups_volt = ups_volt;
     packet.adc_volt = adc_volt;
+    packet.servo_state = servo_state;
     packet.rtl_reason = rtl_reason;
     packet.loiter_reason = loiter_reason;
     packet.s_flag3 = s_flag3;
@@ -173,11 +182,12 @@ static inline uint16_t mavlink_msg_vkfmu_status_pack_status(uint8_t system_id, u
  * @param adc_volt  adc voltage in 0.1V
  * @param flight_time [s] flight time in seconds
  * @param dist_to_tar [cm] distance to target position in cm
+ * @param servo_state  bitmap for servo state
  * @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)
+                                   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)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_VKFMU_STATUS_LEN];
@@ -186,9 +196,10 @@ static inline uint16_t mavlink_msg_vkfmu_status_pack_chan(uint8_t system_id, uin
     _mav_put_uint32_t(buf, 8, dist_to_tar);
     _mav_put_uint16_t(buf, 12, ups_volt);
     _mav_put_uint16_t(buf, 14, adc_volt);
-    _mav_put_uint8_t(buf, 16, rtl_reason);
-    _mav_put_uint8_t(buf, 17, loiter_reason);
-    _mav_put_uint8_t(buf, 18, s_flag3);
+    _mav_put_uint16_t(buf, 16, servo_state);
+    _mav_put_uint8_t(buf, 18, rtl_reason);
+    _mav_put_uint8_t(buf, 19, loiter_reason);
+    _mav_put_uint8_t(buf, 20, s_flag3);
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VKFMU_STATUS_LEN);
 #else
@@ -198,6 +209,7 @@ static inline uint16_t mavlink_msg_vkfmu_status_pack_chan(uint8_t system_id, uin
     packet.dist_to_tar = dist_to_tar;
     packet.ups_volt = ups_volt;
     packet.adc_volt = adc_volt;
+    packet.servo_state = servo_state;
     packet.rtl_reason = rtl_reason;
     packet.loiter_reason = loiter_reason;
     packet.s_flag3 = s_flag3;
@@ -219,7 +231,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);
+    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);
 }
 
 /**
@@ -233,7 +245,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);
+    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);
 }
 
 /**
@@ -247,7 +259,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);
+    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);
 }
 
 /**
@@ -262,10 +274,11 @@ static inline uint16_t mavlink_msg_vkfmu_status_encode_status(uint8_t system_id,
  * @param adc_volt  adc voltage in 0.1V
  * @param flight_time [s] flight time in seconds
  * @param dist_to_tar [cm] distance to target position in cm
+ * @param servo_state  bitmap for servo state
  */
 #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)
+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)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char buf[MAVLINK_MSG_ID_VKFMU_STATUS_LEN];
@@ -274,9 +287,10 @@ static inline void mavlink_msg_vkfmu_status_send(mavlink_channel_t chan, uint32_
     _mav_put_uint32_t(buf, 8, dist_to_tar);
     _mav_put_uint16_t(buf, 12, ups_volt);
     _mav_put_uint16_t(buf, 14, adc_volt);
-    _mav_put_uint8_t(buf, 16, rtl_reason);
-    _mav_put_uint8_t(buf, 17, loiter_reason);
-    _mav_put_uint8_t(buf, 18, s_flag3);
+    _mav_put_uint16_t(buf, 16, servo_state);
+    _mav_put_uint8_t(buf, 18, rtl_reason);
+    _mav_put_uint8_t(buf, 19, loiter_reason);
+    _mav_put_uint8_t(buf, 20, 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
@@ -286,6 +300,7 @@ static inline void mavlink_msg_vkfmu_status_send(mavlink_channel_t chan, uint32_
     packet.dist_to_tar = dist_to_tar;
     packet.ups_volt = ups_volt;
     packet.adc_volt = adc_volt;
+    packet.servo_state = servo_state;
     packet.rtl_reason = rtl_reason;
     packet.loiter_reason = loiter_reason;
     packet.s_flag3 = s_flag3;
@@ -302,7 +317,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);
+    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);
 #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
@@ -316,7 +331,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)
+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)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char *buf = (char *)msgbuf;
@@ -325,9 +340,10 @@ static inline void mavlink_msg_vkfmu_status_send_buf(mavlink_message_t *msgbuf,
     _mav_put_uint32_t(buf, 8, dist_to_tar);
     _mav_put_uint16_t(buf, 12, ups_volt);
     _mav_put_uint16_t(buf, 14, adc_volt);
-    _mav_put_uint8_t(buf, 16, rtl_reason);
-    _mav_put_uint8_t(buf, 17, loiter_reason);
-    _mav_put_uint8_t(buf, 18, s_flag3);
+    _mav_put_uint16_t(buf, 16, servo_state);
+    _mav_put_uint8_t(buf, 18, rtl_reason);
+    _mav_put_uint8_t(buf, 19, loiter_reason);
+    _mav_put_uint8_t(buf, 20, 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
@@ -337,6 +353,7 @@ static inline void mavlink_msg_vkfmu_status_send_buf(mavlink_message_t *msgbuf,
     packet->dist_to_tar = dist_to_tar;
     packet->ups_volt = ups_volt;
     packet->adc_volt = adc_volt;
+    packet->servo_state = servo_state;
     packet->rtl_reason = rtl_reason;
     packet->loiter_reason = loiter_reason;
     packet->s_flag3 = s_flag3;
@@ -368,7 +385,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,  16);
+    return _MAV_RETURN_uint8_t(msg,  18);
 }
 
 /**
@@ -378,7 +395,7 @@ static inline uint8_t mavlink_msg_vkfmu_status_get_rtl_reason(const mavlink_mess
  */
 static inline uint8_t mavlink_msg_vkfmu_status_get_loiter_reason(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint8_t(msg,  17);
+    return _MAV_RETURN_uint8_t(msg,  19);
 }
 
 /**
@@ -388,7 +405,7 @@ static inline uint8_t mavlink_msg_vkfmu_status_get_loiter_reason(const mavlink_m
  */
 static inline uint8_t mavlink_msg_vkfmu_status_get_s_flag3(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint8_t(msg,  18);
+    return _MAV_RETURN_uint8_t(msg,  20);
 }
 
 /**
@@ -431,6 +448,16 @@ static inline uint32_t mavlink_msg_vkfmu_status_get_dist_to_tar(const mavlink_me
     return _MAV_RETURN_uint32_t(msg,  8);
 }
 
+/**
+ * @brief Get field servo_state from vkfmu_status message
+ *
+ * @return  bitmap for servo state
+ */
+static inline uint16_t mavlink_msg_vkfmu_status_get_servo_state(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint16_t(msg,  16);
+}
+
 /**
  * @brief Decode a vkfmu_status message into a struct
  *
@@ -445,6 +472,7 @@ static inline void mavlink_msg_vkfmu_status_decode(const mavlink_message_t* msg,
     vkfmu_status->dist_to_tar = mavlink_msg_vkfmu_status_get_dist_to_tar(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->servo_state = mavlink_msg_vkfmu_status_get_servo_state(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);

+ 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,17859,17963,53,120,187
+        963497464,963497672,963497880,17859,17963,18067,187,254,65
     };
     mavlink_vkfmu_status_t packet1, packet2;
         memset(&packet1, 0, sizeof(packet1));
@@ -122,6 +122,7 @@ static void mavlink_test_vkfmu_status(uint8_t system_id, uint8_t component_id, m
         packet1.dist_to_tar = packet_in.dist_to_tar;
         packet1.ups_volt = packet_in.ups_volt;
         packet1.adc_volt = packet_in.adc_volt;
+        packet1.servo_state = packet_in.servo_state;
         packet1.rtl_reason = packet_in.rtl_reason;
         packet1.loiter_reason = packet_in.loiter_reason;
         packet1.s_flag3 = packet_in.s_flag3;
@@ -139,12 +140,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 );
+    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 );
     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 );
+    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 );
     mavlink_msg_vkfmu_status_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
@@ -157,7 +158,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 );
+    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 );
     mavlink_msg_vkfmu_status_decode(last_msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 

Unele fișiere nu au fost afișate deoarece prea multe fișiere au fost modificate în acest diff