Browse Source

增加外部惯导消息定义代码生成

Liu Yang 1 week ago
parent
commit
380bb1c94c

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 1592171951267676919
+#define MAVLINK_PRIMARY_XML_HASH -2492706412209668611
 
 #ifndef MAVLINK_STX
 #define MAVLINK_STX 253

+ 960 - 0
v2.0/VKFly/mavlink_msg_vk_external_ins_nav.h

@@ -0,0 +1,960 @@
+#pragma once
+// MESSAGE VK_EXTERNAL_INS_NAV PACKING
+
+#define MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV 53023
+
+
+typedef struct __mavlink_vk_external_ins_nav_t {
+ uint32_t timestamp; /*< [ms] timestamp from system boot*/
+ int32_t lon; /*< [degE7] solved longitude*/
+ int32_t lat; /*< [degE7] solved latitude*/
+ float msl; /*< [m] solved latitude*/
+ float ve; /*< [m/s] solved east speed*/
+ float vn; /*< [m/s] solved north speed*/
+ float vu; /*< [m/s] solved up speed*/
+ float yaw; /*< [deg] yaw angle*/
+ float pitch; /*< [deg] pitch angle*/
+ float roll; /*< [deg] roll angle*/
+ float gx; /*< [deg/s] roll angle*/
+ float gy; /*< [deg/s] roll angle*/
+ float gz; /*< [deg/s] roll angle*/
+ float ax; /*< [m/s/s] roll angle*/
+ float ay; /*< [m/s/s] roll angle*/
+ float az; /*< [m/s/s] roll angle*/
+ int32_t sat_lon; /*< [degE7] gps longitude*/
+ int32_t sat_lat; /*< [degE7] gps latitude*/
+ float sat_msl; /*< [m] gps altitude*/
+ float sat_ve; /*< [m/s] gps east speed*/
+ float sat_vn; /*< [m/s] gps north speed*/
+ float sat_vu; /*< [m/s] gps up speed*/
+ uint8_t sat_pfix; /*<  gps position fix*/
+ uint8_t sat_hfix; /*<  gps heading fix*/
+ uint8_t wk_state; /*<  work state*/
+ uint8_t err_code; /*<  error code*/
+} mavlink_vk_external_ins_nav_t;
+
+#define MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV_LEN 92
+#define MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV_MIN_LEN 92
+#define MAVLINK_MSG_ID_53023_LEN 92
+#define MAVLINK_MSG_ID_53023_MIN_LEN 92
+
+#define MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV_CRC 115
+#define MAVLINK_MSG_ID_53023_CRC 115
+
+
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_VK_EXTERNAL_INS_NAV { \
+    53023, \
+    "VK_EXTERNAL_INS_NAV", \
+    26, \
+    {  { "timestamp", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_vk_external_ins_nav_t, timestamp) }, \
+         { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_vk_external_ins_nav_t, lon) }, \
+         { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_vk_external_ins_nav_t, lat) }, \
+         { "msl", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_vk_external_ins_nav_t, msl) }, \
+         { "ve", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_vk_external_ins_nav_t, ve) }, \
+         { "vn", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_vk_external_ins_nav_t, vn) }, \
+         { "vu", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_vk_external_ins_nav_t, vu) }, \
+         { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_vk_external_ins_nav_t, yaw) }, \
+         { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_vk_external_ins_nav_t, pitch) }, \
+         { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_vk_external_ins_nav_t, roll) }, \
+         { "gx", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_vk_external_ins_nav_t, gx) }, \
+         { "gy", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_vk_external_ins_nav_t, gy) }, \
+         { "gz", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_vk_external_ins_nav_t, gz) }, \
+         { "ax", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_vk_external_ins_nav_t, ax) }, \
+         { "ay", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_vk_external_ins_nav_t, ay) }, \
+         { "az", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_vk_external_ins_nav_t, az) }, \
+         { "sat_lon", NULL, MAVLINK_TYPE_INT32_T, 0, 64, offsetof(mavlink_vk_external_ins_nav_t, sat_lon) }, \
+         { "sat_lat", NULL, MAVLINK_TYPE_INT32_T, 0, 68, offsetof(mavlink_vk_external_ins_nav_t, sat_lat) }, \
+         { "sat_msl", NULL, MAVLINK_TYPE_FLOAT, 0, 72, offsetof(mavlink_vk_external_ins_nav_t, sat_msl) }, \
+         { "sat_ve", NULL, MAVLINK_TYPE_FLOAT, 0, 76, offsetof(mavlink_vk_external_ins_nav_t, sat_ve) }, \
+         { "sat_vn", NULL, MAVLINK_TYPE_FLOAT, 0, 80, offsetof(mavlink_vk_external_ins_nav_t, sat_vn) }, \
+         { "sat_vu", NULL, MAVLINK_TYPE_FLOAT, 0, 84, offsetof(mavlink_vk_external_ins_nav_t, sat_vu) }, \
+         { "sat_pfix", NULL, MAVLINK_TYPE_UINT8_T, 0, 88, offsetof(mavlink_vk_external_ins_nav_t, sat_pfix) }, \
+         { "sat_hfix", NULL, MAVLINK_TYPE_UINT8_T, 0, 89, offsetof(mavlink_vk_external_ins_nav_t, sat_hfix) }, \
+         { "wk_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 90, offsetof(mavlink_vk_external_ins_nav_t, wk_state) }, \
+         { "err_code", NULL, MAVLINK_TYPE_UINT8_T, 0, 91, offsetof(mavlink_vk_external_ins_nav_t, err_code) }, \
+         } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_VK_EXTERNAL_INS_NAV { \
+    "VK_EXTERNAL_INS_NAV", \
+    26, \
+    {  { "timestamp", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_vk_external_ins_nav_t, timestamp) }, \
+         { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_vk_external_ins_nav_t, lon) }, \
+         { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_vk_external_ins_nav_t, lat) }, \
+         { "msl", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_vk_external_ins_nav_t, msl) }, \
+         { "ve", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_vk_external_ins_nav_t, ve) }, \
+         { "vn", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_vk_external_ins_nav_t, vn) }, \
+         { "vu", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_vk_external_ins_nav_t, vu) }, \
+         { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_vk_external_ins_nav_t, yaw) }, \
+         { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_vk_external_ins_nav_t, pitch) }, \
+         { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_vk_external_ins_nav_t, roll) }, \
+         { "gx", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_vk_external_ins_nav_t, gx) }, \
+         { "gy", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_vk_external_ins_nav_t, gy) }, \
+         { "gz", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_vk_external_ins_nav_t, gz) }, \
+         { "ax", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_vk_external_ins_nav_t, ax) }, \
+         { "ay", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_vk_external_ins_nav_t, ay) }, \
+         { "az", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_vk_external_ins_nav_t, az) }, \
+         { "sat_lon", NULL, MAVLINK_TYPE_INT32_T, 0, 64, offsetof(mavlink_vk_external_ins_nav_t, sat_lon) }, \
+         { "sat_lat", NULL, MAVLINK_TYPE_INT32_T, 0, 68, offsetof(mavlink_vk_external_ins_nav_t, sat_lat) }, \
+         { "sat_msl", NULL, MAVLINK_TYPE_FLOAT, 0, 72, offsetof(mavlink_vk_external_ins_nav_t, sat_msl) }, \
+         { "sat_ve", NULL, MAVLINK_TYPE_FLOAT, 0, 76, offsetof(mavlink_vk_external_ins_nav_t, sat_ve) }, \
+         { "sat_vn", NULL, MAVLINK_TYPE_FLOAT, 0, 80, offsetof(mavlink_vk_external_ins_nav_t, sat_vn) }, \
+         { "sat_vu", NULL, MAVLINK_TYPE_FLOAT, 0, 84, offsetof(mavlink_vk_external_ins_nav_t, sat_vu) }, \
+         { "sat_pfix", NULL, MAVLINK_TYPE_UINT8_T, 0, 88, offsetof(mavlink_vk_external_ins_nav_t, sat_pfix) }, \
+         { "sat_hfix", NULL, MAVLINK_TYPE_UINT8_T, 0, 89, offsetof(mavlink_vk_external_ins_nav_t, sat_hfix) }, \
+         { "wk_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 90, offsetof(mavlink_vk_external_ins_nav_t, wk_state) }, \
+         { "err_code", NULL, MAVLINK_TYPE_UINT8_T, 0, 91, offsetof(mavlink_vk_external_ins_nav_t, err_code) }, \
+         } \
+}
+#endif
+
+/**
+ * @brief Pack a vk_external_ins_nav 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 timestamp [ms] timestamp from system boot
+ * @param lon [degE7] solved longitude
+ * @param lat [degE7] solved latitude
+ * @param msl [m] solved latitude
+ * @param ve [m/s] solved east speed
+ * @param vn [m/s] solved north speed
+ * @param vu [m/s] solved up speed
+ * @param yaw [deg] yaw angle
+ * @param pitch [deg] pitch angle
+ * @param roll [deg] roll angle
+ * @param gx [deg/s] roll angle
+ * @param gy [deg/s] roll angle
+ * @param gz [deg/s] roll angle
+ * @param ax [m/s/s] roll angle
+ * @param ay [m/s/s] roll angle
+ * @param az [m/s/s] roll angle
+ * @param sat_lon [degE7] gps longitude
+ * @param sat_lat [degE7] gps latitude
+ * @param sat_msl [m] gps altitude
+ * @param sat_ve [m/s] gps east speed
+ * @param sat_vn [m/s] gps north speed
+ * @param sat_vu [m/s] gps up speed
+ * @param sat_pfix  gps position fix
+ * @param sat_hfix  gps heading fix
+ * @param wk_state  work state
+ * @param err_code  error code
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_vk_external_ins_nav_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+                               uint32_t timestamp, int32_t lon, int32_t lat, float msl, float ve, float vn, float vu, float yaw, float pitch, float roll, float gx, float gy, float gz, float ax, float ay, float az, int32_t sat_lon, int32_t sat_lat, float sat_msl, float sat_ve, float sat_vn, float sat_vu, uint8_t sat_pfix, uint8_t sat_hfix, uint8_t wk_state, uint8_t err_code)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV_LEN];
+    _mav_put_uint32_t(buf, 0, timestamp);
+    _mav_put_int32_t(buf, 4, lon);
+    _mav_put_int32_t(buf, 8, lat);
+    _mav_put_float(buf, 12, msl);
+    _mav_put_float(buf, 16, ve);
+    _mav_put_float(buf, 20, vn);
+    _mav_put_float(buf, 24, vu);
+    _mav_put_float(buf, 28, yaw);
+    _mav_put_float(buf, 32, pitch);
+    _mav_put_float(buf, 36, roll);
+    _mav_put_float(buf, 40, gx);
+    _mav_put_float(buf, 44, gy);
+    _mav_put_float(buf, 48, gz);
+    _mav_put_float(buf, 52, ax);
+    _mav_put_float(buf, 56, ay);
+    _mav_put_float(buf, 60, az);
+    _mav_put_int32_t(buf, 64, sat_lon);
+    _mav_put_int32_t(buf, 68, sat_lat);
+    _mav_put_float(buf, 72, sat_msl);
+    _mav_put_float(buf, 76, sat_ve);
+    _mav_put_float(buf, 80, sat_vn);
+    _mav_put_float(buf, 84, sat_vu);
+    _mav_put_uint8_t(buf, 88, sat_pfix);
+    _mav_put_uint8_t(buf, 89, sat_hfix);
+    _mav_put_uint8_t(buf, 90, wk_state);
+    _mav_put_uint8_t(buf, 91, err_code);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV_LEN);
+#else
+    mavlink_vk_external_ins_nav_t packet;
+    packet.timestamp = timestamp;
+    packet.lon = lon;
+    packet.lat = lat;
+    packet.msl = msl;
+    packet.ve = ve;
+    packet.vn = vn;
+    packet.vu = vu;
+    packet.yaw = yaw;
+    packet.pitch = pitch;
+    packet.roll = roll;
+    packet.gx = gx;
+    packet.gy = gy;
+    packet.gz = gz;
+    packet.ax = ax;
+    packet.ay = ay;
+    packet.az = az;
+    packet.sat_lon = sat_lon;
+    packet.sat_lat = sat_lat;
+    packet.sat_msl = sat_msl;
+    packet.sat_ve = sat_ve;
+    packet.sat_vn = sat_vn;
+    packet.sat_vu = sat_vu;
+    packet.sat_pfix = sat_pfix;
+    packet.sat_hfix = sat_hfix;
+    packet.wk_state = wk_state;
+    packet.err_code = err_code;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV;
+    return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV_MIN_LEN, MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV_LEN, MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV_CRC);
+}
+
+/**
+ * @brief Pack a vk_external_ins_nav 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 timestamp [ms] timestamp from system boot
+ * @param lon [degE7] solved longitude
+ * @param lat [degE7] solved latitude
+ * @param msl [m] solved latitude
+ * @param ve [m/s] solved east speed
+ * @param vn [m/s] solved north speed
+ * @param vu [m/s] solved up speed
+ * @param yaw [deg] yaw angle
+ * @param pitch [deg] pitch angle
+ * @param roll [deg] roll angle
+ * @param gx [deg/s] roll angle
+ * @param gy [deg/s] roll angle
+ * @param gz [deg/s] roll angle
+ * @param ax [m/s/s] roll angle
+ * @param ay [m/s/s] roll angle
+ * @param az [m/s/s] roll angle
+ * @param sat_lon [degE7] gps longitude
+ * @param sat_lat [degE7] gps latitude
+ * @param sat_msl [m] gps altitude
+ * @param sat_ve [m/s] gps east speed
+ * @param sat_vn [m/s] gps north speed
+ * @param sat_vu [m/s] gps up speed
+ * @param sat_pfix  gps position fix
+ * @param sat_hfix  gps heading fix
+ * @param wk_state  work state
+ * @param err_code  error code
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_vk_external_ins_nav_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+                               uint32_t timestamp, int32_t lon, int32_t lat, float msl, float ve, float vn, float vu, float yaw, float pitch, float roll, float gx, float gy, float gz, float ax, float ay, float az, int32_t sat_lon, int32_t sat_lat, float sat_msl, float sat_ve, float sat_vn, float sat_vu, uint8_t sat_pfix, uint8_t sat_hfix, uint8_t wk_state, uint8_t err_code)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV_LEN];
+    _mav_put_uint32_t(buf, 0, timestamp);
+    _mav_put_int32_t(buf, 4, lon);
+    _mav_put_int32_t(buf, 8, lat);
+    _mav_put_float(buf, 12, msl);
+    _mav_put_float(buf, 16, ve);
+    _mav_put_float(buf, 20, vn);
+    _mav_put_float(buf, 24, vu);
+    _mav_put_float(buf, 28, yaw);
+    _mav_put_float(buf, 32, pitch);
+    _mav_put_float(buf, 36, roll);
+    _mav_put_float(buf, 40, gx);
+    _mav_put_float(buf, 44, gy);
+    _mav_put_float(buf, 48, gz);
+    _mav_put_float(buf, 52, ax);
+    _mav_put_float(buf, 56, ay);
+    _mav_put_float(buf, 60, az);
+    _mav_put_int32_t(buf, 64, sat_lon);
+    _mav_put_int32_t(buf, 68, sat_lat);
+    _mav_put_float(buf, 72, sat_msl);
+    _mav_put_float(buf, 76, sat_ve);
+    _mav_put_float(buf, 80, sat_vn);
+    _mav_put_float(buf, 84, sat_vu);
+    _mav_put_uint8_t(buf, 88, sat_pfix);
+    _mav_put_uint8_t(buf, 89, sat_hfix);
+    _mav_put_uint8_t(buf, 90, wk_state);
+    _mav_put_uint8_t(buf, 91, err_code);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV_LEN);
+#else
+    mavlink_vk_external_ins_nav_t packet;
+    packet.timestamp = timestamp;
+    packet.lon = lon;
+    packet.lat = lat;
+    packet.msl = msl;
+    packet.ve = ve;
+    packet.vn = vn;
+    packet.vu = vu;
+    packet.yaw = yaw;
+    packet.pitch = pitch;
+    packet.roll = roll;
+    packet.gx = gx;
+    packet.gy = gy;
+    packet.gz = gz;
+    packet.ax = ax;
+    packet.ay = ay;
+    packet.az = az;
+    packet.sat_lon = sat_lon;
+    packet.sat_lat = sat_lat;
+    packet.sat_msl = sat_msl;
+    packet.sat_ve = sat_ve;
+    packet.sat_vn = sat_vn;
+    packet.sat_vu = sat_vu;
+    packet.sat_pfix = sat_pfix;
+    packet.sat_hfix = sat_hfix;
+    packet.wk_state = wk_state;
+    packet.err_code = err_code;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV;
+#if MAVLINK_CRC_EXTRA
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV_MIN_LEN, MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV_LEN, MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV_CRC);
+#else
+    return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV_MIN_LEN, MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a vk_external_ins_nav 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 timestamp [ms] timestamp from system boot
+ * @param lon [degE7] solved longitude
+ * @param lat [degE7] solved latitude
+ * @param msl [m] solved latitude
+ * @param ve [m/s] solved east speed
+ * @param vn [m/s] solved north speed
+ * @param vu [m/s] solved up speed
+ * @param yaw [deg] yaw angle
+ * @param pitch [deg] pitch angle
+ * @param roll [deg] roll angle
+ * @param gx [deg/s] roll angle
+ * @param gy [deg/s] roll angle
+ * @param gz [deg/s] roll angle
+ * @param ax [m/s/s] roll angle
+ * @param ay [m/s/s] roll angle
+ * @param az [m/s/s] roll angle
+ * @param sat_lon [degE7] gps longitude
+ * @param sat_lat [degE7] gps latitude
+ * @param sat_msl [m] gps altitude
+ * @param sat_ve [m/s] gps east speed
+ * @param sat_vn [m/s] gps north speed
+ * @param sat_vu [m/s] gps up speed
+ * @param sat_pfix  gps position fix
+ * @param sat_hfix  gps heading fix
+ * @param wk_state  work state
+ * @param err_code  error code
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_vk_external_ins_nav_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+                               mavlink_message_t* msg,
+                                   uint32_t timestamp,int32_t lon,int32_t lat,float msl,float ve,float vn,float vu,float yaw,float pitch,float roll,float gx,float gy,float gz,float ax,float ay,float az,int32_t sat_lon,int32_t sat_lat,float sat_msl,float sat_ve,float sat_vn,float sat_vu,uint8_t sat_pfix,uint8_t sat_hfix,uint8_t wk_state,uint8_t err_code)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV_LEN];
+    _mav_put_uint32_t(buf, 0, timestamp);
+    _mav_put_int32_t(buf, 4, lon);
+    _mav_put_int32_t(buf, 8, lat);
+    _mav_put_float(buf, 12, msl);
+    _mav_put_float(buf, 16, ve);
+    _mav_put_float(buf, 20, vn);
+    _mav_put_float(buf, 24, vu);
+    _mav_put_float(buf, 28, yaw);
+    _mav_put_float(buf, 32, pitch);
+    _mav_put_float(buf, 36, roll);
+    _mav_put_float(buf, 40, gx);
+    _mav_put_float(buf, 44, gy);
+    _mav_put_float(buf, 48, gz);
+    _mav_put_float(buf, 52, ax);
+    _mav_put_float(buf, 56, ay);
+    _mav_put_float(buf, 60, az);
+    _mav_put_int32_t(buf, 64, sat_lon);
+    _mav_put_int32_t(buf, 68, sat_lat);
+    _mav_put_float(buf, 72, sat_msl);
+    _mav_put_float(buf, 76, sat_ve);
+    _mav_put_float(buf, 80, sat_vn);
+    _mav_put_float(buf, 84, sat_vu);
+    _mav_put_uint8_t(buf, 88, sat_pfix);
+    _mav_put_uint8_t(buf, 89, sat_hfix);
+    _mav_put_uint8_t(buf, 90, wk_state);
+    _mav_put_uint8_t(buf, 91, err_code);
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV_LEN);
+#else
+    mavlink_vk_external_ins_nav_t packet;
+    packet.timestamp = timestamp;
+    packet.lon = lon;
+    packet.lat = lat;
+    packet.msl = msl;
+    packet.ve = ve;
+    packet.vn = vn;
+    packet.vu = vu;
+    packet.yaw = yaw;
+    packet.pitch = pitch;
+    packet.roll = roll;
+    packet.gx = gx;
+    packet.gy = gy;
+    packet.gz = gz;
+    packet.ax = ax;
+    packet.ay = ay;
+    packet.az = az;
+    packet.sat_lon = sat_lon;
+    packet.sat_lat = sat_lat;
+    packet.sat_msl = sat_msl;
+    packet.sat_ve = sat_ve;
+    packet.sat_vn = sat_vn;
+    packet.sat_vu = sat_vu;
+    packet.sat_pfix = sat_pfix;
+    packet.sat_hfix = sat_hfix;
+    packet.wk_state = wk_state;
+    packet.err_code = err_code;
+
+        memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV_LEN);
+#endif
+
+    msg->msgid = MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV;
+    return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV_MIN_LEN, MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV_LEN, MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV_CRC);
+}
+
+/**
+ * @brief Encode a vk_external_ins_nav 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_external_ins_nav C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_vk_external_ins_nav_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_vk_external_ins_nav_t* vk_external_ins_nav)
+{
+    return mavlink_msg_vk_external_ins_nav_pack(system_id, component_id, msg, vk_external_ins_nav->timestamp, vk_external_ins_nav->lon, vk_external_ins_nav->lat, vk_external_ins_nav->msl, vk_external_ins_nav->ve, vk_external_ins_nav->vn, vk_external_ins_nav->vu, vk_external_ins_nav->yaw, vk_external_ins_nav->pitch, vk_external_ins_nav->roll, vk_external_ins_nav->gx, vk_external_ins_nav->gy, vk_external_ins_nav->gz, vk_external_ins_nav->ax, vk_external_ins_nav->ay, vk_external_ins_nav->az, vk_external_ins_nav->sat_lon, vk_external_ins_nav->sat_lat, vk_external_ins_nav->sat_msl, vk_external_ins_nav->sat_ve, vk_external_ins_nav->sat_vn, vk_external_ins_nav->sat_vu, vk_external_ins_nav->sat_pfix, vk_external_ins_nav->sat_hfix, vk_external_ins_nav->wk_state, vk_external_ins_nav->err_code);
+}
+
+/**
+ * @brief Encode a vk_external_ins_nav 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_external_ins_nav C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_vk_external_ins_nav_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_vk_external_ins_nav_t* vk_external_ins_nav)
+{
+    return mavlink_msg_vk_external_ins_nav_pack_chan(system_id, component_id, chan, msg, vk_external_ins_nav->timestamp, vk_external_ins_nav->lon, vk_external_ins_nav->lat, vk_external_ins_nav->msl, vk_external_ins_nav->ve, vk_external_ins_nav->vn, vk_external_ins_nav->vu, vk_external_ins_nav->yaw, vk_external_ins_nav->pitch, vk_external_ins_nav->roll, vk_external_ins_nav->gx, vk_external_ins_nav->gy, vk_external_ins_nav->gz, vk_external_ins_nav->ax, vk_external_ins_nav->ay, vk_external_ins_nav->az, vk_external_ins_nav->sat_lon, vk_external_ins_nav->sat_lat, vk_external_ins_nav->sat_msl, vk_external_ins_nav->sat_ve, vk_external_ins_nav->sat_vn, vk_external_ins_nav->sat_vu, vk_external_ins_nav->sat_pfix, vk_external_ins_nav->sat_hfix, vk_external_ins_nav->wk_state, vk_external_ins_nav->err_code);
+}
+
+/**
+ * @brief Encode a vk_external_ins_nav 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_external_ins_nav C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_vk_external_ins_nav_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_vk_external_ins_nav_t* vk_external_ins_nav)
+{
+    return mavlink_msg_vk_external_ins_nav_pack_status(system_id, component_id, _status, msg,  vk_external_ins_nav->timestamp, vk_external_ins_nav->lon, vk_external_ins_nav->lat, vk_external_ins_nav->msl, vk_external_ins_nav->ve, vk_external_ins_nav->vn, vk_external_ins_nav->vu, vk_external_ins_nav->yaw, vk_external_ins_nav->pitch, vk_external_ins_nav->roll, vk_external_ins_nav->gx, vk_external_ins_nav->gy, vk_external_ins_nav->gz, vk_external_ins_nav->ax, vk_external_ins_nav->ay, vk_external_ins_nav->az, vk_external_ins_nav->sat_lon, vk_external_ins_nav->sat_lat, vk_external_ins_nav->sat_msl, vk_external_ins_nav->sat_ve, vk_external_ins_nav->sat_vn, vk_external_ins_nav->sat_vu, vk_external_ins_nav->sat_pfix, vk_external_ins_nav->sat_hfix, vk_external_ins_nav->wk_state, vk_external_ins_nav->err_code);
+}
+
+/**
+ * @brief Send a vk_external_ins_nav message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param timestamp [ms] timestamp from system boot
+ * @param lon [degE7] solved longitude
+ * @param lat [degE7] solved latitude
+ * @param msl [m] solved latitude
+ * @param ve [m/s] solved east speed
+ * @param vn [m/s] solved north speed
+ * @param vu [m/s] solved up speed
+ * @param yaw [deg] yaw angle
+ * @param pitch [deg] pitch angle
+ * @param roll [deg] roll angle
+ * @param gx [deg/s] roll angle
+ * @param gy [deg/s] roll angle
+ * @param gz [deg/s] roll angle
+ * @param ax [m/s/s] roll angle
+ * @param ay [m/s/s] roll angle
+ * @param az [m/s/s] roll angle
+ * @param sat_lon [degE7] gps longitude
+ * @param sat_lat [degE7] gps latitude
+ * @param sat_msl [m] gps altitude
+ * @param sat_ve [m/s] gps east speed
+ * @param sat_vn [m/s] gps north speed
+ * @param sat_vu [m/s] gps up speed
+ * @param sat_pfix  gps position fix
+ * @param sat_hfix  gps heading fix
+ * @param wk_state  work state
+ * @param err_code  error code
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_vk_external_ins_nav_send(mavlink_channel_t chan, uint32_t timestamp, int32_t lon, int32_t lat, float msl, float ve, float vn, float vu, float yaw, float pitch, float roll, float gx, float gy, float gz, float ax, float ay, float az, int32_t sat_lon, int32_t sat_lat, float sat_msl, float sat_ve, float sat_vn, float sat_vu, uint8_t sat_pfix, uint8_t sat_hfix, uint8_t wk_state, uint8_t err_code)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char buf[MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV_LEN];
+    _mav_put_uint32_t(buf, 0, timestamp);
+    _mav_put_int32_t(buf, 4, lon);
+    _mav_put_int32_t(buf, 8, lat);
+    _mav_put_float(buf, 12, msl);
+    _mav_put_float(buf, 16, ve);
+    _mav_put_float(buf, 20, vn);
+    _mav_put_float(buf, 24, vu);
+    _mav_put_float(buf, 28, yaw);
+    _mav_put_float(buf, 32, pitch);
+    _mav_put_float(buf, 36, roll);
+    _mav_put_float(buf, 40, gx);
+    _mav_put_float(buf, 44, gy);
+    _mav_put_float(buf, 48, gz);
+    _mav_put_float(buf, 52, ax);
+    _mav_put_float(buf, 56, ay);
+    _mav_put_float(buf, 60, az);
+    _mav_put_int32_t(buf, 64, sat_lon);
+    _mav_put_int32_t(buf, 68, sat_lat);
+    _mav_put_float(buf, 72, sat_msl);
+    _mav_put_float(buf, 76, sat_ve);
+    _mav_put_float(buf, 80, sat_vn);
+    _mav_put_float(buf, 84, sat_vu);
+    _mav_put_uint8_t(buf, 88, sat_pfix);
+    _mav_put_uint8_t(buf, 89, sat_hfix);
+    _mav_put_uint8_t(buf, 90, wk_state);
+    _mav_put_uint8_t(buf, 91, err_code);
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV, buf, MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV_MIN_LEN, MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV_LEN, MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV_CRC);
+#else
+    mavlink_vk_external_ins_nav_t packet;
+    packet.timestamp = timestamp;
+    packet.lon = lon;
+    packet.lat = lat;
+    packet.msl = msl;
+    packet.ve = ve;
+    packet.vn = vn;
+    packet.vu = vu;
+    packet.yaw = yaw;
+    packet.pitch = pitch;
+    packet.roll = roll;
+    packet.gx = gx;
+    packet.gy = gy;
+    packet.gz = gz;
+    packet.ax = ax;
+    packet.ay = ay;
+    packet.az = az;
+    packet.sat_lon = sat_lon;
+    packet.sat_lat = sat_lat;
+    packet.sat_msl = sat_msl;
+    packet.sat_ve = sat_ve;
+    packet.sat_vn = sat_vn;
+    packet.sat_vu = sat_vu;
+    packet.sat_pfix = sat_pfix;
+    packet.sat_hfix = sat_hfix;
+    packet.wk_state = wk_state;
+    packet.err_code = err_code;
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV, (const char *)&packet, MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV_MIN_LEN, MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV_LEN, MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV_CRC);
+#endif
+}
+
+/**
+ * @brief Send a vk_external_ins_nav message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_vk_external_ins_nav_send_struct(mavlink_channel_t chan, const mavlink_vk_external_ins_nav_t* vk_external_ins_nav)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    mavlink_msg_vk_external_ins_nav_send(chan, vk_external_ins_nav->timestamp, vk_external_ins_nav->lon, vk_external_ins_nav->lat, vk_external_ins_nav->msl, vk_external_ins_nav->ve, vk_external_ins_nav->vn, vk_external_ins_nav->vu, vk_external_ins_nav->yaw, vk_external_ins_nav->pitch, vk_external_ins_nav->roll, vk_external_ins_nav->gx, vk_external_ins_nav->gy, vk_external_ins_nav->gz, vk_external_ins_nav->ax, vk_external_ins_nav->ay, vk_external_ins_nav->az, vk_external_ins_nav->sat_lon, vk_external_ins_nav->sat_lat, vk_external_ins_nav->sat_msl, vk_external_ins_nav->sat_ve, vk_external_ins_nav->sat_vn, vk_external_ins_nav->sat_vu, vk_external_ins_nav->sat_pfix, vk_external_ins_nav->sat_hfix, vk_external_ins_nav->wk_state, vk_external_ins_nav->err_code);
+#else
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV, (const char *)vk_external_ins_nav, MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV_MIN_LEN, MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV_LEN, MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV_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_external_ins_nav_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint32_t timestamp, int32_t lon, int32_t lat, float msl, float ve, float vn, float vu, float yaw, float pitch, float roll, float gx, float gy, float gz, float ax, float ay, float az, int32_t sat_lon, int32_t sat_lat, float sat_msl, float sat_ve, float sat_vn, float sat_vu, uint8_t sat_pfix, uint8_t sat_hfix, uint8_t wk_state, uint8_t err_code)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    char *buf = (char *)msgbuf;
+    _mav_put_uint32_t(buf, 0, timestamp);
+    _mav_put_int32_t(buf, 4, lon);
+    _mav_put_int32_t(buf, 8, lat);
+    _mav_put_float(buf, 12, msl);
+    _mav_put_float(buf, 16, ve);
+    _mav_put_float(buf, 20, vn);
+    _mav_put_float(buf, 24, vu);
+    _mav_put_float(buf, 28, yaw);
+    _mav_put_float(buf, 32, pitch);
+    _mav_put_float(buf, 36, roll);
+    _mav_put_float(buf, 40, gx);
+    _mav_put_float(buf, 44, gy);
+    _mav_put_float(buf, 48, gz);
+    _mav_put_float(buf, 52, ax);
+    _mav_put_float(buf, 56, ay);
+    _mav_put_float(buf, 60, az);
+    _mav_put_int32_t(buf, 64, sat_lon);
+    _mav_put_int32_t(buf, 68, sat_lat);
+    _mav_put_float(buf, 72, sat_msl);
+    _mav_put_float(buf, 76, sat_ve);
+    _mav_put_float(buf, 80, sat_vn);
+    _mav_put_float(buf, 84, sat_vu);
+    _mav_put_uint8_t(buf, 88, sat_pfix);
+    _mav_put_uint8_t(buf, 89, sat_hfix);
+    _mav_put_uint8_t(buf, 90, wk_state);
+    _mav_put_uint8_t(buf, 91, err_code);
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV, buf, MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV_MIN_LEN, MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV_LEN, MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV_CRC);
+#else
+    mavlink_vk_external_ins_nav_t *packet = (mavlink_vk_external_ins_nav_t *)msgbuf;
+    packet->timestamp = timestamp;
+    packet->lon = lon;
+    packet->lat = lat;
+    packet->msl = msl;
+    packet->ve = ve;
+    packet->vn = vn;
+    packet->vu = vu;
+    packet->yaw = yaw;
+    packet->pitch = pitch;
+    packet->roll = roll;
+    packet->gx = gx;
+    packet->gy = gy;
+    packet->gz = gz;
+    packet->ax = ax;
+    packet->ay = ay;
+    packet->az = az;
+    packet->sat_lon = sat_lon;
+    packet->sat_lat = sat_lat;
+    packet->sat_msl = sat_msl;
+    packet->sat_ve = sat_ve;
+    packet->sat_vn = sat_vn;
+    packet->sat_vu = sat_vu;
+    packet->sat_pfix = sat_pfix;
+    packet->sat_hfix = sat_hfix;
+    packet->wk_state = wk_state;
+    packet->err_code = err_code;
+
+    _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV, (const char *)packet, MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV_MIN_LEN, MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV_LEN, MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE VK_EXTERNAL_INS_NAV UNPACKING
+
+
+/**
+ * @brief Get field timestamp from vk_external_ins_nav message
+ *
+ * @return [ms] timestamp from system boot
+ */
+static inline uint32_t mavlink_msg_vk_external_ins_nav_get_timestamp(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint32_t(msg,  0);
+}
+
+/**
+ * @brief Get field lon from vk_external_ins_nav message
+ *
+ * @return [degE7] solved longitude
+ */
+static inline int32_t mavlink_msg_vk_external_ins_nav_get_lon(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_int32_t(msg,  4);
+}
+
+/**
+ * @brief Get field lat from vk_external_ins_nav message
+ *
+ * @return [degE7] solved latitude
+ */
+static inline int32_t mavlink_msg_vk_external_ins_nav_get_lat(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_int32_t(msg,  8);
+}
+
+/**
+ * @brief Get field msl from vk_external_ins_nav message
+ *
+ * @return [m] solved latitude
+ */
+static inline float mavlink_msg_vk_external_ins_nav_get_msl(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_float(msg,  12);
+}
+
+/**
+ * @brief Get field ve from vk_external_ins_nav message
+ *
+ * @return [m/s] solved east speed
+ */
+static inline float mavlink_msg_vk_external_ins_nav_get_ve(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_float(msg,  16);
+}
+
+/**
+ * @brief Get field vn from vk_external_ins_nav message
+ *
+ * @return [m/s] solved north speed
+ */
+static inline float mavlink_msg_vk_external_ins_nav_get_vn(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_float(msg,  20);
+}
+
+/**
+ * @brief Get field vu from vk_external_ins_nav message
+ *
+ * @return [m/s] solved up speed
+ */
+static inline float mavlink_msg_vk_external_ins_nav_get_vu(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_float(msg,  24);
+}
+
+/**
+ * @brief Get field yaw from vk_external_ins_nav message
+ *
+ * @return [deg] yaw angle
+ */
+static inline float mavlink_msg_vk_external_ins_nav_get_yaw(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_float(msg,  28);
+}
+
+/**
+ * @brief Get field pitch from vk_external_ins_nav message
+ *
+ * @return [deg] pitch angle
+ */
+static inline float mavlink_msg_vk_external_ins_nav_get_pitch(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_float(msg,  32);
+}
+
+/**
+ * @brief Get field roll from vk_external_ins_nav message
+ *
+ * @return [deg] roll angle
+ */
+static inline float mavlink_msg_vk_external_ins_nav_get_roll(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_float(msg,  36);
+}
+
+/**
+ * @brief Get field gx from vk_external_ins_nav message
+ *
+ * @return [deg/s] roll angle
+ */
+static inline float mavlink_msg_vk_external_ins_nav_get_gx(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_float(msg,  40);
+}
+
+/**
+ * @brief Get field gy from vk_external_ins_nav message
+ *
+ * @return [deg/s] roll angle
+ */
+static inline float mavlink_msg_vk_external_ins_nav_get_gy(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_float(msg,  44);
+}
+
+/**
+ * @brief Get field gz from vk_external_ins_nav message
+ *
+ * @return [deg/s] roll angle
+ */
+static inline float mavlink_msg_vk_external_ins_nav_get_gz(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_float(msg,  48);
+}
+
+/**
+ * @brief Get field ax from vk_external_ins_nav message
+ *
+ * @return [m/s/s] roll angle
+ */
+static inline float mavlink_msg_vk_external_ins_nav_get_ax(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_float(msg,  52);
+}
+
+/**
+ * @brief Get field ay from vk_external_ins_nav message
+ *
+ * @return [m/s/s] roll angle
+ */
+static inline float mavlink_msg_vk_external_ins_nav_get_ay(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_float(msg,  56);
+}
+
+/**
+ * @brief Get field az from vk_external_ins_nav message
+ *
+ * @return [m/s/s] roll angle
+ */
+static inline float mavlink_msg_vk_external_ins_nav_get_az(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_float(msg,  60);
+}
+
+/**
+ * @brief Get field sat_lon from vk_external_ins_nav message
+ *
+ * @return [degE7] gps longitude
+ */
+static inline int32_t mavlink_msg_vk_external_ins_nav_get_sat_lon(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_int32_t(msg,  64);
+}
+
+/**
+ * @brief Get field sat_lat from vk_external_ins_nav message
+ *
+ * @return [degE7] gps latitude
+ */
+static inline int32_t mavlink_msg_vk_external_ins_nav_get_sat_lat(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_int32_t(msg,  68);
+}
+
+/**
+ * @brief Get field sat_msl from vk_external_ins_nav message
+ *
+ * @return [m] gps altitude
+ */
+static inline float mavlink_msg_vk_external_ins_nav_get_sat_msl(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_float(msg,  72);
+}
+
+/**
+ * @brief Get field sat_ve from vk_external_ins_nav message
+ *
+ * @return [m/s] gps east speed
+ */
+static inline float mavlink_msg_vk_external_ins_nav_get_sat_ve(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_float(msg,  76);
+}
+
+/**
+ * @brief Get field sat_vn from vk_external_ins_nav message
+ *
+ * @return [m/s] gps north speed
+ */
+static inline float mavlink_msg_vk_external_ins_nav_get_sat_vn(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_float(msg,  80);
+}
+
+/**
+ * @brief Get field sat_vu from vk_external_ins_nav message
+ *
+ * @return [m/s] gps up speed
+ */
+static inline float mavlink_msg_vk_external_ins_nav_get_sat_vu(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_float(msg,  84);
+}
+
+/**
+ * @brief Get field sat_pfix from vk_external_ins_nav message
+ *
+ * @return  gps position fix
+ */
+static inline uint8_t mavlink_msg_vk_external_ins_nav_get_sat_pfix(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint8_t(msg,  88);
+}
+
+/**
+ * @brief Get field sat_hfix from vk_external_ins_nav message
+ *
+ * @return  gps heading fix
+ */
+static inline uint8_t mavlink_msg_vk_external_ins_nav_get_sat_hfix(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint8_t(msg,  89);
+}
+
+/**
+ * @brief Get field wk_state from vk_external_ins_nav message
+ *
+ * @return  work state
+ */
+static inline uint8_t mavlink_msg_vk_external_ins_nav_get_wk_state(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint8_t(msg,  90);
+}
+
+/**
+ * @brief Get field err_code from vk_external_ins_nav message
+ *
+ * @return  error code
+ */
+static inline uint8_t mavlink_msg_vk_external_ins_nav_get_err_code(const mavlink_message_t* msg)
+{
+    return _MAV_RETURN_uint8_t(msg,  91);
+}
+
+/**
+ * @brief Decode a vk_external_ins_nav message into a struct
+ *
+ * @param msg The message to decode
+ * @param vk_external_ins_nav C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_vk_external_ins_nav_decode(const mavlink_message_t* msg, mavlink_vk_external_ins_nav_t* vk_external_ins_nav)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+    vk_external_ins_nav->timestamp = mavlink_msg_vk_external_ins_nav_get_timestamp(msg);
+    vk_external_ins_nav->lon = mavlink_msg_vk_external_ins_nav_get_lon(msg);
+    vk_external_ins_nav->lat = mavlink_msg_vk_external_ins_nav_get_lat(msg);
+    vk_external_ins_nav->msl = mavlink_msg_vk_external_ins_nav_get_msl(msg);
+    vk_external_ins_nav->ve = mavlink_msg_vk_external_ins_nav_get_ve(msg);
+    vk_external_ins_nav->vn = mavlink_msg_vk_external_ins_nav_get_vn(msg);
+    vk_external_ins_nav->vu = mavlink_msg_vk_external_ins_nav_get_vu(msg);
+    vk_external_ins_nav->yaw = mavlink_msg_vk_external_ins_nav_get_yaw(msg);
+    vk_external_ins_nav->pitch = mavlink_msg_vk_external_ins_nav_get_pitch(msg);
+    vk_external_ins_nav->roll = mavlink_msg_vk_external_ins_nav_get_roll(msg);
+    vk_external_ins_nav->gx = mavlink_msg_vk_external_ins_nav_get_gx(msg);
+    vk_external_ins_nav->gy = mavlink_msg_vk_external_ins_nav_get_gy(msg);
+    vk_external_ins_nav->gz = mavlink_msg_vk_external_ins_nav_get_gz(msg);
+    vk_external_ins_nav->ax = mavlink_msg_vk_external_ins_nav_get_ax(msg);
+    vk_external_ins_nav->ay = mavlink_msg_vk_external_ins_nav_get_ay(msg);
+    vk_external_ins_nav->az = mavlink_msg_vk_external_ins_nav_get_az(msg);
+    vk_external_ins_nav->sat_lon = mavlink_msg_vk_external_ins_nav_get_sat_lon(msg);
+    vk_external_ins_nav->sat_lat = mavlink_msg_vk_external_ins_nav_get_sat_lat(msg);
+    vk_external_ins_nav->sat_msl = mavlink_msg_vk_external_ins_nav_get_sat_msl(msg);
+    vk_external_ins_nav->sat_ve = mavlink_msg_vk_external_ins_nav_get_sat_ve(msg);
+    vk_external_ins_nav->sat_vn = mavlink_msg_vk_external_ins_nav_get_sat_vn(msg);
+    vk_external_ins_nav->sat_vu = mavlink_msg_vk_external_ins_nav_get_sat_vu(msg);
+    vk_external_ins_nav->sat_pfix = mavlink_msg_vk_external_ins_nav_get_sat_pfix(msg);
+    vk_external_ins_nav->sat_hfix = mavlink_msg_vk_external_ins_nav_get_sat_hfix(msg);
+    vk_external_ins_nav->wk_state = mavlink_msg_vk_external_ins_nav_get_wk_state(msg);
+    vk_external_ins_nav->err_code = mavlink_msg_vk_external_ins_nav_get_err_code(msg);
+#else
+        uint8_t len = msg->len < MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV_LEN? msg->len : MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV_LEN;
+        memset(vk_external_ins_nav, 0, MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV_LEN);
+    memcpy(vk_external_ins_nav, _MAV_PAYLOAD(msg), len);
+#endif
+}

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

@@ -1030,6 +1030,90 @@ static void mavlink_test_vk_payload_data_relay(uint8_t system_id, uint8_t compon
 #endif
 }
 
+static void mavlink_test_vk_external_ins_nav(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_EXTERNAL_INS_NAV >= 256) {
+            return;
+        }
+#endif
+    mavlink_message_t msg;
+        uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+        uint16_t i;
+    mavlink_vk_external_ins_nav_t packet_in = {
+        963497464,963497672,963497880,101.0,129.0,157.0,185.0,213.0,241.0,269.0,297.0,325.0,353.0,381.0,409.0,437.0,963500792,963501000,521.0,549.0,577.0,605.0,13,80,147,214
+    };
+    mavlink_vk_external_ins_nav_t packet1, packet2;
+        memset(&packet1, 0, sizeof(packet1));
+        packet1.timestamp = packet_in.timestamp;
+        packet1.lon = packet_in.lon;
+        packet1.lat = packet_in.lat;
+        packet1.msl = packet_in.msl;
+        packet1.ve = packet_in.ve;
+        packet1.vn = packet_in.vn;
+        packet1.vu = packet_in.vu;
+        packet1.yaw = packet_in.yaw;
+        packet1.pitch = packet_in.pitch;
+        packet1.roll = packet_in.roll;
+        packet1.gx = packet_in.gx;
+        packet1.gy = packet_in.gy;
+        packet1.gz = packet_in.gz;
+        packet1.ax = packet_in.ax;
+        packet1.ay = packet_in.ay;
+        packet1.az = packet_in.az;
+        packet1.sat_lon = packet_in.sat_lon;
+        packet1.sat_lat = packet_in.sat_lat;
+        packet1.sat_msl = packet_in.sat_msl;
+        packet1.sat_ve = packet_in.sat_ve;
+        packet1.sat_vn = packet_in.sat_vn;
+        packet1.sat_vu = packet_in.sat_vu;
+        packet1.sat_pfix = packet_in.sat_pfix;
+        packet1.sat_hfix = packet_in.sat_hfix;
+        packet1.wk_state = packet_in.wk_state;
+        packet1.err_code = packet_in.err_code;
+        
+        
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+        if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+           // cope with extensions
+           memset(MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV_MIN_LEN);
+        }
+#endif
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_vk_external_ins_nav_encode(system_id, component_id, &msg, &packet1);
+    mavlink_msg_vk_external_ins_nav_decode(&msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_vk_external_ins_nav_pack(system_id, component_id, &msg , packet1.timestamp , packet1.lon , packet1.lat , packet1.msl , packet1.ve , packet1.vn , packet1.vu , packet1.yaw , packet1.pitch , packet1.roll , packet1.gx , packet1.gy , packet1.gz , packet1.ax , packet1.ay , packet1.az , packet1.sat_lon , packet1.sat_lat , packet1.sat_msl , packet1.sat_ve , packet1.sat_vn , packet1.sat_vu , packet1.sat_pfix , packet1.sat_hfix , packet1.wk_state , packet1.err_code );
+    mavlink_msg_vk_external_ins_nav_decode(&msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_vk_external_ins_nav_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.timestamp , packet1.lon , packet1.lat , packet1.msl , packet1.ve , packet1.vn , packet1.vu , packet1.yaw , packet1.pitch , packet1.roll , packet1.gx , packet1.gy , packet1.gz , packet1.ax , packet1.ay , packet1.az , packet1.sat_lon , packet1.sat_lat , packet1.sat_msl , packet1.sat_ve , packet1.sat_vn , packet1.sat_vu , packet1.sat_pfix , packet1.sat_hfix , packet1.wk_state , packet1.err_code );
+    mavlink_msg_vk_external_ins_nav_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_external_ins_nav_decode(last_msg, &packet2);
+        MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+        
+        memset(&packet2, 0, sizeof(packet2));
+    mavlink_msg_vk_external_ins_nav_send(MAVLINK_COMM_1 , packet1.timestamp , packet1.lon , packet1.lat , packet1.msl , packet1.ve , packet1.vn , packet1.vu , packet1.yaw , packet1.pitch , packet1.roll , packet1.gx , packet1.gy , packet1.gz , packet1.ax , packet1.ay , packet1.az , packet1.sat_lon , packet1.sat_lat , packet1.sat_msl , packet1.sat_ve , packet1.sat_vn , packet1.sat_vu , packet1.sat_pfix , packet1.sat_hfix , packet1.wk_state , packet1.err_code );
+    mavlink_msg_vk_external_ins_nav_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_EXTERNAL_INS_NAV") != NULL);
+    MAVLINK_ASSERT(mavlink_get_message_info_by_id(MAVLINK_MSG_ID_VK_EXTERNAL_INS_NAV) != 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
@@ -1429,6 +1513,7 @@ static void mavlink_test_VKFly(uint8_t system_id, uint8_t component_id, mavlink_
     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_external_ins_nav(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 Jul 07 2025"
+#define MAVLINK_BUILD_DATE "Tue Jul 22 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 1368628791415804270
+#define MAVLINK_COMMON_XML_HASH -3781279591668069567
 
 #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 1368628791415804270
+#define MAVLINK_PRIMARY_XML_HASH -3781279591668069567
 
 #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 Jul 07 2025"
+#define MAVLINK_BUILD_DATE "Tue Jul 22 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 -5627380079814967233
+#define MAVLINK_PRIMARY_XML_HASH 8751450265570853780
 
 #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 -5627380079814967233
+#define MAVLINK_MINIMAL_XML_HASH 8751450265570853780
 
 #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 Jul 07 2025"
+#define MAVLINK_BUILD_DATE "Tue Jul 22 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 3342795328012072205
+#define MAVLINK_PRIMARY_XML_HASH 8998573537179189301
 
 #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 3342795328012072205
+#define MAVLINK_STANDARD_XML_HASH 8998573537179189301
 
 #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 Jul 07 2025"
+#define MAVLINK_BUILD_DATE "Tue Jul 22 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