Browse Source

增加 VK_PAYLOAD_DATA_RELAY 消息

LiuYang 2 months ago
parent
commit
4121ad4d9e

+ 8 - 0
msg_definitions/VKFly.xml

@@ -991,6 +991,14 @@
       <field type="uint8_t" name="err_code"></field>
     </message>
 
+    <message id="53022" name="VK_PAYLOAD_DATA_RELAY">
+      <description>VK payload message relay</description>
+      <field type="uint16_t" name="payload_addr">payload address code</field>
+      <field type="uint8_t" name="reserve">reserve</field>
+      <field type="uint8_t" name="data_len">data field length in bytes</field>
+      <field type="uint8_t[128]" name="data">data to relay</field>
+    </message>
+
     <message id="53100" name="VK_FW_UPDATE_BEGIN">
       <description>VKFLY autopilot update firmware begin. This message send from GCS to autopilot. </description>
       <field type="uint8_t" name="target_system">Target system id.</field>

+ 10 - 0
readme.md

@@ -895,6 +895,16 @@ comp_id 为 0 时, 飞控将回复多个消息逐个返回所有可获取设备
 | radius    | 半径, m,          |
 | altitude  | 高度, m, 暂未使用 |
 
+### 2.29 载荷转发数据 VK_PAYLOAD_DATA_RELAY
+飞控将收到的载荷数据通过此包向地面站转发.
+飞控收到地面站的此包数据后, 将数据中 data 内容向载荷转发.
+
+| 字段         | 说明                  |
+| ------------ | --------------------- |
+| payload_addr | 载荷地址码, 目前暂填1 |
+| data_len     | data段字节长度        |
+| data         | 转发的数据内容        |
+
 ## 3 参数设置
 
 飞控的参数修改、读取方法参考 [mavlink services parameter](https://mavlink.io/en/services/parameter.html). 使用16字节的 paramid 作为每各参数的唯一表示码.

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 9043071210877765785
+#define MAVLINK_PRIMARY_XML_HASH -2374734789491976015
 
 #ifndef MAVLINK_STX
 #define MAVLINK_STX 253

+ 334 - 0
v2.0/VKFly/mavlink_msg_vk_payload_data_relay.h

@@ -0,0 +1,334 @@
+#pragma once
+// MESSAGE VK_PAYLOAD_DATA_RELAY PACKING
+
+#define MAVLINK_MSG_ID_VK_PAYLOAD_DATA_RELAY 53022
+
+
+typedef struct __mavlink_vk_payload_data_relay_t {
+ uint16_t payload_addr; /*<  payload address code*/
+ uint8_t reserve; /*<  reserve*/
+ uint8_t data_len; /*<  data field length in bytes*/
+ uint8_t data[128]; /*<  data to relay*/
+} mavlink_vk_payload_data_relay_t;
+
+#define MAVLINK_MSG_ID_VK_PAYLOAD_DATA_RELAY_LEN 132
+#define MAVLINK_MSG_ID_VK_PAYLOAD_DATA_RELAY_MIN_LEN 132
+#define MAVLINK_MSG_ID_53022_LEN 132
+#define MAVLINK_MSG_ID_53022_MIN_LEN 132
+
+#define MAVLINK_MSG_ID_VK_PAYLOAD_DATA_RELAY_CRC 37
+#define MAVLINK_MSG_ID_53022_CRC 37
+
+#define MAVLINK_MSG_VK_PAYLOAD_DATA_RELAY_FIELD_DATA_LEN 128
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_VK_PAYLOAD_DATA_RELAY { \
+    53022, \
+    "VK_PAYLOAD_DATA_RELAY", \
+    4, \
+    {  { "payload_addr", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_vk_payload_data_relay_t, payload_addr) }, \
+         { "reserve", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_vk_payload_data_relay_t, reserve) }, \
+         { "data_len", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_vk_payload_data_relay_t, data_len) }, \
+         { "data", NULL, MAVLINK_TYPE_UINT8_T, 128, 4, offsetof(mavlink_vk_payload_data_relay_t, data) }, \
+         } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_VK_PAYLOAD_DATA_RELAY { \
+    "VK_PAYLOAD_DATA_RELAY", \
+    4, \
+    {  { "payload_addr", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_vk_payload_data_relay_t, payload_addr) }, \
+         { "reserve", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_vk_payload_data_relay_t, reserve) }, \
+         { "data_len", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_vk_payload_data_relay_t, data_len) }, \
+         { "data", NULL, MAVLINK_TYPE_UINT8_T, 128, 4, offsetof(mavlink_vk_payload_data_relay_t, data) }, \
+         } \
+}
+#endif
+
+/**
+ * @brief Pack a vk_payload_data_relay 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 payload_addr  payload address code
+ * @param reserve  reserve
+ * @param data_len  data field length in bytes
+ * @param data  data to relay
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_vk_payload_data_relay_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+                               uint16_t payload_addr, uint8_t reserve, uint8_t data_len, const uint8_t *data)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_VK_PAYLOAD_DATA_RELAY_LEN];
+    _mav_put_uint16_t(buf, 0, payload_addr);
+    _mav_put_uint8_t(buf, 2, reserve);
+    _mav_put_uint8_t(buf, 3, data_len);
+    _mav_put_uint8_t_array(buf, 4, data, 128);
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VK_PAYLOAD_DATA_RELAY_LEN);
+#else
+    mavlink_vk_payload_data_relay_t packet;
+    packet.payload_addr = payload_addr;
+    packet.reserve = reserve;
+    packet.data_len = data_len;
+    mav_array_memcpy(packet.data, data, sizeof(uint8_t)*128);
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VK_PAYLOAD_DATA_RELAY_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_VK_PAYLOAD_DATA_RELAY;
+    return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_VK_PAYLOAD_DATA_RELAY_MIN_LEN, MAVLINK_MSG_ID_VK_PAYLOAD_DATA_RELAY_LEN, MAVLINK_MSG_ID_VK_PAYLOAD_DATA_RELAY_CRC);
+}
+
+/**
+ * @brief Pack a vk_payload_data_relay 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 payload_addr  payload address code
+ * @param reserve  reserve
+ * @param data_len  data field length in bytes
+ * @param data  data to relay
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_vk_payload_data_relay_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+                               uint16_t payload_addr, uint8_t reserve, uint8_t data_len, const uint8_t *data)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_VK_PAYLOAD_DATA_RELAY_LEN];
+    _mav_put_uint16_t(buf, 0, payload_addr);
+    _mav_put_uint8_t(buf, 2, reserve);
+    _mav_put_uint8_t(buf, 3, data_len);
+    _mav_put_uint8_t_array(buf, 4, data, 128);
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VK_PAYLOAD_DATA_RELAY_LEN);
+#else
+    mavlink_vk_payload_data_relay_t packet;
+    packet.payload_addr = payload_addr;
+    packet.reserve = reserve;
+    packet.data_len = data_len;
+    mav_array_memcpy(packet.data, data, sizeof(uint8_t)*128);
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VK_PAYLOAD_DATA_RELAY_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_VK_PAYLOAD_DATA_RELAY;
+#if MAVLINK_CRC_EXTRA
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_VK_PAYLOAD_DATA_RELAY_MIN_LEN, MAVLINK_MSG_ID_VK_PAYLOAD_DATA_RELAY_LEN, MAVLINK_MSG_ID_VK_PAYLOAD_DATA_RELAY_CRC);
+#else
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_VK_PAYLOAD_DATA_RELAY_MIN_LEN, MAVLINK_MSG_ID_VK_PAYLOAD_DATA_RELAY_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a vk_payload_data_relay 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 payload_addr  payload address code
+ * @param reserve  reserve
+ * @param data_len  data field length in bytes
+ * @param data  data to relay
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_vk_payload_data_relay_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+                               mavlink_message_t* msg,
+                                   uint16_t payload_addr,uint8_t reserve,uint8_t data_len,const uint8_t *data)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_VK_PAYLOAD_DATA_RELAY_LEN];
+    _mav_put_uint16_t(buf, 0, payload_addr);
+    _mav_put_uint8_t(buf, 2, reserve);
+    _mav_put_uint8_t(buf, 3, data_len);
+    _mav_put_uint8_t_array(buf, 4, data, 128);
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VK_PAYLOAD_DATA_RELAY_LEN);
+#else
+    mavlink_vk_payload_data_relay_t packet;
+    packet.payload_addr = payload_addr;
+    packet.reserve = reserve;
+    packet.data_len = data_len;
+    mav_array_memcpy(packet.data, data, sizeof(uint8_t)*128);
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VK_PAYLOAD_DATA_RELAY_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_VK_PAYLOAD_DATA_RELAY;
+    return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_VK_PAYLOAD_DATA_RELAY_MIN_LEN, MAVLINK_MSG_ID_VK_PAYLOAD_DATA_RELAY_LEN, MAVLINK_MSG_ID_VK_PAYLOAD_DATA_RELAY_CRC);
+}
+
+/**
+ * @brief Encode a vk_payload_data_relay 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_payload_data_relay C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_vk_payload_data_relay_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_vk_payload_data_relay_t* vk_payload_data_relay)
+{
+    return mavlink_msg_vk_payload_data_relay_pack(system_id, component_id, msg, vk_payload_data_relay->payload_addr, vk_payload_data_relay->reserve, vk_payload_data_relay->data_len, vk_payload_data_relay->data);
+}
+
+/**
+ * @brief Encode a vk_payload_data_relay 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_payload_data_relay C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_vk_payload_data_relay_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_vk_payload_data_relay_t* vk_payload_data_relay)
+{
+    return mavlink_msg_vk_payload_data_relay_pack_chan(system_id, component_id, chan, msg, vk_payload_data_relay->payload_addr, vk_payload_data_relay->reserve, vk_payload_data_relay->data_len, vk_payload_data_relay->data);
+}
+
+/**
+ * @brief Encode a vk_payload_data_relay 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_payload_data_relay C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_vk_payload_data_relay_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_vk_payload_data_relay_t* vk_payload_data_relay)
+{
+    return mavlink_msg_vk_payload_data_relay_pack_status(system_id, component_id, _status, msg,  vk_payload_data_relay->payload_addr, vk_payload_data_relay->reserve, vk_payload_data_relay->data_len, vk_payload_data_relay->data);
+}
+
+/**
+ * @brief Send a vk_payload_data_relay message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param payload_addr  payload address code
+ * @param reserve  reserve
+ * @param data_len  data field length in bytes
+ * @param data  data to relay
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_vk_payload_data_relay_send(mavlink_channel_t chan, uint16_t payload_addr, uint8_t reserve, uint8_t data_len, const uint8_t *data)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_VK_PAYLOAD_DATA_RELAY_LEN];
+    _mav_put_uint16_t(buf, 0, payload_addr);
+    _mav_put_uint8_t(buf, 2, reserve);
+    _mav_put_uint8_t(buf, 3, data_len);
+    _mav_put_uint8_t_array(buf, 4, data, 128);
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VK_PAYLOAD_DATA_RELAY, buf, MAVLINK_MSG_ID_VK_PAYLOAD_DATA_RELAY_MIN_LEN, MAVLINK_MSG_ID_VK_PAYLOAD_DATA_RELAY_LEN, MAVLINK_MSG_ID_VK_PAYLOAD_DATA_RELAY_CRC);
+#else
+    mavlink_vk_payload_data_relay_t packet;
+    packet.payload_addr = payload_addr;
+    packet.reserve = reserve;
+    packet.data_len = data_len;
+    mav_array_memcpy(packet.data, data, sizeof(uint8_t)*128);
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VK_PAYLOAD_DATA_RELAY, (const char *)&packet, MAVLINK_MSG_ID_VK_PAYLOAD_DATA_RELAY_MIN_LEN, MAVLINK_MSG_ID_VK_PAYLOAD_DATA_RELAY_LEN, MAVLINK_MSG_ID_VK_PAYLOAD_DATA_RELAY_CRC);
+#endif
+}
+
+/**
+ * @brief Send a vk_payload_data_relay message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_vk_payload_data_relay_send_struct(mavlink_channel_t chan, const mavlink_vk_payload_data_relay_t* vk_payload_data_relay)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    mavlink_msg_vk_payload_data_relay_send(chan, vk_payload_data_relay->payload_addr, vk_payload_data_relay->reserve, vk_payload_data_relay->data_len, vk_payload_data_relay->data);
+#else
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VK_PAYLOAD_DATA_RELAY, (const char *)vk_payload_data_relay, MAVLINK_MSG_ID_VK_PAYLOAD_DATA_RELAY_MIN_LEN, MAVLINK_MSG_ID_VK_PAYLOAD_DATA_RELAY_LEN, MAVLINK_MSG_ID_VK_PAYLOAD_DATA_RELAY_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_VK_PAYLOAD_DATA_RELAY_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_payload_data_relay_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint16_t payload_addr, uint8_t reserve, uint8_t data_len, const uint8_t *data)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char *buf = (char *)msgbuf;
+    _mav_put_uint16_t(buf, 0, payload_addr);
+    _mav_put_uint8_t(buf, 2, reserve);
+    _mav_put_uint8_t(buf, 3, data_len);
+    _mav_put_uint8_t_array(buf, 4, data, 128);
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VK_PAYLOAD_DATA_RELAY, buf, MAVLINK_MSG_ID_VK_PAYLOAD_DATA_RELAY_MIN_LEN, MAVLINK_MSG_ID_VK_PAYLOAD_DATA_RELAY_LEN, MAVLINK_MSG_ID_VK_PAYLOAD_DATA_RELAY_CRC);
+#else
+    mavlink_vk_payload_data_relay_t *packet = (mavlink_vk_payload_data_relay_t *)msgbuf;
+    packet->payload_addr = payload_addr;
+    packet->reserve = reserve;
+    packet->data_len = data_len;
+    mav_array_memcpy(packet->data, data, sizeof(uint8_t)*128);
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VK_PAYLOAD_DATA_RELAY, (const char *)packet, MAVLINK_MSG_ID_VK_PAYLOAD_DATA_RELAY_MIN_LEN, MAVLINK_MSG_ID_VK_PAYLOAD_DATA_RELAY_LEN, MAVLINK_MSG_ID_VK_PAYLOAD_DATA_RELAY_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE VK_PAYLOAD_DATA_RELAY UNPACKING
+
+
+/**
+ * @brief Get field payload_addr from vk_payload_data_relay message
+ *
+ * @return  payload address code
+ */
+static inline uint16_t mavlink_msg_vk_payload_data_relay_get_payload_addr(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint16_t(msg,  0);
+}
+
+/**
+ * @brief Get field reserve from vk_payload_data_relay message
+ *
+ * @return  reserve
+ */
+static inline uint8_t mavlink_msg_vk_payload_data_relay_get_reserve(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint8_t(msg,  2);
+}
+
+/**
+ * @brief Get field data_len from vk_payload_data_relay message
+ *
+ * @return  data field length in bytes
+ */
+static inline uint8_t mavlink_msg_vk_payload_data_relay_get_data_len(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint8_t(msg,  3);
+}
+
+/**
+ * @brief Get field data from vk_payload_data_relay message
+ *
+ * @return  data to relay
+ */
+static inline uint16_t mavlink_msg_vk_payload_data_relay_get_data(const mavlink_message_t* msg, uint8_t *data)
+{
+    return _MAV_RETURN_uint8_t_array(msg, data, 128,  4);
+}
+
+/**
+ * @brief Decode a vk_payload_data_relay message into a struct
+ *
+ * @param msg The message to decode
+ * @param vk_payload_data_relay C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_vk_payload_data_relay_decode(const mavlink_message_t* msg, mavlink_vk_payload_data_relay_t* vk_payload_data_relay)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    vk_payload_data_relay->payload_addr = mavlink_msg_vk_payload_data_relay_get_payload_addr(msg);
+    vk_payload_data_relay->reserve = mavlink_msg_vk_payload_data_relay_get_reserve(msg);
+    vk_payload_data_relay->data_len = mavlink_msg_vk_payload_data_relay_get_data_len(msg);
+    mavlink_msg_vk_payload_data_relay_get_data(msg, vk_payload_data_relay->data);
+#else
+        uint8_t len = msg->len < MAVLINK_MSG_ID_VK_PAYLOAD_DATA_RELAY_LEN? msg->len : MAVLINK_MSG_ID_VK_PAYLOAD_DATA_RELAY_LEN;
+        memset(vk_payload_data_relay, 0, MAVLINK_MSG_ID_VK_PAYLOAD_DATA_RELAY_LEN);
+    memcpy(vk_payload_data_relay, _MAV_PAYLOAD(msg), len);
+#endif
+}

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

@@ -968,6 +968,68 @@ static void mavlink_test_vk_weigher_state(uint8_t system_id, uint8_t component_i
 #endif
 }
 
+static void mavlink_test_vk_payload_data_relay(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_PAYLOAD_DATA_RELAY >= 256) {
+            return;
+        }
+#endif
+    mavlink_message_t msg;
+        uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+        uint16_t i;
+    mavlink_vk_payload_data_relay_t packet_in = {
+        17235,139,206,{ 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 36, 37, 38, 39, 40, 41, 42, 43, 44, 45, 46, 47, 48, 49, 50, 51, 52, 53, 54, 55, 56, 57, 58, 59, 60, 61, 62, 63, 64, 65, 66, 67, 68, 69, 70, 71, 72, 73, 74, 75, 76, 77, 78, 79, 80, 81, 82, 83, 84, 85, 86, 87, 88, 89, 90, 91, 92, 93, 94, 95, 96, 97, 98, 99, 100, 101, 102, 103, 104, 105, 106, 107, 108, 109, 110, 111, 112, 113, 114, 115, 116, 117, 118, 119, 120, 121, 122, 123, 124, 125, 126, 127, 128, 129, 130, 131, 132, 133, 134, 135, 136, 137, 138, 139, 140, 141, 142, 143, 144 }
+    };
+    mavlink_vk_payload_data_relay_t packet1, packet2;
+        memset(&packet1, 0, sizeof(packet1));
+        packet1.payload_addr = packet_in.payload_addr;
+        packet1.reserve = packet_in.reserve;
+        packet1.data_len = packet_in.data_len;
+        
+        mav_array_memcpy(packet1.data, packet_in.data, sizeof(uint8_t)*128);
+        
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+        if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+           // cope with extensions
+           memset(MAVLINK_MSG_ID_VK_PAYLOAD_DATA_RELAY_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_VK_PAYLOAD_DATA_RELAY_MIN_LEN);
+        }
+#endif
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_vk_payload_data_relay_encode(system_id, component_id, &msg, &packet1);
+    mavlink_msg_vk_payload_data_relay_decode(&msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_vk_payload_data_relay_pack(system_id, component_id, &msg , packet1.payload_addr , packet1.reserve , packet1.data_len , packet1.data );
+    mavlink_msg_vk_payload_data_relay_decode(&msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_vk_payload_data_relay_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.payload_addr , packet1.reserve , packet1.data_len , packet1.data );
+    mavlink_msg_vk_payload_data_relay_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_payload_data_relay_decode(last_msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+        
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_vk_payload_data_relay_send(MAVLINK_COMM_1 , packet1.payload_addr , packet1.reserve , packet1.data_len , packet1.data );
+    mavlink_msg_vk_payload_data_relay_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_PAYLOAD_DATA_RELAY") != NULL);
+    MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_VK_PAYLOAD_DATA_RELAY) != NULL);
+#endif
+}
+
 static void mavlink_test_vk_fw_update_begin(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
 {
 #ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
@@ -1356,6 +1418,7 @@ static void mavlink_test_VKFly(uint8_t system_id, uint8_t component_id, mavlink_
     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_payload_data_relay(system_id, component_id, last_msg);
     mavlink_test_vk_fw_update_begin(system_id, component_id, last_msg);
     mavlink_test_vk_fw_update_ack(system_id, component_id, last_msg);
     mavlink_test_vk_fw_update_data_request(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 "Mon Apr 21 2025"
+#define MAVLINK_BUILD_DATE "Mon May 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 -8619283996827401103
+#define MAVLINK_COMMON_XML_HASH -7846703562892100548
 
 #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 -8619283996827401103
+#define MAVLINK_PRIMARY_XML_HASH -7846703562892100548
 
 #ifndef MAVLINK_STX
 #define MAVLINK_STX 253

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

@@ -7,7 +7,7 @@
 #ifndef MAVLINK_VERSION_H
 #define MAVLINK_VERSION_H
 
-#define MAVLINK_BUILD_DATE "Mon Apr 21 2025"
+#define MAVLINK_BUILD_DATE "Mon May 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 -3880776603943811867
+#define MAVLINK_PRIMARY_XML_HASH -7092616748274636242
 
 #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 -3880776603943811867
+#define MAVLINK_MINIMAL_XML_HASH -7092616748274636242
 
 #ifdef __cplusplus
 extern "C" {

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

@@ -7,7 +7,7 @@
 #ifndef MAVLINK_VERSION_H
 #define MAVLINK_VERSION_H
 
-#define MAVLINK_BUILD_DATE "Mon Apr 21 2025"
+#define MAVLINK_BUILD_DATE "Mon May 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 2473718649607205095
+#define MAVLINK_PRIMARY_XML_HASH 8986179789204880499
 
 #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 2473718649607205095
+#define MAVLINK_STANDARD_XML_HASH 8986179789204880499
 
 #ifdef __cplusplus
 extern "C" {

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

@@ -7,7 +7,7 @@
 #ifndef MAVLINK_VERSION_H
 #define MAVLINK_VERSION_H
 
-#define MAVLINK_BUILD_DATE "Mon Apr 21 2025"
+#define MAVLINK_BUILD_DATE "Mon May 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