Browse Source

增加返航盘旋点消息

Liu Yang 3 months ago
parent
commit
e478c4ee81

+ 13 - 3
msg_definitions/VKFly.xml

@@ -263,7 +263,7 @@
       <entry value="256" name="VKFLY_SYS_ERROR3_YAW_DIFF">
         <description></description>
       </entry>
-      <entry value="256" name="VKFLY_SYS_ERROR3_ASPD_LINK_LOST">
+      <entry value="512" name="VKFLY_SYS_ERROR3_ASPD_LINK_LOST">
         <description></description>
       </entry>
     </enum>
@@ -953,7 +953,7 @@
       <field type="float" name="throttle_value" minValue="-1.0" maxValue="1.0">Throttle control
         value, negative value means throttle off</field>
       <field type="float" name="yaw_value" minValue="-1.0" maxValue="1.0">Throttle control
-        value, negative value means throttle off</field>
+        value, negative value means turn left</field>
     </message>
 
     <message id="53010" name="VK_FIXEDWING_SERVO_SIGNAL">
@@ -962,6 +962,15 @@
       <field type="uint16_t[16]" name="servo_signal">Servo signal</field>
     </message>
 
+
+    <message id="53011" name="VK_FIXEDWING_RTL_CIRCLE_WP">
+      <description></description>
+      <field type="int32_t" name="latitude" units="degE7">Latitude in wgs84</field>
+      <field type="int32_t" name="longitude" units="degE7">Longitude in wgs84</field>
+      <field type="float" name="altitude" units="m">Relativ altitude</field>
+      <field type="float" name="radius" units="m">Radius in m, NAN means use default radius.</field>
+    </message>
+
     <message id="53020" name="VK_PARACHUTE_STATUS">
       <description>parachute status</description>
       <field type="uint32_t" name="timestamp" units="ms">timestamp from system boot</field>
@@ -972,6 +981,7 @@
       <field type="float" name="backvolt">parachute backup voltage</field>
     </message>
 
+
     <message id="53021" name="VK_WEIGHER_STATE">
       <description>Weigher state</description>
       <field type="uint32_t" name="timestamp" units="ms">timestamp from system boot</field>
@@ -1030,4 +1040,4 @@
 
   </messages>
 
-</mavlink>
+</mavlink>

+ 18 - 2
readme.md

@@ -190,6 +190,7 @@ typedef enum VKFLY_SYS_ERROR3
     VKFLY_SYS_ERROR3_GPS1_ERROR=64, /* 普通gps2数据异常 | */
     VKFLY_SYS_ERROR3_RTK_ERROR=128, /* RTK板卡数据异常 | */
     VKFLY_SYS_ERROR3_YAW_DIFF=256, /* RTK和磁偏航角差异过大 | */
+    VKFLY_SYS_ERROR3_ASPD_LINK_LOST=512, /* 空速计未连接 | */
     VKFLY_SYS_ERROR3_ENUM_END=129, /*  | */
 } VKFLY_SYS_ERROR3;
 ```
@@ -602,6 +603,9 @@ LOCAL 定位信息
 电机输出信息
 飞控顶周期向外发送, 默认 5hz. 包含各通道电机控制PWM信号的值.
 
+对于垂起固定翼飞机, M1~M4\M9~M12(当飞机为4轴8桨复合翼时) 为旋翼电机.
+M5~M8\M13~M16为固定翼舵面舵机.
+
 ### 2.9 电调状态回报数据 [ESC_STATUS]
 
 电调数据信息
@@ -878,6 +882,18 @@ LOCAL 定位信息
 | 6    | 左襟翼                                          |
 | 7    | 右襟翼                                          |
 
+### 2.28 固定翼返航盘旋点 VK_FIXEDWING_RTL_CIRCLE_WP
+
+飞控收到 VKFLY_CMD_SET_RTL_CIRCLE_WP 指令后, 向地面站发送此消息.
+可通过 MAV_CMD_REQUEST_MESSAGE 从飞控进行读取. 
+
+| 字段      | 说明              |
+| --------- | ----------------- |
+| latitude  | 纬度, 1e-7deg     |
+| longitude | 经度, 1e-7deg     |
+| radius    | 半径, m,          |
+| altitude  | 高度, m, 暂未使用 |
+
 ## 3 参数设置
 
 飞控的参数修改、读取方法参考 [mavlink services parameter](https://mavlink.io/en/services/parameter.html). 使用16字节的 paramid 作为每各参数的唯一表示码.
@@ -1001,7 +1017,7 @@ param3 分为 byte[4] 进行使用.
 | param6 | 经度 1e-7deg                                                                                                                                                                                                                                                                                                        |
 | param7 | 高度 m                                                                                                                                                                                                                                                                                                              |
 
-### 4.2 电子围栏 MAV_MISSION_TYPE_FENCE
+### 4.2 电子围栏 MAV_MISSION_TYPE_FENCE (未实施)
 
 飞控一共有200个电子围栏点.
 电子围栏功能上包括返回点(return_point)安全区(inclusion)和禁飞区(exlusion)三种.
@@ -1394,7 +1410,7 @@ param1~param5中,
 | param1 | 舵面检查, NAN表示忽略. 0全回中. 1横滚回中, 2右滚, 3左滚. 4俯仰回中, 5抬头, 6低头. 7方向回中, 8左转,9右转. |
 | param2 | 油门检查, NAN表示忽略. -1表示灭车, 0~100 表示给定油门百分比, 0为怠速, 100为满油门                         |
 
-### 5.39 固定翼返航盘旋点 VKFLY_CMD_SET_RTL_CIRCLE_POS
+### 5.39 固定翼返航盘旋点 VKFLY_CMD_SET_RTL_CIRCLE_WP
 
 设置固定翼返航盘旋点。返航时先执行飞往盘旋点, 到达后在盘旋点盘旋降高到返航高度, 再飞往起飞降落点降落.
 

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 -8903054276383468419
+#define MAVLINK_PRIMARY_XML_HASH -201426354676282899
 
 #ifndef MAVLINK_STX
 #define MAVLINK_STX 253

+ 6 - 6
v2.0/VKFly/mavlink_msg_vk_fixedwing_control_value.h

@@ -13,7 +13,7 @@ typedef struct __mavlink_vk_fixedwing_control_value_t {
  float throttle_value; /*<  Throttle control
         value, negative value means throttle off*/
  float yaw_value; /*<  Throttle control
-        value, negative value means throttle off*/
+        value, negative value means turn left*/
 } mavlink_vk_fixedwing_control_value_t;
 
 #define MAVLINK_MSG_ID_VK_FIXEDWING_CONTROL_VALUE_LEN 20
@@ -65,7 +65,7 @@ typedef struct __mavlink_vk_fixedwing_control_value_t {
  * @param throttle_value  Throttle control
         value, negative value means throttle off
  * @param yaw_value  Throttle control
-        value, negative value means throttle off
+        value, negative value means turn left
  * @return length of the message in bytes (excluding serial stream start sign)
  */
 static inline uint16_t mavlink_msg_vk_fixedwing_control_value_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
@@ -110,7 +110,7 @@ static inline uint16_t mavlink_msg_vk_fixedwing_control_value_pack(uint8_t syste
  * @param throttle_value  Throttle control
         value, negative value means throttle off
  * @param yaw_value  Throttle control
-        value, negative value means throttle off
+        value, negative value means turn left
  * @return length of the message in bytes (excluding serial stream start sign)
  */
 static inline uint16_t mavlink_msg_vk_fixedwing_control_value_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
@@ -158,7 +158,7 @@ static inline uint16_t mavlink_msg_vk_fixedwing_control_value_pack_status(uint8_
  * @param throttle_value  Throttle control
         value, negative value means throttle off
  * @param yaw_value  Throttle control
-        value, negative value means throttle off
+        value, negative value means turn left
  * @return length of the message in bytes (excluding serial stream start sign)
  */
 static inline uint16_t mavlink_msg_vk_fixedwing_control_value_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
@@ -242,7 +242,7 @@ static inline uint16_t mavlink_msg_vk_fixedwing_control_value_encode_status(uint
  * @param throttle_value  Throttle control
         value, negative value means throttle off
  * @param yaw_value  Throttle control
-        value, negative value means throttle off
+        value, negative value means turn left
  */
 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
@@ -367,7 +367,7 @@ static inline float mavlink_msg_vk_fixedwing_control_value_get_throttle_value(co
  * @brief Get field yaw_value from vk_fixedwing_control_value message
  *
  * @return  Throttle control
-        value, negative value means throttle off
+        value, negative value means turn left
  */
 static inline float mavlink_msg_vk_fixedwing_control_value_get_yaw_value(const mavlink_message_t* msg)
 {

+ 344 - 0
v2.0/VKFly/mavlink_msg_vk_fixedwing_rtl_circle_wp.h

@@ -0,0 +1,344 @@
+#pragma once
+// MESSAGE VK_FIXEDWING_RTL_CIRCLE_WP PACKING
+
+#define MAVLINK_MSG_ID_VK_FIXEDWING_RTL_CIRCLE_WP 53011
+
+
+typedef struct __mavlink_vk_fixedwing_rtl_circle_wp_t {
+ int32_t latitude; /*< [degE7] Latitude in wgs84*/
+ int32_t longitude; /*< [degE7] Longitude in wgs84*/
+ float altitude; /*< [m] Relativ altitude*/
+ float radius; /*< [m] Radius in m, NAN means use default radius.*/
+} mavlink_vk_fixedwing_rtl_circle_wp_t;
+
+#define MAVLINK_MSG_ID_VK_FIXEDWING_RTL_CIRCLE_WP_LEN 16
+#define MAVLINK_MSG_ID_VK_FIXEDWING_RTL_CIRCLE_WP_MIN_LEN 16
+#define MAVLINK_MSG_ID_53011_LEN 16
+#define MAVLINK_MSG_ID_53011_MIN_LEN 16
+
+#define MAVLINK_MSG_ID_VK_FIXEDWING_RTL_CIRCLE_WP_CRC 128
+#define MAVLINK_MSG_ID_53011_CRC 128
+
+
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_VK_FIXEDWING_RTL_CIRCLE_WP { \
+    53011, \
+    "VK_FIXEDWING_RTL_CIRCLE_WP", \
+    4, \
+    {  { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_vk_fixedwing_rtl_circle_wp_t, latitude) }, \
+         { "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_vk_fixedwing_rtl_circle_wp_t, longitude) }, \
+         { "altitude", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_vk_fixedwing_rtl_circle_wp_t, altitude) }, \
+         { "radius", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_vk_fixedwing_rtl_circle_wp_t, radius) }, \
+         } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_VK_FIXEDWING_RTL_CIRCLE_WP { \
+    "VK_FIXEDWING_RTL_CIRCLE_WP", \
+    4, \
+    {  { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_vk_fixedwing_rtl_circle_wp_t, latitude) }, \
+         { "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_vk_fixedwing_rtl_circle_wp_t, longitude) }, \
+         { "altitude", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_vk_fixedwing_rtl_circle_wp_t, altitude) }, \
+         { "radius", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_vk_fixedwing_rtl_circle_wp_t, radius) }, \
+         } \
+}
+#endif
+
+/**
+ * @brief Pack a vk_fixedwing_rtl_circle_wp message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param latitude [degE7] Latitude in wgs84
+ * @param longitude [degE7] Longitude in wgs84
+ * @param altitude [m] Relativ altitude
+ * @param radius [m] Radius in m, NAN means use default radius.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_vk_fixedwing_rtl_circle_wp_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+                               int32_t latitude, int32_t longitude, float altitude, float radius)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_VK_FIXEDWING_RTL_CIRCLE_WP_LEN];
+    _mav_put_int32_t(buf, 0, latitude);
+    _mav_put_int32_t(buf, 4, longitude);
+    _mav_put_float(buf, 8, altitude);
+    _mav_put_float(buf, 12, radius);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VK_FIXEDWING_RTL_CIRCLE_WP_LEN);
+#else
+    mavlink_vk_fixedwing_rtl_circle_wp_t packet;
+    packet.latitude = latitude;
+    packet.longitude = longitude;
+    packet.altitude = altitude;
+    packet.radius = radius;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VK_FIXEDWING_RTL_CIRCLE_WP_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_VK_FIXEDWING_RTL_CIRCLE_WP;
+    return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_VK_FIXEDWING_RTL_CIRCLE_WP_MIN_LEN, MAVLINK_MSG_ID_VK_FIXEDWING_RTL_CIRCLE_WP_LEN, MAVLINK_MSG_ID_VK_FIXEDWING_RTL_CIRCLE_WP_CRC);
+}
+
+/**
+ * @brief Pack a vk_fixedwing_rtl_circle_wp message
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ *
+ * @param latitude [degE7] Latitude in wgs84
+ * @param longitude [degE7] Longitude in wgs84
+ * @param altitude [m] Relativ altitude
+ * @param radius [m] Radius in m, NAN means use default radius.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_vk_fixedwing_rtl_circle_wp_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+                               int32_t latitude, int32_t longitude, float altitude, float radius)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_VK_FIXEDWING_RTL_CIRCLE_WP_LEN];
+    _mav_put_int32_t(buf, 0, latitude);
+    _mav_put_int32_t(buf, 4, longitude);
+    _mav_put_float(buf, 8, altitude);
+    _mav_put_float(buf, 12, radius);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VK_FIXEDWING_RTL_CIRCLE_WP_LEN);
+#else
+    mavlink_vk_fixedwing_rtl_circle_wp_t packet;
+    packet.latitude = latitude;
+    packet.longitude = longitude;
+    packet.altitude = altitude;
+    packet.radius = radius;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VK_FIXEDWING_RTL_CIRCLE_WP_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_VK_FIXEDWING_RTL_CIRCLE_WP;
+#if MAVLINK_CRC_EXTRA
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_VK_FIXEDWING_RTL_CIRCLE_WP_MIN_LEN, MAVLINK_MSG_ID_VK_FIXEDWING_RTL_CIRCLE_WP_LEN, MAVLINK_MSG_ID_VK_FIXEDWING_RTL_CIRCLE_WP_CRC);
+#else
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_VK_FIXEDWING_RTL_CIRCLE_WP_MIN_LEN, MAVLINK_MSG_ID_VK_FIXEDWING_RTL_CIRCLE_WP_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a vk_fixedwing_rtl_circle_wp message on a channel
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param chan The MAVLink channel this message will be sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param latitude [degE7] Latitude in wgs84
+ * @param longitude [degE7] Longitude in wgs84
+ * @param altitude [m] Relativ altitude
+ * @param radius [m] Radius in m, NAN means use default radius.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_vk_fixedwing_rtl_circle_wp_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+                               mavlink_message_t* msg,
+                                   int32_t latitude,int32_t longitude,float altitude,float radius)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_VK_FIXEDWING_RTL_CIRCLE_WP_LEN];
+    _mav_put_int32_t(buf, 0, latitude);
+    _mav_put_int32_t(buf, 4, longitude);
+    _mav_put_float(buf, 8, altitude);
+    _mav_put_float(buf, 12, radius);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VK_FIXEDWING_RTL_CIRCLE_WP_LEN);
+#else
+    mavlink_vk_fixedwing_rtl_circle_wp_t packet;
+    packet.latitude = latitude;
+    packet.longitude = longitude;
+    packet.altitude = altitude;
+    packet.radius = radius;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VK_FIXEDWING_RTL_CIRCLE_WP_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_VK_FIXEDWING_RTL_CIRCLE_WP;
+    return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_VK_FIXEDWING_RTL_CIRCLE_WP_MIN_LEN, MAVLINK_MSG_ID_VK_FIXEDWING_RTL_CIRCLE_WP_LEN, MAVLINK_MSG_ID_VK_FIXEDWING_RTL_CIRCLE_WP_CRC);
+}
+
+/**
+ * @brief Encode a vk_fixedwing_rtl_circle_wp struct
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param msg The MAVLink message to compress the data into
+ * @param vk_fixedwing_rtl_circle_wp C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_vk_fixedwing_rtl_circle_wp_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_vk_fixedwing_rtl_circle_wp_t* vk_fixedwing_rtl_circle_wp)
+{
+    return mavlink_msg_vk_fixedwing_rtl_circle_wp_pack(system_id, component_id, msg, vk_fixedwing_rtl_circle_wp->latitude, vk_fixedwing_rtl_circle_wp->longitude, vk_fixedwing_rtl_circle_wp->altitude, vk_fixedwing_rtl_circle_wp->radius);
+}
+
+/**
+ * @brief Encode a vk_fixedwing_rtl_circle_wp struct on a channel
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param chan The MAVLink channel this message will be sent over
+ * @param msg The MAVLink message to compress the data into
+ * @param vk_fixedwing_rtl_circle_wp C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_vk_fixedwing_rtl_circle_wp_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_vk_fixedwing_rtl_circle_wp_t* vk_fixedwing_rtl_circle_wp)
+{
+    return mavlink_msg_vk_fixedwing_rtl_circle_wp_pack_chan(system_id, component_id, chan, msg, vk_fixedwing_rtl_circle_wp->latitude, vk_fixedwing_rtl_circle_wp->longitude, vk_fixedwing_rtl_circle_wp->altitude, vk_fixedwing_rtl_circle_wp->radius);
+}
+
+/**
+ * @brief Encode a vk_fixedwing_rtl_circle_wp struct with provided status structure
+ *
+ * @param system_id ID of this system
+ * @param component_id ID of this component (e.g. 200 for IMU)
+ * @param status MAVLink status structure
+ * @param msg The MAVLink message to compress the data into
+ * @param vk_fixedwing_rtl_circle_wp C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_vk_fixedwing_rtl_circle_wp_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_vk_fixedwing_rtl_circle_wp_t* vk_fixedwing_rtl_circle_wp)
+{
+    return mavlink_msg_vk_fixedwing_rtl_circle_wp_pack_status(system_id, component_id, _status, msg,  vk_fixedwing_rtl_circle_wp->latitude, vk_fixedwing_rtl_circle_wp->longitude, vk_fixedwing_rtl_circle_wp->altitude, vk_fixedwing_rtl_circle_wp->radius);
+}
+
+/**
+ * @brief Send a vk_fixedwing_rtl_circle_wp message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param latitude [degE7] Latitude in wgs84
+ * @param longitude [degE7] Longitude in wgs84
+ * @param altitude [m] Relativ altitude
+ * @param radius [m] Radius in m, NAN means use default radius.
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_vk_fixedwing_rtl_circle_wp_send(mavlink_channel_t chan, int32_t latitude, int32_t longitude, float altitude, float radius)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_VK_FIXEDWING_RTL_CIRCLE_WP_LEN];
+    _mav_put_int32_t(buf, 0, latitude);
+    _mav_put_int32_t(buf, 4, longitude);
+    _mav_put_float(buf, 8, altitude);
+    _mav_put_float(buf, 12, radius);
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VK_FIXEDWING_RTL_CIRCLE_WP, buf, MAVLINK_MSG_ID_VK_FIXEDWING_RTL_CIRCLE_WP_MIN_LEN, MAVLINK_MSG_ID_VK_FIXEDWING_RTL_CIRCLE_WP_LEN, MAVLINK_MSG_ID_VK_FIXEDWING_RTL_CIRCLE_WP_CRC);
+#else
+    mavlink_vk_fixedwing_rtl_circle_wp_t packet;
+    packet.latitude = latitude;
+    packet.longitude = longitude;
+    packet.altitude = altitude;
+    packet.radius = radius;
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VK_FIXEDWING_RTL_CIRCLE_WP, (const char *)&packet, MAVLINK_MSG_ID_VK_FIXEDWING_RTL_CIRCLE_WP_MIN_LEN, MAVLINK_MSG_ID_VK_FIXEDWING_RTL_CIRCLE_WP_LEN, MAVLINK_MSG_ID_VK_FIXEDWING_RTL_CIRCLE_WP_CRC);
+#endif
+}
+
+/**
+ * @brief Send a vk_fixedwing_rtl_circle_wp message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_vk_fixedwing_rtl_circle_wp_send_struct(mavlink_channel_t chan, const mavlink_vk_fixedwing_rtl_circle_wp_t* vk_fixedwing_rtl_circle_wp)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    mavlink_msg_vk_fixedwing_rtl_circle_wp_send(chan, vk_fixedwing_rtl_circle_wp->latitude, vk_fixedwing_rtl_circle_wp->longitude, vk_fixedwing_rtl_circle_wp->altitude, vk_fixedwing_rtl_circle_wp->radius);
+#else
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VK_FIXEDWING_RTL_CIRCLE_WP, (const char *)vk_fixedwing_rtl_circle_wp, MAVLINK_MSG_ID_VK_FIXEDWING_RTL_CIRCLE_WP_MIN_LEN, MAVLINK_MSG_ID_VK_FIXEDWING_RTL_CIRCLE_WP_LEN, MAVLINK_MSG_ID_VK_FIXEDWING_RTL_CIRCLE_WP_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_VK_FIXEDWING_RTL_CIRCLE_WP_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+  This variant of _send() can be used to save stack space by re-using
+  memory from the receive buffer.  The caller provides a
+  mavlink_message_t which is the size of a full mavlink message. This
+  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_vk_fixedwing_rtl_circle_wp_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  int32_t latitude, int32_t longitude, float altitude, float radius)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char *buf = (char *)msgbuf;
+    _mav_put_int32_t(buf, 0, latitude);
+    _mav_put_int32_t(buf, 4, longitude);
+    _mav_put_float(buf, 8, altitude);
+    _mav_put_float(buf, 12, radius);
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VK_FIXEDWING_RTL_CIRCLE_WP, buf, MAVLINK_MSG_ID_VK_FIXEDWING_RTL_CIRCLE_WP_MIN_LEN, MAVLINK_MSG_ID_VK_FIXEDWING_RTL_CIRCLE_WP_LEN, MAVLINK_MSG_ID_VK_FIXEDWING_RTL_CIRCLE_WP_CRC);
+#else
+    mavlink_vk_fixedwing_rtl_circle_wp_t *packet = (mavlink_vk_fixedwing_rtl_circle_wp_t *)msgbuf;
+    packet->latitude = latitude;
+    packet->longitude = longitude;
+    packet->altitude = altitude;
+    packet->radius = radius;
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VK_FIXEDWING_RTL_CIRCLE_WP, (const char *)packet, MAVLINK_MSG_ID_VK_FIXEDWING_RTL_CIRCLE_WP_MIN_LEN, MAVLINK_MSG_ID_VK_FIXEDWING_RTL_CIRCLE_WP_LEN, MAVLINK_MSG_ID_VK_FIXEDWING_RTL_CIRCLE_WP_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE VK_FIXEDWING_RTL_CIRCLE_WP UNPACKING
+
+
+/**
+ * @brief Get field latitude from vk_fixedwing_rtl_circle_wp message
+ *
+ * @return [degE7] Latitude in wgs84
+ */
+static inline int32_t mavlink_msg_vk_fixedwing_rtl_circle_wp_get_latitude(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_int32_t(msg,  0);
+}
+
+/**
+ * @brief Get field longitude from vk_fixedwing_rtl_circle_wp message
+ *
+ * @return [degE7] Longitude in wgs84
+ */
+static inline int32_t mavlink_msg_vk_fixedwing_rtl_circle_wp_get_longitude(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_int32_t(msg,  4);
+}
+
+/**
+ * @brief Get field altitude from vk_fixedwing_rtl_circle_wp message
+ *
+ * @return [m] Relativ altitude
+ */
+static inline float mavlink_msg_vk_fixedwing_rtl_circle_wp_get_altitude(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_float(msg,  8);
+}
+
+/**
+ * @brief Get field radius from vk_fixedwing_rtl_circle_wp message
+ *
+ * @return [m] Radius in m, NAN means use default radius.
+ */
+static inline float mavlink_msg_vk_fixedwing_rtl_circle_wp_get_radius(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_float(msg,  12);
+}
+
+/**
+ * @brief Decode a vk_fixedwing_rtl_circle_wp message into a struct
+ *
+ * @param msg The message to decode
+ * @param vk_fixedwing_rtl_circle_wp C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_vk_fixedwing_rtl_circle_wp_decode(const mavlink_message_t* msg, mavlink_vk_fixedwing_rtl_circle_wp_t* vk_fixedwing_rtl_circle_wp)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    vk_fixedwing_rtl_circle_wp->latitude = mavlink_msg_vk_fixedwing_rtl_circle_wp_get_latitude(msg);
+    vk_fixedwing_rtl_circle_wp->longitude = mavlink_msg_vk_fixedwing_rtl_circle_wp_get_longitude(msg);
+    vk_fixedwing_rtl_circle_wp->altitude = mavlink_msg_vk_fixedwing_rtl_circle_wp_get_altitude(msg);
+    vk_fixedwing_rtl_circle_wp->radius = mavlink_msg_vk_fixedwing_rtl_circle_wp_get_radius(msg);
+#else
+        uint8_t len = msg->len < MAVLINK_MSG_ID_VK_FIXEDWING_RTL_CIRCLE_WP_LEN? msg->len : MAVLINK_MSG_ID_VK_FIXEDWING_RTL_CIRCLE_WP_LEN;
+        memset(vk_fixedwing_rtl_circle_wp, 0, MAVLINK_MSG_ID_VK_FIXEDWING_RTL_CIRCLE_WP_LEN);
+    memcpy(vk_fixedwing_rtl_circle_wp, _MAV_PAYLOAD(msg), len);
+#endif
+}

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

@@ -779,6 +779,68 @@ static void mavlink_test_vk_fixedwing_servo_signal(uint8_t system_id, uint8_t co
 #endif
 }
 
+static void mavlink_test_vk_fixedwing_rtl_circle_wp(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
+{
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+    mavlink_status_t *status = mavlink_get_channel_status(MAVLINK_COMM_0);
+        if ((status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_VK_FIXEDWING_RTL_CIRCLE_WP >= 256) {
+            return;
+        }
+#endif
+    mavlink_message_t msg;
+        uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+        uint16_t i;
+    mavlink_vk_fixedwing_rtl_circle_wp_t packet_in = {
+        963497464,963497672,73.0,101.0
+    };
+    mavlink_vk_fixedwing_rtl_circle_wp_t packet1, packet2;
+        memset(&packet1, 0, sizeof(packet1));
+        packet1.latitude = packet_in.latitude;
+        packet1.longitude = packet_in.longitude;
+        packet1.altitude = packet_in.altitude;
+        packet1.radius = packet_in.radius;
+        
+        
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+        if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+           // cope with extensions
+           memset(MAVLINK_MSG_ID_VK_FIXEDWING_RTL_CIRCLE_WP_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_VK_FIXEDWING_RTL_CIRCLE_WP_MIN_LEN);
+        }
+#endif
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_vk_fixedwing_rtl_circle_wp_encode(system_id, component_id, &msg, &packet1);
+    mavlink_msg_vk_fixedwing_rtl_circle_wp_decode(&msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_vk_fixedwing_rtl_circle_wp_pack(system_id, component_id, &msg , packet1.latitude , packet1.longitude , packet1.altitude , packet1.radius );
+    mavlink_msg_vk_fixedwing_rtl_circle_wp_decode(&msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_vk_fixedwing_rtl_circle_wp_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.latitude , packet1.longitude , packet1.altitude , packet1.radius );
+    mavlink_msg_vk_fixedwing_rtl_circle_wp_decode(&msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+        memset(&packet2, 0, sizeof(packet2));
+        mavlink_msg_to_send_buffer(buffer, &msg);
+        for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
+            comm_send_ch(MAVLINK_COMM_0, buffer[i]);
+        }
+    mavlink_msg_vk_fixedwing_rtl_circle_wp_decode(last_msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+        
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_vk_fixedwing_rtl_circle_wp_send(MAVLINK_COMM_1 , packet1.latitude , packet1.longitude , packet1.altitude , packet1.radius );
+    mavlink_msg_vk_fixedwing_rtl_circle_wp_decode(last_msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+#ifdef MAVLINK_HAVE_GET_MESSAGE_INFO
+    MAVLINK_ASSERT(mavlink_get_message_info_by_name("VK_FIXEDWING_RTL_CIRCLE_WP") != NULL);
+    MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_VK_FIXEDWING_RTL_CIRCLE_WP) != NULL);
+#endif
+}
+
 static void mavlink_test_vk_parachute_status(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
 {
 #ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
@@ -1291,6 +1353,7 @@ static void mavlink_test_VKFly(uint8_t system_id, uint8_t component_id, mavlink_
     mavlink_test_vk_digi_esc_status(system_id, component_id, last_msg);
     mavlink_test_vk_fixedwing_control_value(system_id, component_id, last_msg);
     mavlink_test_vk_fixedwing_servo_signal(system_id, component_id, last_msg);
+    mavlink_test_vk_fixedwing_rtl_circle_wp(system_id, component_id, last_msg);
     mavlink_test_vk_parachute_status(system_id, component_id, last_msg);
     mavlink_test_vk_weigher_state(system_id, component_id, last_msg);
     mavlink_test_vk_fw_update_begin(system_id, component_id, last_msg);

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

@@ -7,7 +7,7 @@
 #ifndef MAVLINK_VERSION_H
 #define MAVLINK_VERSION_H
 
-#define MAVLINK_BUILD_DATE "Fri Apr 18 2025"
+#define MAVLINK_BUILD_DATE "Sat Apr 19 2025"
 #define MAVLINK_WIRE_PROTOCOL_VERSION "2.0"
 #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 255
  

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

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

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

@@ -6,7 +6,7 @@
 #ifndef MAVLINK_H
 #define MAVLINK_H
 
-#define MAVLINK_PRIMARY_XML_HASH -6232334486436891425
+#define MAVLINK_PRIMARY_XML_HASH 54582401511230997
 
 #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 -6232334486436891425
+#define MAVLINK_MINIMAL_XML_HASH 54582401511230997
 
 #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 "Fri Apr 18 2025"
+#define MAVLINK_BUILD_DATE "Sat Apr 19 2025"
 #define MAVLINK_WIRE_PROTOCOL_VERSION "2.0"
 #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 22
  

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

@@ -6,7 +6,7 @@
 #ifndef MAVLINK_H
 #define MAVLINK_H
 
-#define MAVLINK_PRIMARY_XML_HASH -2346958281356136060
+#define MAVLINK_PRIMARY_XML_HASH -1048906206261826113
 
 #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 -2346958281356136060
+#define MAVLINK_STANDARD_XML_HASH -1048906206261826113
 
 #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 "Fri Apr 18 2025"
+#define MAVLINK_BUILD_DATE "Sat Apr 19 2025"
 #define MAVLINK_WIRE_PROTOCOL_VERSION "2.0"
 #define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 22
  

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