Browse Source

增加滤波VVH参数, 增加飞行时间、目标距离数据

Liu Yang 1 year ago
parent
commit
1f013ca405

+ 2 - 0
msg_definitions/VKFly.xml

@@ -522,6 +522,8 @@
       <field type="uint8_t" name="s_flag3">fmu sflag3</field>
       <field type="uint16_t" name="ups_volt">ups voltage in 0.1V</field>
       <field type="uint16_t" name="adc_volt">adc voltage in 0.1V</field>
+      <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>
     </message>
 
     <message id="53002" name="VK_ROI_TARGET">

+ 4 - 4
readme.md

@@ -939,7 +939,7 @@ mavlink common 标准消息集中主要由 MAVLINK_MSG_ID_COMMAND_INT 和 MAVLIN
   | --------------- | ----------------------------------------------------------------------------------------- |
   | time_boot_ms    | 系统本地时间戳ms                                                                          |
   | nav_status      | 传感器状态标志, 参考 VKFLY.xml 中 VKFLY_VKINS_NAV_STATUS                                  |
-  | err1            | 错误状态字1, 参考 VKFLY.xml 中 VKFLY_VKINS_ERR1_CODE                                      |
+  | s_flag1         |                                                                                           |
   | s_flag2         |                                                                                           |
   | s_flag3         |                                                                                           |
   | s_flag4         |                                                                                           |
@@ -955,7 +955,7 @@ mavlink common 标准消息集中主要由 MAVLINK_MSG_ID_COMMAND_INT 和 MAVLIN
   | 字段         | 说明                            |
   | ------------ | ------------------------------- |
   | time_boot_ms | 系统本地时间戳ms                |
-  | rtl_reason  | 返航原因, 参考 VKFLY_RTL_REASON |
+  | rtl_reason   | 返航原因, 参考 VKFLY_RTL_REASON |
   | s_flag2      | 预留                            |
   | s_flag3      | 预留                            |
   | ups_volt     | ups电压, 0.1V                   |
@@ -1119,8 +1119,8 @@ mavlink common 标准消息集中主要由 MAVLINK_MSG_ID_COMMAND_INT 和 MAVLIN
 | IMU_ATT_POFF0   | IMU水平PITCH偏移         | FLOAT  | 范围-180~180, 单位 deg <br>飞控通过水平校准自动捕获                                            |
 | IMU_ATT_YOFF0   | IMU水平YAW偏移           | FLOAT  | 范围-180~180, 单位 deg <br>可用于设置飞控IMU安装朝向 <br>安装方向前0, 右90, 左-90, 后180       |
 | ASPD_OFFSET0    | 空速计零偏               | FLOAT  | 范围 -5000~5000, 单位Pa                                                                        |
-| IMU_GFLT_TYPE   | 角速度滤波类型           | UINT8  | 范围0~4, 0-VH 1-H 2-M 3-L 4-VL                                                                 |
-| IMU_AFLT_TYPE   | 加速度滤波类型           | UINT8  | 范围0~4, 0-VH 1-H 2-M 3-L 4-VL                                                                 |
+| IMU_GFLT_TYPE   | 角速度滤波类型           | UINT8  | 范围0~5, 0-VH 1-H 2-M 3-L 4-VL 5-VVH                                                           |
+| IMU_AFLT_TYPE   | 加速度滤波类型           | UINT8  | 范围0~5, 0-VH 1-H 2-M 3-L 4-VL 5-VVH                                                           |
 | IMU_PXOFF       | 飞控IMU X安装距离偏差    | INT32  | 范围-1000~1000, 单位cm <br>IMU安装离飞机中心X轴向偏差距离                                      |
 | IMU_PYOFF       | 飞控IMU Y安装距离偏差    | INT32  | 范围-1000~1000, 单位cm <br>IMU安装离飞机中心Y轴向偏差距离                                      |
 | IMU_PZOFF       | 飞控IMU Z安装距离偏差    | INT32  | 范围-1000~1000, 单位cm <br>IMU安装离飞机中心Z轴向偏差距离                                      |

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 2476404480095784095
+#define MAVLINK_PRIMARY_XML_HASH 6950645065552306442
 
 #ifndef MAVLINK_STX
 #define MAVLINK_STX 253

+ 113 - 57
v2.0/VKFly/mavlink_msg_vkfmu_status.h

@@ -6,6 +6,8 @@
 
 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*/
+ 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*/
  uint8_t rtl_reason; /*<  return to launch reason.*/
@@ -13,13 +15,13 @@ typedef struct __mavlink_vkfmu_status_t {
  uint8_t s_flag3; /*<  fmu sflag3*/
 } mavlink_vkfmu_status_t;
 
-#define MAVLINK_MSG_ID_VKFMU_STATUS_LEN 11
-#define MAVLINK_MSG_ID_VKFMU_STATUS_MIN_LEN 11
-#define MAVLINK_MSG_ID_53001_LEN 11
-#define MAVLINK_MSG_ID_53001_MIN_LEN 11
+#define MAVLINK_MSG_ID_VKFMU_STATUS_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_CRC 31
-#define MAVLINK_MSG_ID_53001_CRC 31
+#define MAVLINK_MSG_ID_VKFMU_STATUS_CRC 223
+#define MAVLINK_MSG_ID_53001_CRC 223
 
 
 
@@ -27,25 +29,29 @@ typedef struct __mavlink_vkfmu_status_t {
 #define MAVLINK_MESSAGE_INFO_VKFMU_STATUS { \
     53001, \
     "VKFMU_STATUS", \
-    6, \
+    8, \
     {  { "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, 8, offsetof(mavlink_vkfmu_status_t, rtl_reason) }, \
-         { "s_flag2", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_vkfmu_status_t, s_flag2) }, \
-         { "s_flag3", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_vkfmu_status_t, s_flag3) }, \
-         { "ups_volt", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_vkfmu_status_t, ups_volt) }, \
-         { "adc_volt", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_vkfmu_status_t, adc_volt) }, \
+         { "rtl_reason", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_vkfmu_status_t, rtl_reason) }, \
+         { "s_flag2", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_vkfmu_status_t, s_flag2) }, \
+         { "s_flag3", NULL, MAVLINK_TYPE_UINT8_T, 0, 18, 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) }, \
          } \
 }
 #else
 #define MAVLINK_MESSAGE_INFO_VKFMU_STATUS { \
     "VKFMU_STATUS", \
-    6, \
+    8, \
     {  { "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, 8, offsetof(mavlink_vkfmu_status_t, rtl_reason) }, \
-         { "s_flag2", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_vkfmu_status_t, s_flag2) }, \
-         { "s_flag3", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_vkfmu_status_t, s_flag3) }, \
-         { "ups_volt", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_vkfmu_status_t, ups_volt) }, \
-         { "adc_volt", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_vkfmu_status_t, adc_volt) }, \
+         { "rtl_reason", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_vkfmu_status_t, rtl_reason) }, \
+         { "s_flag2", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_vkfmu_status_t, s_flag2) }, \
+         { "s_flag3", NULL, MAVLINK_TYPE_UINT8_T, 0, 18, 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) }, \
          } \
 }
 #endif
@@ -62,24 +68,30 @@ typedef struct __mavlink_vkfmu_status_t {
  * @param s_flag3  fmu sflag3
  * @param ups_volt  ups voltage in 0.1V
  * @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
  * @return length of the message in bytes (excluding serial stream start sign)
  */
 static inline uint16_t mavlink_msg_vkfmu_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
-                               uint32_t time_boot_ms, uint8_t rtl_reason, uint8_t s_flag2, uint8_t s_flag3, uint16_t ups_volt, uint16_t adc_volt)
+                               uint32_t time_boot_ms, uint8_t rtl_reason, uint8_t s_flag2, uint8_t s_flag3, uint16_t ups_volt, uint16_t adc_volt, uint32_t flight_time, uint32_t dist_to_tar)
 {
 #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_uint16_t(buf, 4, ups_volt);
-    _mav_put_uint16_t(buf, 6, adc_volt);
-    _mav_put_uint8_t(buf, 8, rtl_reason);
-    _mav_put_uint8_t(buf, 9, s_flag2);
-    _mav_put_uint8_t(buf, 10, s_flag3);
+    _mav_put_uint32_t(buf, 4, flight_time);
+    _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, s_flag2);
+    _mav_put_uint8_t(buf, 18, s_flag3);
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VKFMU_STATUS_LEN);
 #else
     mavlink_vkfmu_status_t packet;
     packet.time_boot_ms = time_boot_ms;
+    packet.flight_time = flight_time;
+    packet.dist_to_tar = dist_to_tar;
     packet.ups_volt = ups_volt;
     packet.adc_volt = adc_volt;
     packet.rtl_reason = rtl_reason;
@@ -106,24 +118,30 @@ static inline uint16_t mavlink_msg_vkfmu_status_pack(uint8_t system_id, uint8_t
  * @param s_flag3  fmu sflag3
  * @param ups_volt  ups voltage in 0.1V
  * @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
  * @return length of the message in bytes (excluding serial stream start sign)
  */
 static inline uint16_t mavlink_msg_vkfmu_status_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
-                               uint32_t time_boot_ms, uint8_t rtl_reason, uint8_t s_flag2, uint8_t s_flag3, uint16_t ups_volt, uint16_t adc_volt)
+                               uint32_t time_boot_ms, uint8_t rtl_reason, uint8_t s_flag2, uint8_t s_flag3, uint16_t ups_volt, uint16_t adc_volt, uint32_t flight_time, uint32_t dist_to_tar)
 {
 #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_uint16_t(buf, 4, ups_volt);
-    _mav_put_uint16_t(buf, 6, adc_volt);
-    _mav_put_uint8_t(buf, 8, rtl_reason);
-    _mav_put_uint8_t(buf, 9, s_flag2);
-    _mav_put_uint8_t(buf, 10, s_flag3);
+    _mav_put_uint32_t(buf, 4, flight_time);
+    _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, s_flag2);
+    _mav_put_uint8_t(buf, 18, s_flag3);
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VKFMU_STATUS_LEN);
 #else
     mavlink_vkfmu_status_t packet;
     packet.time_boot_ms = time_boot_ms;
+    packet.flight_time = flight_time;
+    packet.dist_to_tar = dist_to_tar;
     packet.ups_volt = ups_volt;
     packet.adc_volt = adc_volt;
     packet.rtl_reason = rtl_reason;
@@ -153,25 +171,31 @@ static inline uint16_t mavlink_msg_vkfmu_status_pack_status(uint8_t system_id, u
  * @param s_flag3  fmu sflag3
  * @param ups_volt  ups voltage in 0.1V
  * @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
  * @return length of the message in bytes (excluding serial stream start sign)
  */
 static inline uint16_t mavlink_msg_vkfmu_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
                                mavlink_message_t* msg,
-                                   uint32_t time_boot_ms,uint8_t rtl_reason,uint8_t s_flag2,uint8_t s_flag3,uint16_t ups_volt,uint16_t adc_volt)
+                                   uint32_t time_boot_ms,uint8_t rtl_reason,uint8_t s_flag2,uint8_t s_flag3,uint16_t ups_volt,uint16_t adc_volt,uint32_t flight_time,uint32_t dist_to_tar)
 {
 #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_uint16_t(buf, 4, ups_volt);
-    _mav_put_uint16_t(buf, 6, adc_volt);
-    _mav_put_uint8_t(buf, 8, rtl_reason);
-    _mav_put_uint8_t(buf, 9, s_flag2);
-    _mav_put_uint8_t(buf, 10, s_flag3);
+    _mav_put_uint32_t(buf, 4, flight_time);
+    _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, s_flag2);
+    _mav_put_uint8_t(buf, 18, s_flag3);
 
         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VKFMU_STATUS_LEN);
 #else
     mavlink_vkfmu_status_t packet;
     packet.time_boot_ms = time_boot_ms;
+    packet.flight_time = flight_time;
+    packet.dist_to_tar = dist_to_tar;
     packet.ups_volt = ups_volt;
     packet.adc_volt = adc_volt;
     packet.rtl_reason = rtl_reason;
@@ -195,7 +219,7 @@ static inline uint16_t mavlink_msg_vkfmu_status_pack_chan(uint8_t system_id, uin
  */
 static inline uint16_t mavlink_msg_vkfmu_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_vkfmu_status_t* vkfmu_status)
 {
-    return mavlink_msg_vkfmu_status_pack(system_id, component_id, msg, vkfmu_status->time_boot_ms, vkfmu_status->rtl_reason, vkfmu_status->s_flag2, vkfmu_status->s_flag3, vkfmu_status->ups_volt, vkfmu_status->adc_volt);
+    return mavlink_msg_vkfmu_status_pack(system_id, component_id, msg, vkfmu_status->time_boot_ms, vkfmu_status->rtl_reason, vkfmu_status->s_flag2, vkfmu_status->s_flag3, vkfmu_status->ups_volt, vkfmu_status->adc_volt, vkfmu_status->flight_time, vkfmu_status->dist_to_tar);
 }
 
 /**
@@ -209,7 +233,7 @@ static inline uint16_t mavlink_msg_vkfmu_status_encode(uint8_t system_id, uint8_
  */
 static inline uint16_t mavlink_msg_vkfmu_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_vkfmu_status_t* vkfmu_status)
 {
-    return mavlink_msg_vkfmu_status_pack_chan(system_id, component_id, chan, msg, vkfmu_status->time_boot_ms, vkfmu_status->rtl_reason, vkfmu_status->s_flag2, vkfmu_status->s_flag3, vkfmu_status->ups_volt, vkfmu_status->adc_volt);
+    return mavlink_msg_vkfmu_status_pack_chan(system_id, component_id, chan, msg, vkfmu_status->time_boot_ms, vkfmu_status->rtl_reason, vkfmu_status->s_flag2, vkfmu_status->s_flag3, vkfmu_status->ups_volt, vkfmu_status->adc_volt, vkfmu_status->flight_time, vkfmu_status->dist_to_tar);
 }
 
 /**
@@ -223,7 +247,7 @@ static inline uint16_t mavlink_msg_vkfmu_status_encode_chan(uint8_t system_id, u
  */
 static inline uint16_t mavlink_msg_vkfmu_status_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_vkfmu_status_t* vkfmu_status)
 {
-    return mavlink_msg_vkfmu_status_pack_status(system_id, component_id, _status, msg,  vkfmu_status->time_boot_ms, vkfmu_status->rtl_reason, vkfmu_status->s_flag2, vkfmu_status->s_flag3, vkfmu_status->ups_volt, vkfmu_status->adc_volt);
+    return mavlink_msg_vkfmu_status_pack_status(system_id, component_id, _status, msg,  vkfmu_status->time_boot_ms, vkfmu_status->rtl_reason, vkfmu_status->s_flag2, vkfmu_status->s_flag3, vkfmu_status->ups_volt, vkfmu_status->adc_volt, vkfmu_status->flight_time, vkfmu_status->dist_to_tar);
 }
 
 /**
@@ -236,24 +260,30 @@ static inline uint16_t mavlink_msg_vkfmu_status_encode_status(uint8_t system_id,
  * @param s_flag3  fmu sflag3
  * @param ups_volt  ups voltage in 0.1V
  * @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
  */
 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
-static inline void mavlink_msg_vkfmu_status_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t rtl_reason, uint8_t s_flag2, uint8_t s_flag3, uint16_t ups_volt, uint16_t adc_volt)
+static inline void mavlink_msg_vkfmu_status_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t rtl_reason, uint8_t s_flag2, uint8_t s_flag3, uint16_t ups_volt, uint16_t adc_volt, uint32_t flight_time, uint32_t dist_to_tar)
 {
 #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_uint16_t(buf, 4, ups_volt);
-    _mav_put_uint16_t(buf, 6, adc_volt);
-    _mav_put_uint8_t(buf, 8, rtl_reason);
-    _mav_put_uint8_t(buf, 9, s_flag2);
-    _mav_put_uint8_t(buf, 10, s_flag3);
+    _mav_put_uint32_t(buf, 4, flight_time);
+    _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, s_flag2);
+    _mav_put_uint8_t(buf, 18, s_flag3);
 
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VKFMU_STATUS, buf, MAVLINK_MSG_ID_VKFMU_STATUS_MIN_LEN, MAVLINK_MSG_ID_VKFMU_STATUS_LEN, MAVLINK_MSG_ID_VKFMU_STATUS_CRC);
 #else
     mavlink_vkfmu_status_t packet;
     packet.time_boot_ms = time_boot_ms;
+    packet.flight_time = flight_time;
+    packet.dist_to_tar = dist_to_tar;
     packet.ups_volt = ups_volt;
     packet.adc_volt = adc_volt;
     packet.rtl_reason = rtl_reason;
@@ -272,7 +302,7 @@ static inline void mavlink_msg_vkfmu_status_send(mavlink_channel_t chan, uint32_
 static inline void mavlink_msg_vkfmu_status_send_struct(mavlink_channel_t chan, const mavlink_vkfmu_status_t* vkfmu_status)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
-    mavlink_msg_vkfmu_status_send(chan, vkfmu_status->time_boot_ms, vkfmu_status->rtl_reason, vkfmu_status->s_flag2, vkfmu_status->s_flag3, vkfmu_status->ups_volt, vkfmu_status->adc_volt);
+    mavlink_msg_vkfmu_status_send(chan, vkfmu_status->time_boot_ms, vkfmu_status->rtl_reason, vkfmu_status->s_flag2, vkfmu_status->s_flag3, vkfmu_status->ups_volt, vkfmu_status->adc_volt, vkfmu_status->flight_time, vkfmu_status->dist_to_tar);
 #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
@@ -286,21 +316,25 @@ static inline void mavlink_msg_vkfmu_status_send_struct(mavlink_channel_t chan,
   is usually the receive buffer for the channel, and allows a reply to an
   incoming message with minimum stack space usage.
  */
-static inline void mavlink_msg_vkfmu_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint32_t time_boot_ms, uint8_t rtl_reason, uint8_t s_flag2, uint8_t s_flag3, uint16_t ups_volt, uint16_t adc_volt)
+static inline void mavlink_msg_vkfmu_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint32_t time_boot_ms, uint8_t rtl_reason, uint8_t s_flag2, uint8_t s_flag3, uint16_t ups_volt, uint16_t adc_volt, uint32_t flight_time, uint32_t dist_to_tar)
 {
 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
     char *buf = (char *)msgbuf;
     _mav_put_uint32_t(buf, 0, time_boot_ms);
-    _mav_put_uint16_t(buf, 4, ups_volt);
-    _mav_put_uint16_t(buf, 6, adc_volt);
-    _mav_put_uint8_t(buf, 8, rtl_reason);
-    _mav_put_uint8_t(buf, 9, s_flag2);
-    _mav_put_uint8_t(buf, 10, s_flag3);
+    _mav_put_uint32_t(buf, 4, flight_time);
+    _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, s_flag2);
+    _mav_put_uint8_t(buf, 18, s_flag3);
 
     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VKFMU_STATUS, buf, MAVLINK_MSG_ID_VKFMU_STATUS_MIN_LEN, MAVLINK_MSG_ID_VKFMU_STATUS_LEN, MAVLINK_MSG_ID_VKFMU_STATUS_CRC);
 #else
     mavlink_vkfmu_status_t *packet = (mavlink_vkfmu_status_t *)msgbuf;
     packet->time_boot_ms = time_boot_ms;
+    packet->flight_time = flight_time;
+    packet->dist_to_tar = dist_to_tar;
     packet->ups_volt = ups_volt;
     packet->adc_volt = adc_volt;
     packet->rtl_reason = rtl_reason;
@@ -334,7 +368,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,  8);
+    return _MAV_RETURN_uint8_t(msg,  16);
 }
 
 /**
@@ -344,7 +378,7 @@ static inline uint8_t mavlink_msg_vkfmu_status_get_rtl_reason(const mavlink_mess
  */
 static inline uint8_t mavlink_msg_vkfmu_status_get_s_flag2(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint8_t(msg,  9);
+    return _MAV_RETURN_uint8_t(msg,  17);
 }
 
 /**
@@ -354,7 +388,7 @@ static inline uint8_t mavlink_msg_vkfmu_status_get_s_flag2(const mavlink_message
  */
 static inline uint8_t mavlink_msg_vkfmu_status_get_s_flag3(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint8_t(msg,  10);
+    return _MAV_RETURN_uint8_t(msg,  18);
 }
 
 /**
@@ -364,7 +398,7 @@ static inline uint8_t mavlink_msg_vkfmu_status_get_s_flag3(const mavlink_message
  */
 static inline uint16_t mavlink_msg_vkfmu_status_get_ups_volt(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint16_t(msg,  4);
+    return _MAV_RETURN_uint16_t(msg,  12);
 }
 
 /**
@@ -374,7 +408,27 @@ static inline uint16_t mavlink_msg_vkfmu_status_get_ups_volt(const mavlink_messa
  */
 static inline uint16_t mavlink_msg_vkfmu_status_get_adc_volt(const mavlink_message_t* msg)
 {
-    return _MAV_RETURN_uint16_t(msg,  6);
+    return _MAV_RETURN_uint16_t(msg,  14);
+}
+
+/**
+ * @brief Get field flight_time from vkfmu_status message
+ *
+ * @return [s] flight time in seconds
+ */
+static inline uint32_t mavlink_msg_vkfmu_status_get_flight_time(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint32_t(msg,  4);
+}
+
+/**
+ * @brief Get field dist_to_tar from vkfmu_status message
+ *
+ * @return [cm] distance to target position in cm
+ */
+static inline uint32_t mavlink_msg_vkfmu_status_get_dist_to_tar(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint32_t(msg,  8);
 }
 
 /**
@@ -387,6 +441,8 @@ 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->flight_time = mavlink_msg_vkfmu_status_get_flight_time(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->rtl_reason = mavlink_msg_vkfmu_status_get_rtl_reason(msg);

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

@@ -113,11 +113,13 @@ 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,17443,17547,29,96,163
+        963497464,963497672,963497880,17859,17963,53,120,187
     };
     mavlink_vkfmu_status_t packet1, packet2;
         memset(&packet1, 0, sizeof(packet1));
         packet1.time_boot_ms = packet_in.time_boot_ms;
+        packet1.flight_time = packet_in.flight_time;
+        packet1.dist_to_tar = packet_in.dist_to_tar;
         packet1.ups_volt = packet_in.ups_volt;
         packet1.adc_volt = packet_in.adc_volt;
         packet1.rtl_reason = packet_in.rtl_reason;
@@ -137,12 +139,12 @@ static void mavlink_test_vkfmu_status(uint8_t system_id, uint8_t component_id, m
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_vkfmu_status_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.rtl_reason , packet1.s_flag2 , packet1.s_flag3 , packet1.ups_volt , packet1.adc_volt );
+    mavlink_msg_vkfmu_status_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.rtl_reason , packet1.s_flag2 , packet1.s_flag3 , packet1.ups_volt , packet1.adc_volt , packet1.flight_time , packet1.dist_to_tar );
     mavlink_msg_vkfmu_status_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_vkfmu_status_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.rtl_reason , packet1.s_flag2 , packet1.s_flag3 , packet1.ups_volt , packet1.adc_volt );
+    mavlink_msg_vkfmu_status_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.rtl_reason , packet1.s_flag2 , packet1.s_flag3 , packet1.ups_volt , packet1.adc_volt , packet1.flight_time , packet1.dist_to_tar );
     mavlink_msg_vkfmu_status_decode(&msg, &packet2);
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
@@ -155,7 +157,7 @@ static void mavlink_test_vkfmu_status(uint8_t system_id, uint8_t component_id, m
         MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
         
         memset(&packet2, 0, sizeof(packet2));
-    mavlink_msg_vkfmu_status_send(MAVLINK_COMM_1 , packet1.time_boot_ms , packet1.rtl_reason , packet1.s_flag2 , packet1.s_flag3 , packet1.ups_volt , packet1.adc_volt );
+    mavlink_msg_vkfmu_status_send(MAVLINK_COMM_1 , packet1.time_boot_ms , packet1.rtl_reason , packet1.s_flag2 , packet1.s_flag3 , packet1.ups_volt , packet1.adc_volt , packet1.flight_time , packet1.dist_to_tar );
     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 "Sat Jun 01 2024"
+#define MAVLINK_BUILD_DATE "Tue Jun 04 2024"
 #define MAVLINK_WIRE_PROTOCOL_VERSION "2.0"
 #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255
  

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

@@ -10,7 +10,7 @@
     #error Wrong include order: MAVLINK_COMMON.H MUST NOT BE DIRECTLY USED. Include mavlink.h from the same directory instead or set ALL AND EVERY defines from MAVLINK.H manually accordingly, including the #define MAVLINK_H call.
 #endif
 
-#define MAVLINK_COMMON_XML_HASH 4170117283486075577
+#define MAVLINK_COMMON_XML_HASH 3557628105774713632
 
 #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 4170117283486075577
+#define MAVLINK_PRIMARY_XML_HASH 3557628105774713632
 
 #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 "Sat Jun 01 2024"
+#define MAVLINK_BUILD_DATE "Tue Jun 04 2024"
 #define MAVLINK_WIRE_PROTOCOL_VERSION "2.0"
 #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255
  

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

@@ -6,7 +6,7 @@
 #ifndef MAVLINK_H
 #define MAVLINK_H
 
-#define MAVLINK_PRIMARY_XML_HASH 272505349383596025
+#define MAVLINK_PRIMARY_XML_HASH -1202384784193353241
 
 #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 272505349383596025
+#define MAVLINK_MINIMAL_XML_HASH -1202384784193353241
 
 #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 "Sat Jun 01 2024"
+#define MAVLINK_BUILD_DATE "Tue Jun 04 2024"
 #define MAVLINK_WIRE_PROTOCOL_VERSION "2.0"
 #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 22
  

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

@@ -6,7 +6,7 @@
 #ifndef MAVLINK_H
 #define MAVLINK_H
 
-#define MAVLINK_PRIMARY_XML_HASH -2481605930984615826
+#define MAVLINK_PRIMARY_XML_HASH -3564793849385641896
 
 #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 -2481605930984615826
+#define MAVLINK_STANDARD_XML_HASH -3564793849385641896
 
 #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 "Sat Jun 01 2024"
+#define MAVLINK_BUILD_DATE "Tue Jun 04 2024"
 #define MAVLINK_WIRE_PROTOCOL_VERSION "2.0"
 #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 22
  

Some files were not shown because too many files changed in this diff