From 1fb5cb53e9f6601171f08caa5782ea3b59a82d46 Mon Sep 17 00:00:00 2001
From: frogmane <7685285+xznhj8129@users.noreply.github.com>
Date: Sat, 13 Dec 2025 03:27:41 -0500
Subject: [PATCH 01/46] mavlink compatibility fixes
---
src/main/telemetry/mavlink.c | 613 +++++++++++++++++++++++++++++++----
1 file changed, 549 insertions(+), 64 deletions(-)
diff --git a/src/main/telemetry/mavlink.c b/src/main/telemetry/mavlink.c
index d5084b32a62..50d59ec5909 100644
--- a/src/main/telemetry/mavlink.c
+++ b/src/main/telemetry/mavlink.c
@@ -97,6 +97,15 @@
#define TELEMETRY_MAVLINK_PORT_MODE MODE_RXTX
#define TELEMETRY_MAVLINK_MAXRATE 50
#define TELEMETRY_MAVLINK_DELAY ((1000 * 1000) / TELEMETRY_MAVLINK_MAXRATE)
+#define MAV_DATA_STREAM_EXTENDED_SYS_STATE (MAV_DATA_STREAM_EXTRA3 + 1)
+
+typedef enum {
+ MAV_FRAME_SUPPORTED_NONE = 0,
+ MAV_FRAME_SUPPORTED_GLOBAL = (1 << 0),
+ MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT = (1 << 1),
+ MAV_FRAME_SUPPORTED_GLOBAL_INT = (1 << 2),
+ MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT_INT = (1 << 3),
+} mavFrameSupportMask_e;
/**
* MAVLink requires angles to be in the range -Pi..Pi.
@@ -129,7 +138,11 @@ typedef enum APM_PLANE_MODE
PLANE_MODE_QLAND=20,
PLANE_MODE_QRTL=21,
PLANE_MODE_QAUTOTUNE=22,
- PLANE_MODE_ENUM_END=23,
+ PLANE_MODE_QACRO=23,
+ PLANE_MODE_THERMAL=24,
+ PLANE_MODE_LOITER_ALT_QLAND=25,
+ PLANE_MODE_AUTOLAND=26,
+ PLANE_MODE_ENUM_END=27,
} APM_PLANE_MODE;
/** @brief A mapping of copter flight modes for custom_mode field of heartbeat. */
@@ -154,7 +167,14 @@ typedef enum APM_COPTER_MODE
COPTER_MODE_AVOID_ADSB=19,
COPTER_MODE_GUIDED_NOGPS=20,
COPTER_MODE_SMART_RTL=21,
- COPTER_MODE_ENUM_END=22,
+ COPTER_MODE_FLOWHOLD=22,
+ COPTER_MODE_FOLLOW=23,
+ COPTER_MODE_ZIGZAG=24,
+ COPTER_MODE_SYSTEMID=25,
+ COPTER_MODE_AUTOROTATE=26,
+ COPTER_MODE_AUTO_RTL=27,
+ COPTER_MODE_TURTLE=28,
+ COPTER_MODE_ENUM_END=29,
} APM_COPTER_MODE;
static serialPort_t *mavlinkPort = NULL;
@@ -172,12 +192,14 @@ static uint8_t mavRates[] = {
[MAV_DATA_STREAM_POSITION] = 2, // 2Hz
[MAV_DATA_STREAM_EXTRA1] = 3, // 3Hz
[MAV_DATA_STREAM_EXTRA2] = 2, // 2Hz, HEARTBEATs are important
- [MAV_DATA_STREAM_EXTRA3] = 1 // 1Hz
+ [MAV_DATA_STREAM_EXTRA3] = 1, // 1Hz
+ [MAV_DATA_STREAM_EXTENDED_SYS_STATE] = 1 // 1Hz
};
#define MAXSTREAMS (sizeof(mavRates) / sizeof(mavRates[0]))
static timeUs_t lastMavlinkMessage = 0;
+static uint8_t mavRatesConfigured[MAXSTREAMS];
static uint8_t mavTicks[MAXSTREAMS];
static mavlink_message_t mavSendMsg;
static mavlink_message_t mavRecvMsg;
@@ -286,6 +308,22 @@ static int mavlinkStreamTrigger(enum MAV_DATA_STREAM streamNum)
return 0;
}
+static void mavlinkSetStreamRate(uint8_t streamNum, uint8_t rate)
+{
+ mavRates[streamNum] = rate;
+ mavTicks[streamNum] = 0;
+}
+
+static int32_t mavlinkStreamIntervalUs(uint8_t streamNum)
+{
+ uint8_t rate = mavRates[streamNum];
+ if (rate == 0) {
+ return -1;
+ }
+
+ return 1000000 / rate;
+}
+
void freeMAVLinkTelemetryPort(void)
{
closeSerialPort(mavlinkPort);
@@ -297,6 +335,7 @@ void initMAVLinkTelemetry(void)
{
portConfig = findSerialPortConfig(FUNCTION_TELEMETRY_MAVLINK);
mavlinkPortSharing = determinePortSharing(portConfig, FUNCTION_TELEMETRY_MAVLINK);
+ memcpy(mavRatesConfigured, mavRates, sizeof(mavRatesConfigured));
}
void configureMAVLinkTelemetryPort(void)
@@ -324,12 +363,14 @@ void configureMAVLinkTelemetryPort(void)
static void configureMAVLinkStreamRates(void)
{
- mavRates[MAV_DATA_STREAM_EXTENDED_STATUS] = telemetryConfig()->mavlink.extended_status_rate;
- mavRates[MAV_DATA_STREAM_RC_CHANNELS] = telemetryConfig()->mavlink.rc_channels_rate;
- mavRates[MAV_DATA_STREAM_POSITION] = telemetryConfig()->mavlink.position_rate;
- mavRates[MAV_DATA_STREAM_EXTRA1] = telemetryConfig()->mavlink.extra1_rate;
- mavRates[MAV_DATA_STREAM_EXTRA2] = telemetryConfig()->mavlink.extra2_rate;
- mavRates[MAV_DATA_STREAM_EXTRA3] = telemetryConfig()->mavlink.extra3_rate;
+ mavlinkSetStreamRate(MAV_DATA_STREAM_EXTENDED_STATUS, telemetryConfig()->mavlink.extended_status_rate);
+ mavlinkSetStreamRate(MAV_DATA_STREAM_RC_CHANNELS, telemetryConfig()->mavlink.rc_channels_rate);
+ mavlinkSetStreamRate(MAV_DATA_STREAM_POSITION, telemetryConfig()->mavlink.position_rate);
+ mavlinkSetStreamRate(MAV_DATA_STREAM_EXTRA1, telemetryConfig()->mavlink.extra1_rate);
+ mavlinkSetStreamRate(MAV_DATA_STREAM_EXTRA2, telemetryConfig()->mavlink.extra2_rate);
+ mavlinkSetStreamRate(MAV_DATA_STREAM_EXTRA3, telemetryConfig()->mavlink.extra3_rate);
+ mavlinkSetStreamRate(MAV_DATA_STREAM_EXTENDED_SYS_STATE, telemetryConfig()->mavlink.extra3_rate);
+ memcpy(mavRatesConfigured, mavRates, sizeof(mavRates));
}
void checkMAVLinkTelemetryState(void)
@@ -365,6 +406,178 @@ static void mavlinkSendMessage(void)
}
}
+static void __attribute__((unused)) mavlinkSendAutopilotVersion(void)
+{
+ if (telemetryConfig()->mavlink.version == 1) return;
+
+ // will need to add real capabilities according to ifdef: https://mavlink.io/en/messages/common.html#MAV_PROTOCOL_CAPABILITY
+ uint64_t capabilities = 0;
+ capabilities |= MAV_PROTOCOL_CAPABILITY_MAVLINK2;
+ capabilities |= MAV_PROTOCOL_CAPABILITY_MISSION_INT; // i assume
+ capabilities |= MAV_PROTOCOL_CAPABILITY_COMMAND_INT;
+ // MAV_PROTOCOL_CAPABILITY_MISSION_FENCE geofence
+ capabilities |= MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_GLOBAL_INT;
+
+ // Bare minimum: caps + IDs. Everything else 0 is fine.
+ mavlink_msg_autopilot_version_pack(
+ mavSystemId,
+ mavComponentId,
+ &mavSendMsg,
+ capabilities, // capabilities
+ 0, // flight_sw_version
+ 0, // middleware_sw_version
+ 0, // os_sw_version
+ 0, // board_version
+ 0ULL, // flight_custom_version
+ 0ULL, // middleware_custom_version
+ 0ULL, // os_custom_version
+ 0ULL, // vendor_id
+ 0ULL, // product_id
+ (uint64_t)mavSystemId, // uid (any stable nonzero is fine)
+ 0ULL // uid2
+ );
+ mavlinkSendMessage();
+}
+
+static void mavlinkSendProtocolVersion(void)
+{
+ if (telemetryConfig()->mavlink.version == 1) return;
+
+ uint8_t specHash[8] = {0};
+ uint8_t libHash[8] = {0};
+
+ mavlink_msg_protocol_version_pack(
+ mavSystemId,
+ mavComponentId,
+ &mavSendMsg,
+ MAVLINK_VERSION,
+ MAVLINK_VERSION,
+ MAVLINK_VERSION,
+ specHash,
+ libHash);
+
+ mavlinkSendMessage();
+}
+
+static bool mavlinkFrameIsSupported(uint8_t frame, mavFrameSupportMask_e allowedMask)
+{
+ switch (frame) {
+ case MAV_FRAME_GLOBAL:
+ return allowedMask & MAV_FRAME_SUPPORTED_GLOBAL;
+ case MAV_FRAME_GLOBAL_INT:
+ return allowedMask & MAV_FRAME_SUPPORTED_GLOBAL_INT;
+ case MAV_FRAME_GLOBAL_RELATIVE_ALT:
+ return allowedMask & MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT;
+ case MAV_FRAME_GLOBAL_RELATIVE_ALT_INT:
+ return allowedMask & MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT_INT;
+ default:
+ return false;
+ }
+}
+
+typedef struct {
+ uint8_t customMode;
+ const char *name;
+} mavlinkModeDescriptor_t;
+
+static const mavlinkModeDescriptor_t planeModes[] = {
+ { PLANE_MODE_MANUAL, "MANUAL" },
+ { PLANE_MODE_ACRO, "ACRO" },
+ { PLANE_MODE_STABILIZE, "STABILIZE" },
+ { PLANE_MODE_FLY_BY_WIRE_A,"FBWA" },
+ { PLANE_MODE_FLY_BY_WIRE_B,"FBWB" },
+ { PLANE_MODE_CRUISE, "CRUISE" },
+ { PLANE_MODE_AUTO, "AUTO" },
+ { PLANE_MODE_RTL, "RTL" },
+ { PLANE_MODE_LOITER, "LOITER" },
+ { PLANE_MODE_TAKEOFF, "TAKEOFF" },
+ { PLANE_MODE_GUIDED, "GUIDED" },
+};
+
+static const mavlinkModeDescriptor_t copterModes[] = {
+ { COPTER_MODE_ACRO, "ACRO" },
+ { COPTER_MODE_STABILIZE, "STABILIZE" },
+ { COPTER_MODE_ALT_HOLD, "ALT_HOLD" },
+ { COPTER_MODE_POSHOLD, "POSHOLD" },
+ { COPTER_MODE_LOITER, "LOITER" },
+ { COPTER_MODE_AUTO, "AUTO" },
+ { COPTER_MODE_GUIDED, "GUIDED" },
+ { COPTER_MODE_RTL, "RTL" },
+ { COPTER_MODE_LAND, "LAND" },
+ { COPTER_MODE_BRAKE, "BRAKE" },
+ { COPTER_MODE_THROW, "THROW" },
+ { COPTER_MODE_SMART_RTL, "SMART_RTL" },
+ { COPTER_MODE_DRIFT, "DRIFT" },
+};
+
+static void mavlinkSendAvailableModes(const mavlinkModeDescriptor_t *modes, uint8_t count, uint8_t currentCustom)
+{
+ for (uint8_t i = 0; i < count; i++) {
+ const uint8_t modeIndex = i + 1;
+ const uint8_t stdMode = MAV_STANDARD_MODE_NON_STANDARD;
+ const uint32_t properties = 0;
+
+ mavlink_msg_available_modes_pack(
+ mavSystemId,
+ mavComponentId,
+ &mavSendMsg,
+ count,
+ modeIndex,
+ stdMode,
+ modes[i].customMode,
+ properties,
+ modes[i].name);
+
+ mavlinkSendMessage();
+
+ if (modes[i].customMode == currentCustom) {
+ mavlink_msg_current_mode_pack(
+ mavSystemId,
+ mavComponentId,
+ &mavSendMsg,
+ stdMode,
+ currentCustom,
+ currentCustom);
+ mavlinkSendMessage();
+ }
+ }
+}
+
+static void mavlinkSendExtendedSysState(void)
+{
+ uint8_t vtolState = MAV_VTOL_STATE_UNDEFINED;
+ uint8_t landedState;
+
+ switch (NAV_Status.state) {
+ case MW_NAV_STATE_LAND_START:
+ case MW_NAV_STATE_LAND_IN_PROGRESS:
+ case MW_NAV_STATE_LAND_SETTLE:
+ case MW_NAV_STATE_LAND_START_DESCENT:
+ case MW_NAV_STATE_EMERGENCY_LANDING:
+ landedState = MAV_LANDED_STATE_LANDING;
+ break;
+ case MW_NAV_STATE_LANDED:
+ landedState = MAV_LANDED_STATE_ON_GROUND;
+ break;
+ default:
+ if (!ARMING_FLAG(ARMED) || STATE(LANDING_DETECTED)) {
+ landedState = MAV_LANDED_STATE_ON_GROUND;
+ } else {
+ landedState = MAV_LANDED_STATE_IN_AIR;
+ }
+ break;
+ }
+
+ mavlink_msg_extended_sys_state_pack(
+ mavSystemId,
+ mavComponentId,
+ &mavSendMsg,
+ vtolState,
+ landedState);
+
+ mavlinkSendMessage();
+}
+
void mavlinkSendSystemStatus(void)
{
// Receiver is assumed to be always present
@@ -590,6 +803,29 @@ void mavlinkSendRCChannelsAndRSSI(void)
}
#if defined(USE_GPS)
+static void mavlinkSendHomePosition(void)
+{
+ float q[4] = { 1.0f, 0.0f, 0.0f, 0.0f };
+
+ mavlink_msg_home_position_pack(
+ mavSystemId,
+ mavComponentId,
+ &mavSendMsg,
+ GPS_home.lat,
+ GPS_home.lon,
+ GPS_home.alt * 10,
+ 0.0f,
+ 0.0f,
+ 0.0f,
+ q,
+ 0.0f,
+ 0.0f,
+ 0.0f,
+ ((uint64_t) millis()) * 1000);
+
+ mavlinkSendMessage();
+}
+
void mavlinkSendPosition(timeUs_t currentTimeUs)
{
uint8_t gpsFixType = 0;
@@ -783,7 +1019,7 @@ void mavlinkSendHUDAndHeartbeat(void)
flightModeForTelemetry_e flm = getFlightModeForTelemetry();
uint8_t mavCustomMode;
- if (STATE(FIXED_WING_LEGACY)) {
+ if (STATE(FIXED_WING_LEGACY) || mixerConfig()->platformType == PLATFORM_AIRPLANE) {
mavCustomMode = (uint8_t)inavToArduPlaneMap(flm);
}
else {
@@ -904,6 +1140,7 @@ void mavlinkSendBatteryTemperatureStatusText(void)
mavlinkSendMessage();
+ mavlinkSendExtendedSysState();
// FIXME - Status text is limited to boards with USE_OSD
#ifdef USE_OSD
@@ -955,6 +1192,10 @@ void processMAVLinkTelemetry(timeUs_t currentTimeUs)
mavlinkSendHUDAndHeartbeat();
}
+ if (mavlinkStreamTrigger(MAV_DATA_STREAM_EXTENDED_SYS_STATE)) {
+ mavlinkSendExtendedSysState();
+ }
+
if (mavlinkStreamTrigger(MAV_DATA_STREAM_EXTRA3)) {
mavlinkSendBatteryTemperatureStatusText();
}
@@ -1157,77 +1398,321 @@ static bool handleIncoming_MISSION_REQUEST(void)
return false;
}
+static bool mavlinkMessageToStream(uint16_t messageId, uint8_t *streamNum)
+{
+ switch (messageId) {
+ case MAVLINK_MSG_ID_HEARTBEAT:
+ case MAVLINK_MSG_ID_VFR_HUD:
+ *streamNum = MAV_DATA_STREAM_EXTRA2;
+ return true;
+ case MAVLINK_MSG_ID_ATTITUDE:
+ *streamNum = MAV_DATA_STREAM_EXTRA1;
+ return true;
+ case MAVLINK_MSG_ID_SYS_STATUS:
+ *streamNum = MAV_DATA_STREAM_EXTENDED_STATUS;
+ return true;
+ case MAVLINK_MSG_ID_EXTENDED_SYS_STATE:
+ *streamNum = MAV_DATA_STREAM_EXTENDED_SYS_STATE;
+ return true;
+ case MAVLINK_MSG_ID_RC_CHANNELS:
+ case MAVLINK_MSG_ID_RC_CHANNELS_RAW:
+ case MAVLINK_MSG_ID_RC_CHANNELS_SCALED:
+ *streamNum = MAV_DATA_STREAM_RC_CHANNELS;
+ return true;
+ case MAVLINK_MSG_ID_GPS_RAW_INT:
+ case MAVLINK_MSG_ID_GLOBAL_POSITION_INT:
+ case MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN:
+ *streamNum = MAV_DATA_STREAM_POSITION;
+ return true;
+ case MAVLINK_MSG_ID_BATTERY_STATUS:
+ case MAVLINK_MSG_ID_SCALED_PRESSURE:
+ *streamNum = MAV_DATA_STREAM_EXTRA3;
+ return true;
+ default:
+ return false;
+ }
+}
-static bool handleIncoming_COMMAND_INT(void)
+
+static void mavlinkSendCommandAck(uint16_t command, MAV_RESULT result, uint8_t ackTargetSystem, uint8_t ackTargetComponent)
{
- mavlink_command_int_t msg;
- mavlink_msg_command_int_decode(&mavRecvMsg, &msg);
+ mavlink_msg_command_ack_pack(mavSystemId, mavComponentId, &mavSendMsg,
+ command,
+ result,
+ 0,
+ 0,
+ ackTargetSystem,
+ ackTargetComponent);
+ mavlinkSendMessage();
+}
- if (msg.target_system == mavSystemId) {
+static bool handleIncoming_COMMAND(uint8_t targetSystem, uint8_t ackTargetSystem, uint8_t ackTargetComponent, uint16_t command, uint8_t frame, float param1, float param2, float param3, float param4, float latitudeDeg, float longitudeDeg, float altitudeMeters)
+{
+ if (targetSystem != mavSystemId) {
+ return false;
+ }
+ UNUSED(param3);
+
+ switch (command) {
+ case MAV_CMD_DO_REPOSITION:
+ if (!mavlinkFrameIsSupported(frame,
+ MAV_FRAME_SUPPORTED_GLOBAL |
+ MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT |
+ MAV_FRAME_SUPPORTED_GLOBAL_INT |
+ MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT_INT)) {
+ mavlinkSendCommandAck(command, MAV_RESULT_UNSUPPORTED, ackTargetSystem, ackTargetComponent);
+ return true;
+ }
- if (msg.command == MAV_CMD_DO_REPOSITION) {
-
- if (!(msg.frame == MAV_FRAME_GLOBAL)) { //|| msg.frame == MAV_FRAME_GLOBAL_RELATIVE_ALT || msg.frame == MAV_FRAME_GLOBAL_TERRAIN_ALT)) {
-
- mavlink_msg_command_ack_pack(mavSystemId, mavComponentId, &mavSendMsg,
- msg.command,
- MAV_RESULT_UNSUPPORTED,
- 0, // progress
- 0, // result_param2
- mavRecvMsg.sysid,
- mavRecvMsg.compid);
- mavlinkSendMessage();
- return true;
- }
+ if (isnan(latitudeDeg) || isnan(longitudeDeg)) {
+ mavlinkSendCommandAck(command, MAV_RESULT_FAILED, ackTargetSystem, ackTargetComponent);
+ return true;
+ }
if (isGCSValid()) {
navWaypoint_t wp;
wp.action = NAV_WP_ACTION_WAYPOINT;
- wp.lat = (int32_t)msg.x;
- wp.lon = (int32_t)msg.y;
- wp.alt = msg.z * 100.0f;
- if (!isnan(msg.param4) && msg.param4 >= 0.0f && msg.param4 < 360.0f) {
- wp.p1 = (int16_t)msg.param4;
+ wp.lat = (int32_t)(latitudeDeg * 1e7f);
+ wp.lon = (int32_t)(longitudeDeg * 1e7f);
+ wp.alt = (int32_t)(altitudeMeters * 100.0f);
+ if (!isnan(param4) && param4 >= 0.0f && param4 < 360.0f) {
+ wp.p1 = (int16_t)param4;
} else {
wp.p1 = 0;
}
- wp.p2 = 0; // TODO: Alt modes
+ wp.p2 = 0;
wp.p3 = 0;
wp.flag = 0;
setWaypoint(255, &wp);
- mavlink_msg_command_ack_pack(mavSystemId, mavComponentId, &mavSendMsg,
- msg.command,
- MAV_RESULT_ACCEPTED,
- 0, // progress
- 0, // result_param2
- mavRecvMsg.sysid,
- mavRecvMsg.compid);
- mavlinkSendMessage();
+ mavlinkSendCommandAck(command, MAV_RESULT_ACCEPTED, ackTargetSystem, ackTargetComponent);
} else {
- mavlink_msg_command_ack_pack(mavSystemId, mavComponentId, &mavSendMsg,
- msg.command,
- MAV_RESULT_DENIED,
- 0,
- 0,
- mavRecvMsg.sysid,
- mavRecvMsg.compid);
- mavlinkSendMessage();
+ mavlinkSendCommandAck(command, MAV_RESULT_DENIED, ackTargetSystem, ackTargetComponent);
+ }
+ return true;
+ case MAV_CMD_SET_MESSAGE_INTERVAL:
+ {
+ uint8_t stream;
+ MAV_RESULT result = MAV_RESULT_UNSUPPORTED;
+
+ if (mavlinkMessageToStream((uint16_t)param1, &stream)) {
+ if (param2 == 0.0f) {
+ mavlinkSetStreamRate(stream, mavRatesConfigured[stream]);
+ result = MAV_RESULT_ACCEPTED;
+ } else if (param2 < 0.0f) {
+ mavlinkSetStreamRate(stream, 0);
+ result = MAV_RESULT_ACCEPTED;
+ } else {
+ uint32_t intervalUs = (uint32_t)param2;
+ if (intervalUs > 0) {
+ uint32_t rate = 1000000UL / intervalUs;
+ if (rate > 0) {
+ if (rate > TELEMETRY_MAVLINK_MAXRATE) {
+ rate = TELEMETRY_MAVLINK_MAXRATE;
+ }
+ mavlinkSetStreamRate(stream, rate);
+ result = MAV_RESULT_ACCEPTED;
+ }
+ }
+ }
+ }
+
+ mavlinkSendCommandAck(command, result, ackTargetSystem, ackTargetComponent);
+ return true;
}
- } else {
- mavlink_msg_command_ack_pack(mavSystemId, mavComponentId, &mavSendMsg,
- msg.command,
- MAV_RESULT_UNSUPPORTED,
- 0,
- 0,
- mavRecvMsg.sysid,
- mavRecvMsg.compid);
+ case MAV_CMD_GET_MESSAGE_INTERVAL:
+ {
+ uint8_t stream;
+ if (!mavlinkMessageToStream((uint16_t)param1, &stream)) {
+ mavlinkSendCommandAck(command, MAV_RESULT_UNSUPPORTED, ackTargetSystem, ackTargetComponent);
+ return true;
+ }
+
+ mavlink_msg_message_interval_pack(
+ mavSystemId,
+ mavComponentId,
+ &mavSendMsg,
+ (uint16_t)param1,
+ mavlinkStreamIntervalUs(stream));
mavlinkSendMessage();
- }
+
+ mavlinkSendCommandAck(command, MAV_RESULT_ACCEPTED, ackTargetSystem, ackTargetComponent);
+ return true;
+ }
+ case MAV_CMD_REQUEST_PROTOCOL_VERSION:
+ mavlinkSendProtocolVersion();
+ mavlinkSendCommandAck(command, MAV_RESULT_ACCEPTED, ackTargetSystem, ackTargetComponent);
+ return true;
+ case MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES:
+ mavlinkSendAutopilotVersion();
+ mavlinkSendCommandAck(command, MAV_RESULT_ACCEPTED, ackTargetSystem, ackTargetComponent);
+ return true;
+ case MAV_CMD_REQUEST_MESSAGE:
+ {
+ bool sent = false;
+ uint16_t messageId = (uint16_t)param1;
+
+ switch (messageId) {
+ case MAVLINK_MSG_ID_HEARTBEAT:
+ mavlinkSendHUDAndHeartbeat();
+ sent = true;
+ break;
+ case MAVLINK_MSG_ID_AUTOPILOT_VERSION:
+ mavlinkSendAutopilotVersion();
+ sent = true;
+ break;
+ case MAVLINK_MSG_ID_PROTOCOL_VERSION:
+ mavlinkSendProtocolVersion();
+ sent = true;
+ break;
+ case MAVLINK_MSG_ID_SYS_STATUS:
+ mavlinkSendSystemStatus();
+ sent = true;
+ break;
+ case MAVLINK_MSG_ID_ATTITUDE:
+ mavlinkSendAttitude();
+ sent = true;
+ break;
+ case MAVLINK_MSG_ID_VFR_HUD:
+ mavlinkSendHUDAndHeartbeat();
+ sent = true;
+ break;
+ case MAVLINK_MSG_ID_AVAILABLE_MODES:
+ {
+ flightModeForTelemetry_e flm = getFlightModeForTelemetry();
+ uint8_t currentCustom;
+ if (mixerConfig()->platformType == PLATFORM_AIRPLANE || STATE(FIXED_WING_LEGACY)) {
+ currentCustom = (uint8_t)inavToArduPlaneMap(flm);
+ mavlinkSendAvailableModes(planeModes, ARRAYLEN(planeModes), currentCustom);
+ } else {
+ currentCustom = (uint8_t)inavToArduCopterMap(flm);
+ mavlinkSendAvailableModes(copterModes, ARRAYLEN(copterModes), currentCustom);
+ }
+ sent = true;
+ }
+ break;
+ case MAVLINK_MSG_ID_CURRENT_MODE:
+ {
+ flightModeForTelemetry_e flm = getFlightModeForTelemetry();
+ uint8_t currentCustom;
+ if (mixerConfig()->platformType == PLATFORM_AIRPLANE || STATE(FIXED_WING_LEGACY)) {
+ currentCustom = (uint8_t)inavToArduPlaneMap(flm);
+ } else {
+ currentCustom = (uint8_t)inavToArduCopterMap(flm);
+ }
+ mavlink_msg_current_mode_pack(
+ mavSystemId,
+ mavComponentId,
+ &mavSendMsg,
+ MAV_STANDARD_MODE_NON_STANDARD,
+ currentCustom,
+ currentCustom);
+ mavlinkSendMessage();
+ sent = true;
+ }
+ break;
+ case MAVLINK_MSG_ID_EXTENDED_SYS_STATE:
+ mavlinkSendExtendedSysState();
+ sent = true;
+ break;
+ case MAVLINK_MSG_ID_RC_CHANNELS:
+ case MAVLINK_MSG_ID_RC_CHANNELS_RAW:
+ case MAVLINK_MSG_ID_RC_CHANNELS_SCALED:
+ mavlinkSendRCChannelsAndRSSI();
+ sent = true;
+ break;
+ case MAVLINK_MSG_ID_GPS_RAW_INT:
+ case MAVLINK_MSG_ID_GLOBAL_POSITION_INT:
+ case MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN:
+ #ifdef USE_GPS
+ mavlinkSendPosition(micros());
+ sent = true;
+ #endif
+ break;
+ case MAVLINK_MSG_ID_BATTERY_STATUS:
+ case MAVLINK_MSG_ID_SCALED_PRESSURE:
+ mavlinkSendBatteryTemperatureStatusText();
+ sent = true;
+ break;
+ case MAVLINK_MSG_ID_HOME_POSITION:
+ #ifdef USE_GPS
+ if (STATE(GPS_FIX_HOME)) {
+ mavlinkSendHomePosition();
+ sent = true;
+ }
+ #endif
+ break;
+ default:
+ break;
+ }
+
+ mavlinkSendCommandAck(command, sent ? MAV_RESULT_ACCEPTED : MAV_RESULT_UNSUPPORTED, ackTargetSystem, ackTargetComponent);
+ return true;
+ }
+#ifdef USE_GPS
+ case MAV_CMD_GET_HOME_POSITION:
+ if (STATE(GPS_FIX_HOME)) {
+ mavlinkSendHomePosition();
+ mavlinkSendCommandAck(command, MAV_RESULT_ACCEPTED, ackTargetSystem, ackTargetComponent);
+ } else {
+ mavlinkSendCommandAck(command, MAV_RESULT_FAILED, ackTargetSystem, ackTargetComponent);
+ }
+ return true;
+#endif
+ default:
+ mavlinkSendCommandAck(command, MAV_RESULT_UNSUPPORTED, ackTargetSystem, ackTargetComponent);
+ return true;
+ }
+}
+
+static bool handleIncoming_COMMAND_INT(void)
+{
+ mavlink_command_int_t msg;
+ mavlink_msg_command_int_decode(&mavRecvMsg, &msg);
+
+ return handleIncoming_COMMAND(msg.target_system, mavRecvMsg.sysid, mavRecvMsg.compid, msg.command, msg.frame, msg.param1, msg.param2, msg.param3, msg.param4, (float)msg.x / 1e7f, (float)msg.y / 1e7f, msg.z);
+}
+
+static bool handleIncoming_COMMAND_LONG(void)
+{
+ mavlink_command_long_t msg;
+ mavlink_msg_command_long_decode(&mavRecvMsg, &msg);
+
+ return handleIncoming_COMMAND(msg.target_system, mavRecvMsg.sysid, mavRecvMsg.compid, msg.command, msg.confirmation, msg.param1, msg.param2, msg.param3, msg.param4, msg.param5, msg.param6, msg.param7);
+}
+
+static bool handleIncoming_SET_POSITION_TARGET_GLOBAL_INT(void)
+{
+ mavlink_set_position_target_global_int_t msg;
+ mavlink_msg_set_position_target_global_int_decode(&mavRecvMsg, &msg);
+
+ if (msg.target_system != mavSystemId) {
+ return false;
+ }
+
+ uint8_t frame = msg.coordinate_frame;
+ if (!mavlinkFrameIsSupported(frame,
+ MAV_FRAME_SUPPORTED_GLOBAL_INT |
+ MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT_INT)) {
return true;
}
- return false;
+
+ if (isGCSValid()) {
+ navWaypoint_t wp;
+ wp.action = NAV_WP_ACTION_WAYPOINT;
+ wp.lat = msg.lat_int;
+ wp.lon = msg.lon_int;
+ wp.alt = (int32_t)(msg.alt * 100.0f);
+ wp.p1 = 0;
+ wp.p2 = 0;
+ wp.p3 = 0;
+ wp.flag = 0;
+
+ setWaypoint(255, &wp);
+ }
+
+ return true;
}
@@ -1352,10 +1837,8 @@ static bool processMAVLinkIncomingTelemetry(void)
case MAVLINK_MSG_ID_MISSION_REQUEST_LIST:
return handleIncoming_MISSION_REQUEST_LIST();
- //TODO:
- //case MAVLINK_MSG_ID_COMMAND_LONG; //up to 7 float parameters
- //return handleIncoming_COMMAND_LONG();
-
+ case MAVLINK_MSG_ID_COMMAND_LONG:
+ return handleIncoming_COMMAND_LONG();
case MAVLINK_MSG_ID_COMMAND_INT: //7 parameters: parameters 1-4, 7 are floats, and parameters 5,6 are scaled integers
return handleIncoming_COMMAND_INT();
case MAVLINK_MSG_ID_MISSION_REQUEST:
@@ -1364,6 +1847,8 @@ static bool processMAVLinkIncomingTelemetry(void)
handleIncoming_RC_CHANNELS_OVERRIDE();
// Don't set that we handled a message, otherwise RC channel packets will block telemetry messages
return false;
+ case MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT:
+ return handleIncoming_SET_POSITION_TARGET_GLOBAL_INT();
#ifdef USE_ADSB
case MAVLINK_MSG_ID_ADSB_VEHICLE:
return handleIncoming_ADSB_VEHICLE();
From b89b8e1376175d91dd7bcab3c872f211acd50c7e Mon Sep 17 00:00:00 2001
From: frogmane <7685285+xznhj8129@users.noreply.github.com>
Date: Sat, 13 Dec 2025 13:50:31 -0500
Subject: [PATCH 02/46] compatibility + messages
---
dm.txt | 0
src/main/telemetry/mavlink.c | 377 ++++++++++++++++++++++-------------
2 files changed, 241 insertions(+), 136 deletions(-)
create mode 100644 dm.txt
diff --git a/dm.txt b/dm.txt
new file mode 100644
index 00000000000..e69de29bb2d
diff --git a/src/main/telemetry/mavlink.c b/src/main/telemetry/mavlink.c
index 50d59ec5909..fddcff582c7 100644
--- a/src/main/telemetry/mavlink.c
+++ b/src/main/telemetry/mavlink.c
@@ -31,6 +31,7 @@
#include "build/build_config.h"
#include "build/debug.h"
+#include "build/version.h"
#include "common/axis.h"
#include "common/color.h"
@@ -98,6 +99,9 @@
#define TELEMETRY_MAVLINK_MAXRATE 50
#define TELEMETRY_MAVLINK_DELAY ((1000 * 1000) / TELEMETRY_MAVLINK_MAXRATE)
#define MAV_DATA_STREAM_EXTENDED_SYS_STATE (MAV_DATA_STREAM_EXTRA3 + 1)
+#define ARDUPILOT_VERSION_MAJOR 4
+#define ARDUPILOT_VERSION_MINOR 6
+#define ARDUPILOT_VERSION_PATCH 3
typedef enum {
MAV_FRAME_SUPPORTED_NONE = 0,
@@ -210,6 +214,27 @@ static uint8_t mavSystemId = 1;
static uint8_t mavAutopilotType;
static uint8_t mavComponentId = MAV_COMP_ID_AUTOPILOT1;
+static uint8_t mavlinkGetVehicleType(void)
+{
+ switch (mixerConfig()->platformType)
+ {
+ case PLATFORM_MULTIROTOR:
+ return MAV_TYPE_QUADROTOR;
+ case PLATFORM_TRICOPTER:
+ return MAV_TYPE_TRICOPTER;
+ case PLATFORM_AIRPLANE:
+ return MAV_TYPE_FIXED_WING;
+ case PLATFORM_ROVER:
+ return MAV_TYPE_GROUND_ROVER;
+ case PLATFORM_BOAT:
+ return MAV_TYPE_SURFACE_BOAT;
+ case PLATFORM_HELICOPTER:
+ return MAV_TYPE_HELICOPTER;
+ default:
+ return MAV_TYPE_GENERIC;
+ }
+}
+
static APM_COPTER_MODE inavToArduCopterMap(flightModeForTelemetry_e flightMode)
{
switch (flightMode)
@@ -406,16 +431,16 @@ static void mavlinkSendMessage(void)
}
}
-static void __attribute__((unused)) mavlinkSendAutopilotVersion(void)
+static void mavlinkSendAutopilotVersion(void)
{
if (telemetryConfig()->mavlink.version == 1) return;
- // will need to add real capabilities according to ifdef: https://mavlink.io/en/messages/common.html#MAV_PROTOCOL_CAPABILITY
+ // Capabilities aligned with what we actually support.
uint64_t capabilities = 0;
capabilities |= MAV_PROTOCOL_CAPABILITY_MAVLINK2;
- capabilities |= MAV_PROTOCOL_CAPABILITY_MISSION_INT; // i assume
+ capabilities |= MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT;
+ capabilities |= MAV_PROTOCOL_CAPABILITY_MISSION_INT;
capabilities |= MAV_PROTOCOL_CAPABILITY_COMMAND_INT;
- // MAV_PROTOCOL_CAPABILITY_MISSION_FENCE geofence
capabilities |= MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_GLOBAL_INT;
// Bare minimum: caps + IDs. Everything else 0 is fine.
@@ -882,8 +907,8 @@ void mavlinkSendPosition(timeUs_t currentTimeUs)
// Global position
mavlink_msg_global_position_int_pack(mavSystemId, mavComponentId, &mavSendMsg,
- // time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
- currentTimeUs,
+ // time_boot_ms Timestamp (milliseconds since system boot)
+ currentTimeUs / 1000,
// lat Latitude in 1E7 degrees
gpsSol.llh.lat,
// lon Longitude in 1E7 degrees
@@ -990,31 +1015,7 @@ void mavlinkSendHUDAndHeartbeat(void)
if (ARMING_FLAG(ARMED))
mavModes |= MAV_MODE_FLAG_SAFETY_ARMED;
- uint8_t mavSystemType;
- switch (mixerConfig()->platformType)
- {
- case PLATFORM_MULTIROTOR:
- mavSystemType = MAV_TYPE_QUADROTOR;
- break;
- case PLATFORM_TRICOPTER:
- mavSystemType = MAV_TYPE_TRICOPTER;
- break;
- case PLATFORM_AIRPLANE:
- mavSystemType = MAV_TYPE_FIXED_WING;
- break;
- case PLATFORM_ROVER:
- mavSystemType = MAV_TYPE_GROUND_ROVER;
- break;
- case PLATFORM_BOAT:
- mavSystemType = MAV_TYPE_SURFACE_BOAT;
- break;
- case PLATFORM_HELICOPTER:
- mavSystemType = MAV_TYPE_HELICOPTER;
- break;
- default:
- mavSystemType = MAV_TYPE_GENERIC;
- break;
- }
+ uint8_t mavSystemType = mavlinkGetVehicleType();
flightModeForTelemetry_e flm = getFlightModeForTelemetry();
uint8_t mavCustomMode;
@@ -1222,6 +1223,67 @@ static bool handleIncoming_MISSION_CLEAR_ALL(void)
static int incomingMissionWpCount = 0;
static int incomingMissionWpSequence = 0;
+static bool mavlinkHandleMissionItemCommon(bool useIntMessages, uint8_t frame, uint16_t command, uint8_t autocontinue, uint16_t seq, int32_t lat, int32_t lon, float altMeters)
+{
+ if ((autocontinue == 0) || (command != MAV_CMD_NAV_WAYPOINT && command != MAV_CMD_NAV_RETURN_TO_LAUNCH)) {
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, MAV_MISSION_UNSUPPORTED, MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
+ return true;
+ }
+
+ if (!mavlinkFrameIsSupported(frame,
+ MAV_FRAME_SUPPORTED_GLOBAL |
+ MAV_FRAME_SUPPORTED_GLOBAL_INT |
+ MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT |
+ MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT_INT) &&
+ !(frame == MAV_FRAME_MISSION && command == MAV_CMD_NAV_RETURN_TO_LAUNCH)) {
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, MAV_MISSION_UNSUPPORTED_FRAME, MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
+ return true;
+ }
+
+ if (seq == incomingMissionWpSequence) {
+ incomingMissionWpSequence++;
+
+ navWaypoint_t wp;
+ wp.action = (command == MAV_CMD_NAV_RETURN_TO_LAUNCH) ? NAV_WP_ACTION_RTH : NAV_WP_ACTION_WAYPOINT;
+ wp.lat = lat;
+ wp.lon = lon;
+ wp.alt = (int32_t)(altMeters * 100.0f);
+ wp.p1 = 0;
+ wp.p2 = 0;
+ wp.p3 = 0;
+ wp.flag = (incomingMissionWpSequence >= incomingMissionWpCount) ? NAV_WP_FLAG_LAST : 0;
+
+ setWaypoint(incomingMissionWpSequence, &wp);
+
+ if (incomingMissionWpSequence >= incomingMissionWpCount) {
+ if (isWaypointListValid()) {
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, MAV_MISSION_ACCEPTED, MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
+ }
+ else {
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, MAV_MISSION_INVALID, MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
+ }
+ }
+ else {
+ if (useIntMessages) {
+ mavlink_msg_mission_request_int_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, incomingMissionWpSequence, MAV_MISSION_TYPE_MISSION);
+ } else {
+ mavlink_msg_mission_request_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, incomingMissionWpSequence, MAV_MISSION_TYPE_MISSION);
+ }
+ mavlinkSendMessage();
+ }
+ }
+ else {
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, MAV_MISSION_INVALID_SEQUENCE, MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
+ }
+
+ return true;
+}
+
static bool handleIncoming_MISSION_COUNT(void)
{
mavlink_mission_count_t msg;
@@ -1232,7 +1294,7 @@ static bool handleIncoming_MISSION_COUNT(void)
if (msg.count <= NAV_MAX_WAYPOINTS) {
incomingMissionWpCount = msg.count; // We need to know how many items to request
incomingMissionWpSequence = 0;
- mavlink_msg_mission_request_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, incomingMissionWpSequence, MAV_MISSION_TYPE_MISSION);
+ mavlink_msg_mission_request_int_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, incomingMissionWpSequence, MAV_MISSION_TYPE_MISSION);
mavlinkSendMessage();
return true;
}
@@ -1256,94 +1318,44 @@ static bool handleIncoming_MISSION_ITEM(void)
mavlink_mission_item_t msg;
mavlink_msg_mission_item_decode(&mavRecvMsg, &msg);
- // Check if this message is for us
- if (msg.target_system == mavSystemId) {
- // Check supported values first
- if (ARMING_FLAG(ARMED)) {
- // Legacy Mission Planner BS for GUIDED
- if (isGCSValid() && (msg.command == MAV_CMD_NAV_WAYPOINT) && (msg.current == 2)) {
- if (!(msg.frame == MAV_FRAME_GLOBAL)) {
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg,
- mavRecvMsg.sysid, mavRecvMsg.compid,
- MAV_MISSION_UNSUPPORTED_FRAME, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
- return true;
- }
-
- navWaypoint_t wp;
- wp.action = NAV_WP_ACTION_WAYPOINT;
- wp.lat = (int32_t)(msg.x * 1e7f);
- wp.lon = (int32_t)(msg.y * 1e7f);
- wp.alt = (int32_t)(msg.z * 100.0f);
- wp.p1 = 0;
- wp.p2 = 0;
- wp.p3 = 0;
- setWaypoint(255, &wp);
+ if (msg.target_system != mavSystemId) {
+ return false;
+ }
+ if (ARMING_FLAG(ARMED)) {
+ // Legacy Mission Planner GUIDED
+ if (isGCSValid() && (msg.command == MAV_CMD_NAV_WAYPOINT) && (msg.current == 2)) {
+ if (!(msg.frame == MAV_FRAME_GLOBAL)) {
mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg,
mavRecvMsg.sysid, mavRecvMsg.compid,
- MAV_MISSION_ACCEPTED, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
- return true;
- } else {
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, MAV_MISSION_ERROR, MAV_MISSION_TYPE_MISSION, 0);
+ MAV_MISSION_UNSUPPORTED_FRAME, MAV_MISSION_TYPE_MISSION, 0);
mavlinkSendMessage();
return true;
}
- }
-
- if ((msg.autocontinue == 0) || (msg.command != MAV_CMD_NAV_WAYPOINT && msg.command != MAV_CMD_NAV_RETURN_TO_LAUNCH)) {
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, MAV_MISSION_UNSUPPORTED, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
- return true;
- }
-
- if ((msg.frame != MAV_FRAME_GLOBAL_RELATIVE_ALT) && !(msg.frame == MAV_FRAME_MISSION && msg.command == MAV_CMD_NAV_RETURN_TO_LAUNCH)) {
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, MAV_MISSION_UNSUPPORTED_FRAME, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
- return true;
- }
-
- if (msg.seq == incomingMissionWpSequence) {
- incomingMissionWpSequence++;
navWaypoint_t wp;
- wp.action = (msg.command == MAV_CMD_NAV_RETURN_TO_LAUNCH) ? NAV_WP_ACTION_RTH : NAV_WP_ACTION_WAYPOINT;
+ wp.action = NAV_WP_ACTION_WAYPOINT;
wp.lat = (int32_t)(msg.x * 1e7f);
wp.lon = (int32_t)(msg.y * 1e7f);
- wp.alt = msg.z * 100.0f;
+ wp.alt = (int32_t)(msg.z * 100.0f);
wp.p1 = 0;
wp.p2 = 0;
wp.p3 = 0;
- wp.flag = (incomingMissionWpSequence >= incomingMissionWpCount) ? NAV_WP_FLAG_LAST : 0;
-
- setWaypoint(incomingMissionWpSequence, &wp);
+ setWaypoint(255, &wp);
- if (incomingMissionWpSequence >= incomingMissionWpCount) {
- if (isWaypointListValid()) {
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, MAV_MISSION_ACCEPTED, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
- }
- else {
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, MAV_MISSION_INVALID, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
- }
- }
- else {
- mavlink_msg_mission_request_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, incomingMissionWpSequence, MAV_MISSION_TYPE_MISSION);
- mavlinkSendMessage();
- }
- }
- else {
- // Wrong sequence number received
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, MAV_MISSION_INVALID_SEQUENCE, MAV_MISSION_TYPE_MISSION, 0);
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg,
+ mavRecvMsg.sysid, mavRecvMsg.compid,
+ MAV_MISSION_ACCEPTED, MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
+ return true;
+ } else {
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, MAV_MISSION_ERROR, MAV_MISSION_TYPE_MISSION, 0);
mavlinkSendMessage();
+ return true;
}
-
- return true;
}
- return false;
+ return mavlinkHandleMissionItemCommon(false, msg.frame, msg.command, msg.autocontinue, msg.seq, (int32_t)(msg.x * 1e7f), (int32_t)(msg.y * 1e7f), msg.z);
}
static bool handleIncoming_MISSION_REQUEST_LIST(void)
@@ -1366,36 +1378,35 @@ static bool handleIncoming_MISSION_REQUEST(void)
mavlink_mission_request_t msg;
mavlink_msg_mission_request_decode(&mavRecvMsg, &msg);
- // Check if this message is for us
- if (msg.target_system == mavSystemId) {
- int wpCount = getWaypointCount();
+ if (msg.target_system != mavSystemId) {
+ return false;
+ }
- if (msg.seq < wpCount) {
- navWaypoint_t wp;
- getWaypoint(msg.seq + 1, &wp);
-
- mavlink_msg_mission_item_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid,
- msg.seq,
- wp.action == NAV_WP_ACTION_RTH ? MAV_FRAME_MISSION : MAV_FRAME_GLOBAL_RELATIVE_ALT,
- wp.action == NAV_WP_ACTION_RTH ? MAV_CMD_NAV_RETURN_TO_LAUNCH : MAV_CMD_NAV_WAYPOINT,
- 0,
- 1,
- 0, 0, 0, 0,
- wp.lat / 1e7f,
- wp.lon / 1e7f,
- wp.alt / 100.0f,
- MAV_MISSION_TYPE_MISSION);
- mavlinkSendMessage();
- }
- else {
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, MAV_MISSION_INVALID_SEQUENCE, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
- }
+ int wpCount = getWaypointCount();
- return true;
+ if (msg.seq < wpCount) {
+ navWaypoint_t wp;
+ getWaypoint(msg.seq + 1, &wp);
+
+ mavlink_msg_mission_item_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid,
+ msg.seq,
+ wp.action == NAV_WP_ACTION_RTH ? MAV_FRAME_MISSION : MAV_FRAME_GLOBAL_RELATIVE_ALT,
+ wp.action == NAV_WP_ACTION_RTH ? MAV_CMD_NAV_RETURN_TO_LAUNCH : MAV_CMD_NAV_WAYPOINT,
+ 0,
+ 1,
+ 0, 0, 0, 0,
+ wp.lat / 1e7f,
+ wp.lon / 1e7f,
+ wp.alt / 100.0f,
+ MAV_MISSION_TYPE_MISSION);
+ mavlinkSendMessage();
+ }
+ else {
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, MAV_MISSION_INVALID_SEQUENCE, MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
}
- return false;
+ return true;
}
static bool mavlinkMessageToStream(uint16_t messageId, uint8_t *streamNum)
@@ -1541,12 +1552,20 @@ static bool handleIncoming_COMMAND(uint8_t targetSystem, uint8_t ackTargetSystem
return true;
}
case MAV_CMD_REQUEST_PROTOCOL_VERSION:
- mavlinkSendProtocolVersion();
- mavlinkSendCommandAck(command, MAV_RESULT_ACCEPTED, ackTargetSystem, ackTargetComponent);
+ if (telemetryConfig()->mavlink.version == 1) {
+ mavlinkSendCommandAck(command, MAV_RESULT_UNSUPPORTED, ackTargetSystem, ackTargetComponent);
+ } else {
+ mavlinkSendProtocolVersion();
+ mavlinkSendCommandAck(command, MAV_RESULT_ACCEPTED, ackTargetSystem, ackTargetComponent);
+ }
return true;
case MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES:
- mavlinkSendAutopilotVersion();
- mavlinkSendCommandAck(command, MAV_RESULT_ACCEPTED, ackTargetSystem, ackTargetComponent);
+ if (telemetryConfig()->mavlink.version == 1) {
+ mavlinkSendCommandAck(command, MAV_RESULT_UNSUPPORTED, ackTargetSystem, ackTargetComponent);
+ } else {
+ mavlinkSendAutopilotVersion();
+ mavlinkSendCommandAck(command, MAV_RESULT_ACCEPTED, ackTargetSystem, ackTargetComponent);
+ }
return true;
case MAV_CMD_REQUEST_MESSAGE:
{
@@ -1559,12 +1578,16 @@ static bool handleIncoming_COMMAND(uint8_t targetSystem, uint8_t ackTargetSystem
sent = true;
break;
case MAVLINK_MSG_ID_AUTOPILOT_VERSION:
- mavlinkSendAutopilotVersion();
- sent = true;
+ if (telemetryConfig()->mavlink.version != 1) {
+ mavlinkSendAutopilotVersion();
+ sent = true;
+ }
break;
case MAVLINK_MSG_ID_PROTOCOL_VERSION:
- mavlinkSendProtocolVersion();
- sent = true;
+ if (telemetryConfig()->mavlink.version != 1) {
+ mavlinkSendProtocolVersion();
+ sent = true;
+ }
break;
case MAVLINK_MSG_ID_SYS_STATUS:
mavlinkSendSystemStatus();
@@ -1682,6 +1705,82 @@ static bool handleIncoming_COMMAND_LONG(void)
return handleIncoming_COMMAND(msg.target_system, mavRecvMsg.sysid, mavRecvMsg.compid, msg.command, msg.confirmation, msg.param1, msg.param2, msg.param3, msg.param4, msg.param5, msg.param6, msg.param7);
}
+static bool handleIncoming_MISSION_ITEM_INT(void)
+{
+ mavlink_mission_item_int_t msg;
+ mavlink_msg_mission_item_int_decode(&mavRecvMsg, &msg);
+
+ if (msg.target_system != mavSystemId) {
+ return false;
+ }
+
+ if (ARMING_FLAG(ARMED)) {
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, MAV_MISSION_ERROR, MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
+ return true;
+ }
+
+ return mavlinkHandleMissionItemCommon(true, msg.frame, msg.command, msg.autocontinue, msg.seq, msg.x, msg.y, msg.z);
+}
+
+static bool handleIncoming_MISSION_REQUEST_INT(void)
+{
+ mavlink_mission_request_int_t msg;
+ mavlink_msg_mission_request_int_decode(&mavRecvMsg, &msg);
+
+ if (msg.target_system != mavSystemId) {
+ return false;
+ }
+
+ int wpCount = getWaypointCount();
+
+ if (msg.seq < wpCount) {
+ navWaypoint_t wp;
+ getWaypoint(msg.seq + 1, &wp);
+
+ mavlink_msg_mission_item_int_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid,
+ msg.seq,
+ wp.action == NAV_WP_ACTION_RTH ? MAV_FRAME_MISSION : MAV_FRAME_GLOBAL_RELATIVE_ALT_INT,
+ wp.action == NAV_WP_ACTION_RTH ? MAV_CMD_NAV_RETURN_TO_LAUNCH : MAV_CMD_NAV_WAYPOINT,
+ 0,
+ 1,
+ 0, 0, 0, 0,
+ wp.lat,
+ wp.lon,
+ wp.alt / 100.0f,
+ MAV_MISSION_TYPE_MISSION);
+ mavlinkSendMessage();
+ }
+ else {
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, MAV_MISSION_INVALID_SEQUENCE, MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
+ }
+
+ return true;
+}
+
+static bool handleIncoming_REQUEST_DATA_STREAM(void)
+{
+ mavlink_request_data_stream_t msg;
+ mavlink_msg_request_data_stream_decode(&mavRecvMsg, &msg);
+
+ if (msg.target_system != mavSystemId) {
+ return false;
+ }
+
+ if (msg.start_stop == 0) {
+ mavlinkSetStreamRate(msg.req_stream_id, 0);
+ return true;
+ }
+
+ uint8_t rate = (uint8_t)msg.req_message_rate;
+ if (rate > TELEMETRY_MAVLINK_MAXRATE) {
+ rate = TELEMETRY_MAVLINK_MAXRATE;
+ }
+ mavlinkSetStreamRate(msg.req_stream_id, rate);
+ return true;
+}
+
static bool handleIncoming_SET_POSITION_TARGET_GLOBAL_INT(void)
{
mavlink_set_position_target_global_int_t msg;
@@ -1834,6 +1933,8 @@ static bool processMAVLinkIncomingTelemetry(void)
return handleIncoming_MISSION_COUNT();
case MAVLINK_MSG_ID_MISSION_ITEM:
return handleIncoming_MISSION_ITEM();
+ case MAVLINK_MSG_ID_MISSION_ITEM_INT:
+ return handleIncoming_MISSION_ITEM_INT();
case MAVLINK_MSG_ID_MISSION_REQUEST_LIST:
return handleIncoming_MISSION_REQUEST_LIST();
@@ -1843,6 +1944,10 @@ static bool processMAVLinkIncomingTelemetry(void)
return handleIncoming_COMMAND_INT();
case MAVLINK_MSG_ID_MISSION_REQUEST:
return handleIncoming_MISSION_REQUEST();
+ case MAVLINK_MSG_ID_MISSION_REQUEST_INT:
+ return handleIncoming_MISSION_REQUEST_INT();
+ case MAVLINK_MSG_ID_REQUEST_DATA_STREAM:
+ return handleIncoming_REQUEST_DATA_STREAM();
case MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE:
handleIncoming_RC_CHANNELS_OVERRIDE();
// Don't set that we handled a message, otherwise RC channel packets will block telemetry messages
From 7201a83abf086a8b674bba866ade6cfbcb8f96d4 Mon Sep 17 00:00:00 2001
From: frogmane <7685285+xznhj8129@users.noreply.github.com>
Date: Sat, 13 Dec 2025 15:04:54 -0500
Subject: [PATCH 03/46] qgc mission errors fix + frame handling
---
src/main/telemetry/mavlink.c | 381 +++++++++++++++++++++++++++++------
1 file changed, 322 insertions(+), 59 deletions(-)
diff --git a/src/main/telemetry/mavlink.c b/src/main/telemetry/mavlink.c
index fddcff582c7..402d81d4718 100644
--- a/src/main/telemetry/mavlink.c
+++ b/src/main/telemetry/mavlink.c
@@ -449,7 +449,7 @@ static void mavlinkSendAutopilotVersion(void)
mavComponentId,
&mavSendMsg,
capabilities, // capabilities
- 0, // flight_sw_version
+ 0, // flight_sw_version. Setting this to actual Ardupilot version makes QGC not display modes anymore but "Unknown", except Guided is "GUIDED". Why?
0, // middleware_sw_version
0, // os_sw_version
0, // board_version
@@ -500,6 +500,31 @@ static bool mavlinkFrameIsSupported(uint8_t frame, mavFrameSupportMask_e allowed
}
}
+static bool mavlinkFrameUsesAbsoluteAltitude(uint8_t frame)
+{
+ return frame == MAV_FRAME_GLOBAL || frame == MAV_FRAME_GLOBAL_INT;
+}
+
+static uint8_t navWaypointFrame(const navWaypoint_t *wp, bool useIntMessages)
+{
+ switch (wp->action) {
+ case NAV_WP_ACTION_RTH:
+ case NAV_WP_ACTION_JUMP:
+ case NAV_WP_ACTION_SET_HEAD:
+ return MAV_FRAME_MISSION;
+ default:
+ break;
+ }
+
+ const bool absoluteAltitude = (wp->p3 & NAV_WP_ALTMODE) == NAV_WP_ALTMODE;
+
+ if (absoluteAltitude) {
+ return useIntMessages ? MAV_FRAME_GLOBAL_INT : MAV_FRAME_GLOBAL;
+ }
+
+ return useIntMessages ? MAV_FRAME_GLOBAL_RELATIVE_ALT_INT : MAV_FRAME_GLOBAL_RELATIVE_ALT;
+}
+
typedef struct {
uint8_t customMode;
const char *name;
@@ -965,7 +990,7 @@ void mavlinkSendAttitude(void)
mavlinkSendMessage();
}
-void mavlinkSendHUDAndHeartbeat(void)
+void mavlinkSendVfrHud(void)
{
float mavAltitude = 0;
float mavGroundSpeed = 0;
@@ -1009,11 +1034,11 @@ void mavlinkSendHUDAndHeartbeat(void)
mavClimbRate);
mavlinkSendMessage();
+}
-
- uint8_t mavModes = MAV_MODE_FLAG_MANUAL_INPUT_ENABLED | MAV_MODE_FLAG_CUSTOM_MODE_ENABLED;
- if (ARMING_FLAG(ARMED))
- mavModes |= MAV_MODE_FLAG_SAFETY_ARMED;
+void mavlinkSendHeartbeat(void)
+{
+ uint8_t mavModes = MAV_MODE_FLAG_CUSTOM_MODE_ENABLED;
uint8_t mavSystemType = mavlinkGetVehicleType();
@@ -1027,12 +1052,22 @@ void mavlinkSendHUDAndHeartbeat(void)
mavCustomMode = (uint8_t)inavToArduCopterMap(flm);
}
- if (flm != FLM_MANUAL) {
- mavModes |= MAV_MODE_FLAG_STABILIZE_ENABLED;
+ const bool manualInputAllowed = !(flm == FLM_MISSION || flm == FLM_RTH || flm == FLM_FAILSAFE);
+ if (manualInputAllowed) {
+ mavModes |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED;
}
- if (flm == FLM_POSITION_HOLD || flm == FLM_RTH || flm == FLM_MISSION) {
+ if (flm == FLM_POSITION_HOLD) {
mavModes |= MAV_MODE_FLAG_GUIDED_ENABLED;
}
+ else if (flm == FLM_MISSION || flm == FLM_RTH ) {
+ mavModes |= MAV_MODE_FLAG_AUTO_ENABLED;
+ }
+ else if (flm != FLM_MANUAL && flm!= FLM_ACRO && flm!=FLM_ACRO_AIR) {
+ mavModes |= MAV_MODE_FLAG_STABILIZE_ENABLED;
+ }
+
+ if (ARMING_FLAG(ARMED))
+ mavModes |= MAV_MODE_FLAG_SAFETY_ARMED;
uint8_t mavSystemState = 0;
if (ARMING_FLAG(ARMED)) {
@@ -1190,7 +1225,8 @@ void processMAVLinkTelemetry(timeUs_t currentTimeUs)
}
if (mavlinkStreamTrigger(MAV_DATA_STREAM_EXTRA2)) {
- mavlinkSendHUDAndHeartbeat();
+ mavlinkSendVfrHud();
+ mavlinkSendHeartbeat();
}
if (mavlinkStreamTrigger(MAV_DATA_STREAM_EXTENDED_SYS_STATE)) {
@@ -1223,36 +1259,169 @@ static bool handleIncoming_MISSION_CLEAR_ALL(void)
static int incomingMissionWpCount = 0;
static int incomingMissionWpSequence = 0;
-static bool mavlinkHandleMissionItemCommon(bool useIntMessages, uint8_t frame, uint16_t command, uint8_t autocontinue, uint16_t seq, int32_t lat, int32_t lon, float altMeters)
+static bool mavlinkHandleMissionItemCommon(bool useIntMessages, uint8_t frame, uint16_t command, uint8_t autocontinue, uint16_t seq, float param1, float param2, float param3, float param4, int32_t lat, int32_t lon, float altMeters)
{
- if ((autocontinue == 0) || (command != MAV_CMD_NAV_WAYPOINT && command != MAV_CMD_NAV_RETURN_TO_LAUNCH)) {
+ if (autocontinue == 0) {
mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, MAV_MISSION_UNSUPPORTED, MAV_MISSION_TYPE_MISSION, 0);
mavlinkSendMessage();
return true;
}
- if (!mavlinkFrameIsSupported(frame,
- MAV_FRAME_SUPPORTED_GLOBAL |
- MAV_FRAME_SUPPORTED_GLOBAL_INT |
- MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT |
- MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT_INT) &&
- !(frame == MAV_FRAME_MISSION && command == MAV_CMD_NAV_RETURN_TO_LAUNCH)) {
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, MAV_MISSION_UNSUPPORTED_FRAME, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
- return true;
+ UNUSED(param3);
+
+ navWaypoint_t wp;
+ memset(&wp, 0, sizeof(wp));
+
+ switch (command) {
+ case MAV_CMD_NAV_WAYPOINT:
+ if (!mavlinkFrameIsSupported(frame,
+ MAV_FRAME_SUPPORTED_GLOBAL |
+ MAV_FRAME_SUPPORTED_GLOBAL_INT |
+ MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT |
+ MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT_INT)) {
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, MAV_MISSION_UNSUPPORTED_FRAME, MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
+ return true;
+ }
+ wp.action = NAV_WP_ACTION_WAYPOINT;
+ wp.lat = lat;
+ wp.lon = lon;
+ wp.alt = (int32_t)(altMeters * 100.0f);
+ wp.p3 = mavlinkFrameUsesAbsoluteAltitude(frame) ? NAV_WP_ALTMODE : 0;
+ break;
+
+ case MAV_CMD_NAV_LOITER_TIME:
+ if (!mavlinkFrameIsSupported(frame,
+ MAV_FRAME_SUPPORTED_GLOBAL |
+ MAV_FRAME_SUPPORTED_GLOBAL_INT |
+ MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT |
+ MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT_INT)) {
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, MAV_MISSION_UNSUPPORTED_FRAME, MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
+ return true;
+ }
+ wp.action = NAV_WP_ACTION_HOLD_TIME;
+ wp.lat = lat;
+ wp.lon = lon;
+ wp.alt = (int32_t)(altMeters * 100.0f);
+ wp.p1 = (int16_t)lrintf(param1);
+ wp.p3 = mavlinkFrameUsesAbsoluteAltitude(frame) ? NAV_WP_ALTMODE : 0;
+ break;
+
+ case MAV_CMD_NAV_TAKEOFF:
+ if (!mavlinkFrameIsSupported(frame,
+ MAV_FRAME_SUPPORTED_GLOBAL |
+ MAV_FRAME_SUPPORTED_GLOBAL_INT |
+ MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT |
+ MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT_INT)) {
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, MAV_MISSION_UNSUPPORTED_FRAME, MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
+ return true;
+ }
+ // INAV has no dedicated TAKEOFF mission action; treat it as a normal waypoint.
+ wp.action = NAV_WP_ACTION_WAYPOINT;
+ wp.lat = lat;
+ wp.lon = lon;
+ wp.alt = (int32_t)(altMeters * 100.0f);
+ wp.p3 = mavlinkFrameUsesAbsoluteAltitude(frame) ? NAV_WP_ALTMODE : 0;
+ break;
+
+ case MAV_CMD_NAV_RETURN_TO_LAUNCH:
+ {
+ const bool coordinateFrame = mavlinkFrameIsSupported(frame,
+ MAV_FRAME_SUPPORTED_GLOBAL |
+ MAV_FRAME_SUPPORTED_GLOBAL_INT |
+ MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT |
+ MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT_INT);
+
+ if (!coordinateFrame && frame != MAV_FRAME_MISSION) {
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, MAV_MISSION_UNSUPPORTED_FRAME, MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
+ return true;
+ }
+ wp.action = NAV_WP_ACTION_RTH;
+ wp.lat = coordinateFrame ? lat : 0;
+ wp.lon = coordinateFrame ? lon : 0;
+ wp.alt = coordinateFrame ? (int32_t)(altMeters * 100.0f) : 0;
+ wp.p3 = mavlinkFrameUsesAbsoluteAltitude(frame) ? NAV_WP_ALTMODE : 0;
+ break;
+ }
+
+ case MAV_CMD_NAV_LAND:
+ if (!mavlinkFrameIsSupported(frame,
+ MAV_FRAME_SUPPORTED_GLOBAL |
+ MAV_FRAME_SUPPORTED_GLOBAL_INT |
+ MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT |
+ MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT_INT)) {
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, MAV_MISSION_UNSUPPORTED_FRAME, MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
+ return true;
+ }
+ wp.action = NAV_WP_ACTION_LAND;
+ wp.lat = lat;
+ wp.lon = lon;
+ wp.alt = (int32_t)(altMeters * 100.0f);
+ wp.p3 = mavlinkFrameUsesAbsoluteAltitude(frame) ? NAV_WP_ALTMODE : 0;
+ break;
+
+ case MAV_CMD_DO_JUMP:
+ if (frame != MAV_FRAME_MISSION) {
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, MAV_MISSION_UNSUPPORTED_FRAME, MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
+ return true;
+ }
+ if (param1 < 0.0f) {
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, MAV_MISSION_UNSUPPORTED, MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
+ return true;
+ }
+ wp.action = NAV_WP_ACTION_JUMP;
+ wp.p1 = (int16_t)lrintf(param1 + 1.0f);
+ wp.p2 = (int16_t)lrintf(param2);
+ break;
+
+ case MAV_CMD_DO_SET_ROI:
+ if (param1 != MAV_ROI_LOCATION ||
+ !mavlinkFrameIsSupported(frame,
+ MAV_FRAME_SUPPORTED_GLOBAL |
+ MAV_FRAME_SUPPORTED_GLOBAL_INT |
+ MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT |
+ MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT_INT)) {
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, MAV_MISSION_UNSUPPORTED, MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
+ return true;
+ }
+ wp.action = NAV_WP_ACTION_SET_POI;
+ wp.lat = lat;
+ wp.lon = lon;
+ wp.alt = (int32_t)(altMeters * 100.0f);
+ wp.p3 = mavlinkFrameUsesAbsoluteAltitude(frame) ? NAV_WP_ALTMODE : 0;
+ break;
+
+ case MAV_CMD_CONDITION_YAW:
+ if (frame != MAV_FRAME_MISSION) {
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, MAV_MISSION_UNSUPPORTED_FRAME, MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
+ return true;
+ }
+ if (param4 != 0.0f) {
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, MAV_MISSION_UNSUPPORTED, MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
+ return true;
+ }
+ wp.action = NAV_WP_ACTION_SET_HEAD;
+ wp.p1 = (int16_t)lrintf(param1);
+ break;
+
+ default:
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, MAV_MISSION_UNSUPPORTED, MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
+ return true;
}
if (seq == incomingMissionWpSequence) {
incomingMissionWpSequence++;
- navWaypoint_t wp;
- wp.action = (command == MAV_CMD_NAV_RETURN_TO_LAUNCH) ? NAV_WP_ACTION_RTH : NAV_WP_ACTION_WAYPOINT;
- wp.lat = lat;
- wp.lon = lon;
- wp.alt = (int32_t)(altMeters * 100.0f);
- wp.p1 = 0;
- wp.p2 = 0;
- wp.p3 = 0;
wp.flag = (incomingMissionWpSequence >= incomingMissionWpCount) ? NAV_WP_FLAG_LAST : 0;
setWaypoint(incomingMissionWpSequence, &wp);
@@ -1277,8 +1446,18 @@ static bool mavlinkHandleMissionItemCommon(bool useIntMessages, uint8_t frame, u
}
}
else {
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, MAV_MISSION_INVALID_SEQUENCE, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
+ // If we get a duplicate of the last accepted item, re-request the next one instead of aborting.
+ if (seq + 1 == incomingMissionWpSequence) {
+ if (useIntMessages) {
+ mavlink_msg_mission_request_int_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, incomingMissionWpSequence, MAV_MISSION_TYPE_MISSION);
+ } else {
+ mavlink_msg_mission_request_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, incomingMissionWpSequence, MAV_MISSION_TYPE_MISSION);
+ }
+ mavlinkSendMessage();
+ } else {
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, MAV_MISSION_INVALID_SEQUENCE, MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
+ }
}
return true;
@@ -1355,7 +1534,7 @@ static bool handleIncoming_MISSION_ITEM(void)
}
}
- return mavlinkHandleMissionItemCommon(false, msg.frame, msg.command, msg.autocontinue, msg.seq, (int32_t)(msg.x * 1e7f), (int32_t)(msg.y * 1e7f), msg.z);
+ return mavlinkHandleMissionItemCommon(false, msg.frame, msg.command, msg.autocontinue, msg.seq, msg.param1, msg.param2, msg.param3, msg.param4, (int32_t)(msg.x * 1e7f), (int32_t)(msg.y * 1e7f), msg.z);
}
static bool handleIncoming_MISSION_REQUEST_LIST(void)
@@ -1373,6 +1552,78 @@ static bool handleIncoming_MISSION_REQUEST_LIST(void)
return false;
}
+typedef struct {
+ uint8_t frame;
+ uint16_t command;
+ float param1;
+ float param2;
+ float param3;
+ float param4;
+ int32_t lat;
+ int32_t lon;
+ float alt;
+} mavlinkMissionItemData_t;
+
+static bool fillMavlinkMissionItemFromWaypoint(const navWaypoint_t *wp, bool useIntMessages, mavlinkMissionItemData_t *item)
+{
+ mavlinkMissionItemData_t data = {0};
+
+ data.frame = navWaypointFrame(wp, useIntMessages);
+
+ switch (wp->action) {
+ case NAV_WP_ACTION_WAYPOINT:
+ data.command = MAV_CMD_NAV_WAYPOINT;
+ data.lat = wp->lat;
+ data.lon = wp->lon;
+ data.alt = wp->alt / 100.0f;
+ break;
+
+ case NAV_WP_ACTION_HOLD_TIME:
+ data.command = MAV_CMD_NAV_LOITER_TIME;
+ data.param1 = wp->p1;
+ data.lat = wp->lat;
+ data.lon = wp->lon;
+ data.alt = wp->alt / 100.0f;
+ break;
+
+ case NAV_WP_ACTION_RTH:
+ data.command = MAV_CMD_NAV_RETURN_TO_LAUNCH;
+ break;
+
+ case NAV_WP_ACTION_LAND:
+ data.command = MAV_CMD_NAV_LAND;
+ data.lat = wp->lat;
+ data.lon = wp->lon;
+ data.alt = wp->alt / 100.0f;
+ break;
+
+ case NAV_WP_ACTION_JUMP:
+ data.command = MAV_CMD_DO_JUMP;
+ data.param1 = (wp->p1 > 0) ? (float)(wp->p1 - 1) : 0.0f;
+ data.param2 = wp->p2;
+ break;
+
+ case NAV_WP_ACTION_SET_POI:
+ data.command = MAV_CMD_DO_SET_ROI;
+ data.param1 = MAV_ROI_LOCATION;
+ data.lat = wp->lat;
+ data.lon = wp->lon;
+ data.alt = wp->alt / 100.0f;
+ break;
+
+ case NAV_WP_ACTION_SET_HEAD:
+ data.command = MAV_CMD_CONDITION_YAW;
+ data.param1 = wp->p1;
+ break;
+
+ default:
+ return false;
+ }
+
+ *item = data;
+ return true;
+}
+
static bool handleIncoming_MISSION_REQUEST(void)
{
mavlink_mission_request_t msg;
@@ -1388,18 +1639,24 @@ static bool handleIncoming_MISSION_REQUEST(void)
navWaypoint_t wp;
getWaypoint(msg.seq + 1, &wp);
- mavlink_msg_mission_item_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid,
- msg.seq,
- wp.action == NAV_WP_ACTION_RTH ? MAV_FRAME_MISSION : MAV_FRAME_GLOBAL_RELATIVE_ALT,
- wp.action == NAV_WP_ACTION_RTH ? MAV_CMD_NAV_RETURN_TO_LAUNCH : MAV_CMD_NAV_WAYPOINT,
- 0,
- 1,
- 0, 0, 0, 0,
- wp.lat / 1e7f,
- wp.lon / 1e7f,
- wp.alt / 100.0f,
- MAV_MISSION_TYPE_MISSION);
- mavlinkSendMessage();
+ mavlinkMissionItemData_t item;
+ if (fillMavlinkMissionItemFromWaypoint(&wp, false, &item)) {
+ mavlink_msg_mission_item_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid,
+ msg.seq,
+ item.frame,
+ item.command,
+ 0,
+ 1,
+ item.param1, item.param2, item.param3, item.param4,
+ item.lat / 1e7f,
+ item.lon / 1e7f,
+ item.alt,
+ MAV_MISSION_TYPE_MISSION);
+ mavlinkSendMessage();
+ } else {
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, MAV_MISSION_ERROR, MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
+ }
}
else {
mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, MAV_MISSION_INVALID_SEQUENCE, MAV_MISSION_TYPE_MISSION, 0);
@@ -1574,7 +1831,7 @@ static bool handleIncoming_COMMAND(uint8_t targetSystem, uint8_t ackTargetSystem
switch (messageId) {
case MAVLINK_MSG_ID_HEARTBEAT:
- mavlinkSendHUDAndHeartbeat();
+ mavlinkSendHeartbeat();
sent = true;
break;
case MAVLINK_MSG_ID_AUTOPILOT_VERSION:
@@ -1598,7 +1855,7 @@ static bool handleIncoming_COMMAND(uint8_t targetSystem, uint8_t ackTargetSystem
sent = true;
break;
case MAVLINK_MSG_ID_VFR_HUD:
- mavlinkSendHUDAndHeartbeat();
+ mavlinkSendVfrHud();
sent = true;
break;
case MAVLINK_MSG_ID_AVAILABLE_MODES:
@@ -1720,7 +1977,7 @@ static bool handleIncoming_MISSION_ITEM_INT(void)
return true;
}
- return mavlinkHandleMissionItemCommon(true, msg.frame, msg.command, msg.autocontinue, msg.seq, msg.x, msg.y, msg.z);
+ return mavlinkHandleMissionItemCommon(true, msg.frame, msg.command, msg.autocontinue, msg.seq, msg.param1, msg.param2, msg.param3, msg.param4, msg.x, msg.y, msg.z);
}
static bool handleIncoming_MISSION_REQUEST_INT(void)
@@ -1738,18 +1995,24 @@ static bool handleIncoming_MISSION_REQUEST_INT(void)
navWaypoint_t wp;
getWaypoint(msg.seq + 1, &wp);
- mavlink_msg_mission_item_int_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid,
- msg.seq,
- wp.action == NAV_WP_ACTION_RTH ? MAV_FRAME_MISSION : MAV_FRAME_GLOBAL_RELATIVE_ALT_INT,
- wp.action == NAV_WP_ACTION_RTH ? MAV_CMD_NAV_RETURN_TO_LAUNCH : MAV_CMD_NAV_WAYPOINT,
- 0,
- 1,
- 0, 0, 0, 0,
- wp.lat,
- wp.lon,
- wp.alt / 100.0f,
- MAV_MISSION_TYPE_MISSION);
- mavlinkSendMessage();
+ mavlinkMissionItemData_t item;
+ if (fillMavlinkMissionItemFromWaypoint(&wp, true, &item)) {
+ mavlink_msg_mission_item_int_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid,
+ msg.seq,
+ item.frame,
+ item.command,
+ 0,
+ 1,
+ item.param1, item.param2, item.param3, item.param4,
+ item.lat,
+ item.lon,
+ item.alt,
+ MAV_MISSION_TYPE_MISSION);
+ mavlinkSendMessage();
+ } else {
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, MAV_MISSION_ERROR, MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
+ }
}
else {
mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, MAV_MISSION_INVALID_SEQUENCE, MAV_MISSION_TYPE_MISSION, 0);
From 59b7ea887bf92da7b4a629c608860b990474e5dc Mon Sep 17 00:00:00 2001
From: frogmane <7685285+xznhj8129@users.noreply.github.com>
Date: Sat, 13 Dec 2025 15:19:47 -0500
Subject: [PATCH 04/46] no takeoff
---
src/main/telemetry/mavlink.c | 18 ------------------
1 file changed, 18 deletions(-)
diff --git a/src/main/telemetry/mavlink.c b/src/main/telemetry/mavlink.c
index 402d81d4718..6d3c73f469d 100644
--- a/src/main/telemetry/mavlink.c
+++ b/src/main/telemetry/mavlink.c
@@ -1308,24 +1308,6 @@ static bool mavlinkHandleMissionItemCommon(bool useIntMessages, uint8_t frame, u
wp.p3 = mavlinkFrameUsesAbsoluteAltitude(frame) ? NAV_WP_ALTMODE : 0;
break;
- case MAV_CMD_NAV_TAKEOFF:
- if (!mavlinkFrameIsSupported(frame,
- MAV_FRAME_SUPPORTED_GLOBAL |
- MAV_FRAME_SUPPORTED_GLOBAL_INT |
- MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT |
- MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT_INT)) {
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, MAV_MISSION_UNSUPPORTED_FRAME, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
- return true;
- }
- // INAV has no dedicated TAKEOFF mission action; treat it as a normal waypoint.
- wp.action = NAV_WP_ACTION_WAYPOINT;
- wp.lat = lat;
- wp.lon = lon;
- wp.alt = (int32_t)(altMeters * 100.0f);
- wp.p3 = mavlinkFrameUsesAbsoluteAltitude(frame) ? NAV_WP_ALTMODE : 0;
- break;
-
case MAV_CMD_NAV_RETURN_TO_LAUNCH:
{
const bool coordinateFrame = mavlinkFrameIsSupported(frame,
From 8fe997640258391c00cde71fe32c2633938a9bc1 Mon Sep 17 00:00:00 2001
From: frogmane <7685285+xznhj8129@users.noreply.github.com>
Date: Sun, 14 Dec 2025 12:40:05 -0500
Subject: [PATCH 05/46] defaults in wps
---
src/main/telemetry/mavlink.c | 24 +++++++++++++++++++++---
1 file changed, 21 insertions(+), 3 deletions(-)
diff --git a/src/main/telemetry/mavlink.c b/src/main/telemetry/mavlink.c
index 6d3c73f469d..e5ec36baa05 100644
--- a/src/main/telemetry/mavlink.c
+++ b/src/main/telemetry/mavlink.c
@@ -1287,6 +1287,8 @@ static bool mavlinkHandleMissionItemCommon(bool useIntMessages, uint8_t frame, u
wp.lat = lat;
wp.lon = lon;
wp.alt = (int32_t)(altMeters * 100.0f);
+ wp.p1 = 0;
+ wp.p2 = 0;
wp.p3 = mavlinkFrameUsesAbsoluteAltitude(frame) ? NAV_WP_ALTMODE : 0;
break;
@@ -1305,6 +1307,7 @@ static bool mavlinkHandleMissionItemCommon(bool useIntMessages, uint8_t frame, u
wp.lon = lon;
wp.alt = (int32_t)(altMeters * 100.0f);
wp.p1 = (int16_t)lrintf(param1);
+ wp.p2 = 0;
wp.p3 = mavlinkFrameUsesAbsoluteAltitude(frame) ? NAV_WP_ALTMODE : 0;
break;
@@ -1322,9 +1325,11 @@ static bool mavlinkHandleMissionItemCommon(bool useIntMessages, uint8_t frame, u
return true;
}
wp.action = NAV_WP_ACTION_RTH;
- wp.lat = coordinateFrame ? lat : 0;
- wp.lon = coordinateFrame ? lon : 0;
+ wp.lat = 0;
+ wp.lon = 0;
wp.alt = coordinateFrame ? (int32_t)(altMeters * 100.0f) : 0;
+ wp.p1 = 0; // Land if non-zero
+ wp.p2 = 0;
wp.p3 = mavlinkFrameUsesAbsoluteAltitude(frame) ? NAV_WP_ALTMODE : 0;
break;
}
@@ -1343,7 +1348,9 @@ static bool mavlinkHandleMissionItemCommon(bool useIntMessages, uint8_t frame, u
wp.lat = lat;
wp.lon = lon;
wp.alt = (int32_t)(altMeters * 100.0f);
- wp.p3 = mavlinkFrameUsesAbsoluteAltitude(frame) ? NAV_WP_ALTMODE : 0;
+ wp.p1 = 0; // Speed (cm/s)
+ wp.p2 = 0; // Elevation Adjustment (m): P2 defines the ground elevation (in metres) for the LAND WP. If the altitude mode is absolute, this is also absolute; for relative altitude, then it is the difference between the assumed home location and the LAND WP.
+ wp.p3 = mavlinkFrameUsesAbsoluteAltitude(frame) ? NAV_WP_ALTMODE : 0; // Altitude Mode & Actions, P3 defines the altitude mode. 0 (default, legacy) = Relative to Home, 1 = Absolute (AMSL).
break;
case MAV_CMD_DO_JUMP:
@@ -1357,9 +1364,13 @@ static bool mavlinkHandleMissionItemCommon(bool useIntMessages, uint8_t frame, u
mavlinkSendMessage();
return true;
}
+ wp.lat = 0;
+ wp.lon = 0;
+ wp.alt = 0;
wp.action = NAV_WP_ACTION_JUMP;
wp.p1 = (int16_t)lrintf(param1 + 1.0f);
wp.p2 = (int16_t)lrintf(param2);
+ wp.p3 = 0;
break;
case MAV_CMD_DO_SET_ROI:
@@ -1377,6 +1388,8 @@ static bool mavlinkHandleMissionItemCommon(bool useIntMessages, uint8_t frame, u
wp.lat = lat;
wp.lon = lon;
wp.alt = (int32_t)(altMeters * 100.0f);
+ wp.p1 = 0;
+ wp.p2 = 0;
wp.p3 = mavlinkFrameUsesAbsoluteAltitude(frame) ? NAV_WP_ALTMODE : 0;
break;
@@ -1391,8 +1404,13 @@ static bool mavlinkHandleMissionItemCommon(bool useIntMessages, uint8_t frame, u
mavlinkSendMessage();
return true;
}
+ wp.lat = 0;
+ wp.lon = 0;
+ wp.alt = 0;
wp.action = NAV_WP_ACTION_SET_HEAD;
wp.p1 = (int16_t)lrintf(param1);
+ wp.p2 = 0;
+ wp.p3 = 0;
break;
default:
From a3526add0b837116b5f1e384ee1786b7da58beb4 Mon Sep 17 00:00:00 2001
From: frogmane <7685285+xznhj8129@users.noreply.github.com>
Date: Sat, 17 Jan 2026 01:03:27 -0500
Subject: [PATCH 06/46] available modes fixes + unit tests
---
src/main/telemetry/mavlink.c | 96 +++-
src/test/unit/CMakeLists.txt | 10 +
src/test/unit/mavlink_unittest.cc | 888 ++++++++++++++++++++++++++++++
3 files changed, 985 insertions(+), 9 deletions(-)
create mode 100644 src/test/unit/mavlink_unittest.cc
diff --git a/src/main/telemetry/mavlink.c b/src/main/telemetry/mavlink.c
index e5ec36baa05..ace1a4061e3 100644
--- a/src/main/telemetry/mavlink.c
+++ b/src/main/telemetry/mavlink.c
@@ -335,6 +335,9 @@ static int mavlinkStreamTrigger(enum MAV_DATA_STREAM streamNum)
static void mavlinkSetStreamRate(uint8_t streamNum, uint8_t rate)
{
+ if (streamNum >= MAXSTREAMS) {
+ return;
+ }
mavRates[streamNum] = rate;
mavTicks[streamNum] = 0;
}
@@ -560,10 +563,84 @@ static const mavlinkModeDescriptor_t copterModes[] = {
{ COPTER_MODE_DRIFT, "DRIFT" },
};
-static void mavlinkSendAvailableModes(const mavlinkModeDescriptor_t *modes, uint8_t count, uint8_t currentCustom)
+static bool mavlinkPlaneModeIsConfigured(uint8_t customMode)
{
+ switch ((APM_PLANE_MODE)customMode) {
+ case PLANE_MODE_MANUAL:
+ return isModeActivationConditionPresent(BOXMANUAL);
+ case PLANE_MODE_ACRO:
+ return true;
+ case PLANE_MODE_STABILIZE:
+ return isModeActivationConditionPresent(BOXHORIZON) ||
+ isModeActivationConditionPresent(BOXANGLEHOLD);
+ case PLANE_MODE_FLY_BY_WIRE_A:
+ return isModeActivationConditionPresent(BOXANGLE);
+ case PLANE_MODE_FLY_BY_WIRE_B:
+ return isModeActivationConditionPresent(BOXNAVALTHOLD);
+ case PLANE_MODE_CRUISE:
+ return isModeActivationConditionPresent(BOXNAVCRUISE);
+ case PLANE_MODE_AUTO:
+ return isModeActivationConditionPresent(BOXNAVWP);
+ case PLANE_MODE_RTL:
+ return isModeActivationConditionPresent(BOXNAVRTH);
+ case PLANE_MODE_LOITER:
+ return isModeActivationConditionPresent(BOXNAVPOSHOLD);
+ case PLANE_MODE_GUIDED:
+ return isModeActivationConditionPresent(BOXNAVPOSHOLD) &&
+ isModeActivationConditionPresent(BOXGCSNAV);
+ case PLANE_MODE_TAKEOFF:
+ return isModeActivationConditionPresent(BOXNAVLAUNCH);
+ default:
+ return false;
+ }
+}
+
+static bool mavlinkCopterModeIsConfigured(uint8_t customMode)
+{
+ switch ((APM_COPTER_MODE)customMode) {
+ case COPTER_MODE_ACRO:
+ return true;
+ case COPTER_MODE_STABILIZE:
+ return isModeActivationConditionPresent(BOXANGLE) ||
+ isModeActivationConditionPresent(BOXHORIZON) ||
+ isModeActivationConditionPresent(BOXANGLEHOLD);
+ case COPTER_MODE_ALT_HOLD:
+ return isModeActivationConditionPresent(BOXNAVALTHOLD);
+ case COPTER_MODE_POSHOLD:
+ case COPTER_MODE_GUIDED:
+ return isModeActivationConditionPresent(BOXNAVPOSHOLD);
+ case COPTER_MODE_RTL:
+ return isModeActivationConditionPresent(BOXNAVRTH);
+ case COPTER_MODE_AUTO:
+ return isModeActivationConditionPresent(BOXNAVWP);
+ case COPTER_MODE_THROW:
+ return isModeActivationConditionPresent(BOXNAVLAUNCH);
+ default:
+ return false;
+ }
+}
+
+static void mavlinkSendAvailableModes(const mavlinkModeDescriptor_t *modes, uint8_t count, uint8_t currentCustom,
+ bool (*isModeConfigured)(uint8_t customMode))
+{
+ uint8_t availableCount = 0;
+ for (uint8_t i = 0; i < count; i++) {
+ if (isModeConfigured(modes[i].customMode)) {
+ availableCount++;
+ }
+ }
+
+ if (availableCount == 0) {
+ return;
+ }
+
+ uint8_t modeIndex = 0;
for (uint8_t i = 0; i < count; i++) {
- const uint8_t modeIndex = i + 1;
+ if (!isModeConfigured(modes[i].customMode)) {
+ continue;
+ }
+
+ modeIndex++;
const uint8_t stdMode = MAV_STANDARD_MODE_NON_STANDARD;
const uint32_t properties = 0;
@@ -571,7 +648,7 @@ static void mavlinkSendAvailableModes(const mavlinkModeDescriptor_t *modes, uint
mavSystemId,
mavComponentId,
&mavSendMsg,
- count,
+ availableCount,
modeIndex,
stdMode,
modes[i].customMode,
@@ -981,11 +1058,11 @@ void mavlinkSendAttitude(void)
// yaw Yaw angle (rad)
RADIANS_TO_MAVLINK_RANGE(DECIDEGREES_TO_RADIANS(attitude.values.yaw)),
// rollspeed Roll angular speed (rad/s)
- gyro.gyroADCf[FD_ROLL],
+ DEGREES_TO_RADIANS(gyro.gyroADCf[FD_ROLL]),
// pitchspeed Pitch angular speed (rad/s)
- gyro.gyroADCf[FD_PITCH],
+ DEGREES_TO_RADIANS(gyro.gyroADCf[FD_PITCH]),
// yawspeed Yaw angular speed (rad/s)
- gyro.gyroADCf[FD_YAW]);
+ DEGREES_TO_RADIANS(gyro.gyroADCf[FD_YAW]));
mavlinkSendMessage();
}
@@ -1864,10 +1941,10 @@ static bool handleIncoming_COMMAND(uint8_t targetSystem, uint8_t ackTargetSystem
uint8_t currentCustom;
if (mixerConfig()->platformType == PLATFORM_AIRPLANE || STATE(FIXED_WING_LEGACY)) {
currentCustom = (uint8_t)inavToArduPlaneMap(flm);
- mavlinkSendAvailableModes(planeModes, ARRAYLEN(planeModes), currentCustom);
+ mavlinkSendAvailableModes(planeModes, ARRAYLEN(planeModes), currentCustom, mavlinkPlaneModeIsConfigured);
} else {
currentCustom = (uint8_t)inavToArduCopterMap(flm);
- mavlinkSendAvailableModes(copterModes, ARRAYLEN(copterModes), currentCustom);
+ mavlinkSendAvailableModes(copterModes, ARRAYLEN(copterModes), currentCustom, mavlinkCopterModeIsConfigured);
}
sent = true;
}
@@ -1959,7 +2036,8 @@ static bool handleIncoming_COMMAND_LONG(void)
mavlink_command_long_t msg;
mavlink_msg_command_long_decode(&mavRecvMsg, &msg);
- return handleIncoming_COMMAND(msg.target_system, mavRecvMsg.sysid, mavRecvMsg.compid, msg.command, msg.confirmation, msg.param1, msg.param2, msg.param3, msg.param4, msg.param5, msg.param6, msg.param7);
+ // COMMAND_LONG has no frame field; location commands are WGS84 global by definition.
+ return handleIncoming_COMMAND(msg.target_system, mavRecvMsg.sysid, mavRecvMsg.compid, msg.command, MAV_FRAME_GLOBAL, msg.param1, msg.param2, msg.param3, msg.param4, msg.param5, msg.param6, msg.param7);
}
static bool handleIncoming_MISSION_ITEM_INT(void)
diff --git a/src/test/unit/CMakeLists.txt b/src/test/unit/CMakeLists.txt
index 2cb53b64ecb..f377b24a80e 100644
--- a/src/test/unit/CMakeLists.txt
+++ b/src/test/unit/CMakeLists.txt
@@ -43,6 +43,12 @@ set_property(SOURCE gps_ublox_unittest.cc PROPERTY definitions GPS_UBLOX_UNIT_TE
set_property(SOURCE gimbal_serial_unittest.cc PROPERTY depends "io/gimbal_serial.c" "drivers/gimbal_common.c" "common/maths.c" "drivers/headtracker_common.c")
set_property(SOURCE gimbal_serial_unittest.cc PROPERTY definitions USE_SERIAL_GIMBAL GIMBAL_UNIT_TEST USE_HEADTRACKER)
+set_property(SOURCE mavlink_unittest.cc PROPERTY depends
+ "telemetry/mavlink.c" "common/maths.c")
+set_property(SOURCE mavlink_unittest.cc PROPERTY definitions USE_TELEMETRY USE_TELEMETRY_MAVLINK)
+set_property(SOURCE mavlink_unittest.cc PROPERTY includes
+ "${CMAKE_CURRENT_SOURCE_DIR}/../../../lib/main/MAVLink")
+
function(unit_test src)
get_filename_component(basename ${src} NAME)
string(REPLACE ".cc" "" name ${basename} )
@@ -51,6 +57,7 @@ function(unit_test src)
list(TRANSFORM headers REPLACE "\.c$" ".h")
list(APPEND deps ${headers})
get_property(defs SOURCE ${src} PROPERTY definitions)
+ get_property(extra_includes SOURCE ${src} PROPERTY includes)
set(test_definitions "UNIT_TEST")
if (defs)
list(APPEND test_definitions ${defs})
@@ -60,6 +67,9 @@ function(unit_test src)
set(gen_name ${name}_gen)
get_generated_files_dir(gen ${gen_name})
target_include_directories(${name} PRIVATE . ${MAIN_DIR} ${gen})
+ if (extra_includes)
+ target_include_directories(${name} PRIVATE ${extra_includes})
+ endif()
target_compile_definitions(${name} PRIVATE ${test_definitions})
target_compile_options(${name} PRIVATE -pthread -Wall -Wextra -Wno-extern-c-compat -ggdb3 -O0)
enable_settings(${name} ${gen_name} OUTPUTS setting_files SETTINGS_CXX g++)
diff --git a/src/test/unit/mavlink_unittest.cc b/src/test/unit/mavlink_unittest.cc
new file mode 100644
index 00000000000..306e15e8bf4
--- /dev/null
+++ b/src/test/unit/mavlink_unittest.cc
@@ -0,0 +1,888 @@
+/*
+ * This file is part of Cleanflight.
+ *
+ * Cleanflight is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * Cleanflight is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with Cleanflight. If not, see .
+ */
+
+#include
+#include
+#include
+
+#include
+
+extern "C" {
+ #include "platform.h"
+
+ #include "build/debug.h"
+
+ #include "common/axis.h"
+ #include "common/maths.h"
+ #include "common/time.h"
+
+ #include "config/parameter_group.h"
+ #include "config/parameter_group_ids.h"
+
+ #include "drivers/display.h"
+ #include "drivers/osd_symbols.h"
+ #include "drivers/serial.h"
+
+ #include "fc/config.h"
+ #include "fc/rc_modes.h"
+ #include "fc/runtime_config.h"
+ #include "fc/settings.h"
+
+ #include "flight/failsafe.h"
+ #include "flight/imu.h"
+ #include "flight/mixer.h"
+ #include "flight/mixer_profile.h"
+
+ #include "io/adsb.h"
+ #include "io/gps.h"
+ #include "io/osd.h"
+
+ #include "navigation/navigation.h"
+
+ #include "rx/rx.h"
+
+ #include "sensors/barometer.h"
+ #include "sensors/battery.h"
+ #include "sensors/diagnostics.h"
+ #include "sensors/gyro.h"
+ #include "sensors/pitotmeter.h"
+ #include "sensors/temperature.h"
+
+ #include "telemetry/mavlink.h"
+ #include "telemetry/telemetry.h"
+
+#pragma GCC diagnostic push
+#pragma GCC diagnostic ignored "-Wunused-function"
+ #define MAVLINK_COMM_NUM_BUFFERS 1
+ #include "common/mavlink.h"
+#pragma GCC diagnostic pop
+
+ void mavlinkSendAttitude(void);
+
+ PG_REGISTER(telemetryConfig_t, telemetryConfig, PG_TELEMETRY_CONFIG, 0);
+ PG_REGISTER(rxConfig_t, rxConfig, PG_RX_CONFIG, 0);
+ PG_REGISTER(systemConfig_t, systemConfig, PG_SYSTEM_CONFIG, 0);
+ PG_REGISTER_ARRAY(mixerProfile_t, MAX_MIXER_PROFILE_COUNT, mixerProfiles, PG_MIXER_PROFILE, 0);
+}
+
+#include "unittest_macros.h"
+#include "gtest/gtest.h"
+
+static serialPort_t testSerialPort;
+static serialPortConfig_t testPortConfig;
+static uint8_t serialRxBuffer[2048];
+static uint8_t serialTxBuffer[2048];
+static size_t serialRxLen;
+static size_t serialRxPos;
+static size_t serialTxLen;
+
+const uint32_t baudRates[] = {
+ 0, 1200, 2400, 4800, 9600, 19200, 38400, 57600, 115200, 230400, 250000,
+ 460800, 921600, 1000000, 1500000, 2000000, 2470000
+};
+
+static navWaypoint_t lastWaypoint;
+static int setWaypointCalls;
+static int resetWaypointCalls;
+static int mavlinkRxHandleCalls;
+static bool gcsValid;
+static int waypointCount;
+static navWaypoint_t waypointStore[4];
+
+static void resetSerialBuffers(void)
+{
+ serialRxLen = 0;
+ serialRxPos = 0;
+ serialTxLen = 0;
+}
+
+static void pushRxMessage(const mavlink_message_t *msg)
+{
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ int length = mavlink_msg_to_send_buffer(buffer, msg);
+ memcpy(&serialRxBuffer[serialRxLen], buffer, (size_t)length);
+ serialRxLen += (size_t)length;
+}
+
+static bool popTxMessage(mavlink_message_t *msg)
+{
+ mavlink_status_t status;
+ memset(&status, 0, sizeof(status));
+ for (size_t i = 0; i < serialTxLen; i++) {
+ if (mavlink_parse_char(0, serialTxBuffer[i], msg, &status) == MAVLINK_FRAMING_OK) {
+ return true;
+ }
+ }
+ return false;
+}
+
+static void initMavlinkTestState(void)
+{
+ resetSerialBuffers();
+ setWaypointCalls = 0;
+ resetWaypointCalls = 0;
+ mavlinkRxHandleCalls = 0;
+ gcsValid = true;
+ waypointCount = 0;
+ memset(waypointStore, 0, sizeof(waypointStore));
+ memset(&rxLinkStatistics, 0, sizeof(rxLinkStatistics));
+
+ telemetryConfigMutable()->mavlink.sysid = 1;
+ telemetryConfigMutable()->mavlink.autopilot_type = MAVLINK_AUTOPILOT_ARDUPILOT;
+ telemetryConfigMutable()->mavlink.version = 2;
+ telemetryConfigMutable()->mavlink.min_txbuff = 0;
+ telemetryConfigMutable()->halfDuplex = 0;
+
+ rxConfigMutable()->receiverType = RX_TYPE_NONE;
+ rxConfigMutable()->serialrx_provider = SERIALRX_SBUS;
+ rxConfigMutable()->halfDuplex = 0;
+
+ systemConfigMutable()->current_mixer_profile_index = 0;
+ mixerProfilesMutable(0)->mixer_config.platformType = PLATFORM_AIRPLANE;
+
+ rxRuntimeConfig.channelCount = 8;
+
+ initMAVLinkTelemetry();
+ configureMAVLinkTelemetryPort();
+}
+
+TEST(MavlinkTelemetryTest, AttitudeUsesRadiansPerSecond)
+{
+ initMavlinkTestState();
+
+ attitude.values.roll = 100;
+ attitude.values.pitch = -200;
+ attitude.values.yaw = 450;
+ gyro.gyroADCf[FD_ROLL] = 90.0f;
+ gyro.gyroADCf[FD_PITCH] = -45.0f;
+ gyro.gyroADCf[FD_YAW] = 180.0f;
+
+ mavlinkSendAttitude();
+
+ mavlink_message_t msg;
+ ASSERT_TRUE(popTxMessage(&msg));
+ ASSERT_EQ(msg.msgid, MAVLINK_MSG_ID_ATTITUDE);
+
+ mavlink_attitude_t att;
+ mavlink_msg_attitude_decode(&msg, &att);
+
+ EXPECT_NEAR(att.rollspeed, DEGREES_TO_RADIANS(gyro.gyroADCf[FD_ROLL]), 1e-6f);
+ EXPECT_NEAR(att.pitchspeed, DEGREES_TO_RADIANS(gyro.gyroADCf[FD_PITCH]), 1e-6f);
+ EXPECT_NEAR(att.yawspeed, DEGREES_TO_RADIANS(gyro.gyroADCf[FD_YAW]), 1e-6f);
+}
+
+TEST(MavlinkTelemetryTest, CommandLongRepositionUsesGlobalFrameAndParams)
+{
+ initMavlinkTestState();
+
+ mavlink_message_t cmd;
+ mavlink_msg_command_long_pack(
+ 42, 200, &cmd,
+ 1, MAV_COMP_ID_MISSIONPLANNER,
+ MAV_CMD_DO_REPOSITION,
+ 0,
+ 0, 0, 0, 123.4f,
+ 37.5f, -122.25f, 12.3f);
+
+ pushRxMessage(&cmd);
+ handleMAVLinkTelemetry(1000);
+
+ mavlink_message_t ackMsg;
+ ASSERT_TRUE(popTxMessage(&ackMsg));
+ ASSERT_EQ(ackMsg.msgid, MAVLINK_MSG_ID_COMMAND_ACK);
+
+ mavlink_command_ack_t ack;
+ mavlink_msg_command_ack_decode(&ackMsg, &ack);
+
+ EXPECT_EQ(ack.command, MAV_CMD_DO_REPOSITION);
+ EXPECT_EQ(ack.result, MAV_RESULT_ACCEPTED);
+ EXPECT_EQ(setWaypointCalls, 1);
+ EXPECT_EQ(lastWaypoint.lat, (int32_t)(37.5f * 1e7f));
+ EXPECT_EQ(lastWaypoint.lon, (int32_t)(-122.25f * 1e7f));
+ EXPECT_EQ(lastWaypoint.alt, (int32_t)(12.3f * 100.0f));
+ EXPECT_EQ(lastWaypoint.p1, 123);
+}
+
+TEST(MavlinkTelemetryTest, CommandIntUnsupportedFrameIsRejected)
+{
+ initMavlinkTestState();
+
+ mavlink_message_t cmd;
+ mavlink_msg_command_int_pack(
+ 42, 200, &cmd,
+ 1, MAV_COMP_ID_MISSIONPLANNER,
+ MAV_FRAME_BODY_NED,
+ MAV_CMD_DO_REPOSITION,
+ 0, 0,
+ 0, 0, 0, 0,
+ 100000000, 200000000, 10.0f);
+
+ pushRxMessage(&cmd);
+ handleMAVLinkTelemetry(1000);
+
+ mavlink_message_t ackMsg;
+ ASSERT_TRUE(popTxMessage(&ackMsg));
+ ASSERT_EQ(ackMsg.msgid, MAVLINK_MSG_ID_COMMAND_ACK);
+
+ mavlink_command_ack_t ack;
+ mavlink_msg_command_ack_decode(&ackMsg, &ack);
+
+ EXPECT_EQ(ack.command, MAV_CMD_DO_REPOSITION);
+ EXPECT_EQ(ack.result, MAV_RESULT_UNSUPPORTED);
+ EXPECT_EQ(setWaypointCalls, 0);
+}
+
+TEST(MavlinkTelemetryTest, CommandIntRepositionScalesCoordinates)
+{
+ initMavlinkTestState();
+
+ mavlink_message_t cmd;
+ mavlink_msg_command_int_pack(
+ 42, 200, &cmd,
+ 1, MAV_COMP_ID_MISSIONPLANNER,
+ MAV_FRAME_GLOBAL_RELATIVE_ALT_INT,
+ MAV_CMD_DO_REPOSITION,
+ 0, 0,
+ 0, 0, 0, 45.6f,
+ 375000000, -1222500000, 12.3f);
+
+ pushRxMessage(&cmd);
+ handleMAVLinkTelemetry(1000);
+
+ mavlink_message_t ackMsg;
+ ASSERT_TRUE(popTxMessage(&ackMsg));
+ ASSERT_EQ(ackMsg.msgid, MAVLINK_MSG_ID_COMMAND_ACK);
+
+ mavlink_command_ack_t ack;
+ mavlink_msg_command_ack_decode(&ackMsg, &ack);
+
+ EXPECT_EQ(ack.command, MAV_CMD_DO_REPOSITION);
+ EXPECT_EQ(ack.result, MAV_RESULT_ACCEPTED);
+ EXPECT_EQ(setWaypointCalls, 1);
+ EXPECT_EQ(lastWaypoint.lat, 375000000);
+ EXPECT_NEAR((double)lastWaypoint.lon, -1222500000.0, 100.0);
+ EXPECT_EQ(lastWaypoint.alt, (int32_t)(12.3f * 100.0f));
+ EXPECT_EQ(lastWaypoint.p1, 45);
+}
+
+TEST(MavlinkTelemetryTest, MissionClearAllAcksAndResets)
+{
+ initMavlinkTestState();
+
+ mavlink_message_t msg;
+ mavlink_msg_mission_clear_all_pack(
+ 42, 200, &msg,
+ 1, MAV_COMP_ID_MISSIONPLANNER, MAV_MISSION_TYPE_MISSION);
+
+ pushRxMessage(&msg);
+ handleMAVLinkTelemetry(1000);
+
+ EXPECT_EQ(resetWaypointCalls, 1);
+
+ mavlink_message_t ackMsg;
+ ASSERT_TRUE(popTxMessage(&ackMsg));
+ ASSERT_EQ(ackMsg.msgid, MAVLINK_MSG_ID_MISSION_ACK);
+
+ mavlink_mission_ack_t ack;
+ mavlink_msg_mission_ack_decode(&ackMsg, &ack);
+
+ EXPECT_EQ(ack.type, MAV_MISSION_ACCEPTED);
+ EXPECT_EQ(ack.mission_type, MAV_MISSION_TYPE_MISSION);
+}
+
+TEST(MavlinkTelemetryTest, MissionCountRequestsFirstItem)
+{
+ initMavlinkTestState();
+
+ mavlink_message_t msg;
+ mavlink_msg_mission_count_pack(
+ 42, 200, &msg,
+ 1, MAV_COMP_ID_MISSIONPLANNER, 1, MAV_MISSION_TYPE_MISSION, 0);
+
+ pushRxMessage(&msg);
+ handleMAVLinkTelemetry(1000);
+
+ mavlink_message_t reqMsg;
+ ASSERT_TRUE(popTxMessage(&reqMsg));
+ ASSERT_EQ(reqMsg.msgid, MAVLINK_MSG_ID_MISSION_REQUEST_INT);
+
+ mavlink_mission_request_int_t req;
+ mavlink_msg_mission_request_int_decode(&reqMsg, &req);
+
+ EXPECT_EQ(req.seq, 0);
+ EXPECT_EQ(req.mission_type, MAV_MISSION_TYPE_MISSION);
+}
+
+TEST(MavlinkTelemetryTest, MissionItemIntSingleItemAcksAccepted)
+{
+ initMavlinkTestState();
+
+ mavlink_message_t countMsg;
+ mavlink_msg_mission_count_pack(
+ 42, 200, &countMsg,
+ 1, MAV_COMP_ID_MISSIONPLANNER, 1, MAV_MISSION_TYPE_MISSION, 0);
+
+ pushRxMessage(&countMsg);
+ handleMAVLinkTelemetry(1000);
+
+ serialTxLen = 0;
+
+ mavlink_message_t itemMsg;
+ mavlink_msg_mission_item_int_pack(
+ 42, 200, &itemMsg,
+ 1, MAV_COMP_ID_MISSIONPLANNER, 0,
+ MAV_FRAME_GLOBAL_RELATIVE_ALT_INT,
+ MAV_CMD_NAV_WAYPOINT, 0, 1,
+ 0, 0, 0, 0,
+ 375000000, -1222500000, 12.3f,
+ MAV_MISSION_TYPE_MISSION);
+
+ pushRxMessage(&itemMsg);
+ handleMAVLinkTelemetry(1000);
+
+ mavlink_message_t ackMsg;
+ ASSERT_TRUE(popTxMessage(&ackMsg));
+ ASSERT_EQ(ackMsg.msgid, MAVLINK_MSG_ID_MISSION_ACK);
+
+ mavlink_mission_ack_t ack;
+ mavlink_msg_mission_ack_decode(&ackMsg, &ack);
+
+ EXPECT_EQ(ack.type, MAV_MISSION_ACCEPTED);
+ EXPECT_EQ(setWaypointCalls, 1);
+ EXPECT_EQ(lastWaypoint.lat, 375000000);
+ EXPECT_EQ(lastWaypoint.lon, -1222500000);
+ EXPECT_EQ(lastWaypoint.alt, (int32_t)(12.3f * 100.0f));
+}
+
+TEST(MavlinkTelemetryTest, MissionRequestListSendsCount)
+{
+ initMavlinkTestState();
+ waypointCount = 2;
+
+ mavlink_message_t msg;
+ mavlink_msg_mission_request_list_pack(
+ 42, 200, &msg,
+ 1, MAV_COMP_ID_MISSIONPLANNER, MAV_MISSION_TYPE_MISSION);
+
+ pushRxMessage(&msg);
+ handleMAVLinkTelemetry(1000);
+
+ mavlink_message_t countMsg;
+ ASSERT_TRUE(popTxMessage(&countMsg));
+ ASSERT_EQ(countMsg.msgid, MAVLINK_MSG_ID_MISSION_COUNT);
+
+ mavlink_mission_count_t count;
+ mavlink_msg_mission_count_decode(&countMsg, &count);
+
+ EXPECT_EQ(count.count, 2);
+ EXPECT_EQ(count.mission_type, MAV_MISSION_TYPE_MISSION);
+}
+
+TEST(MavlinkTelemetryTest, MissionRequestSendsWaypoint)
+{
+ initMavlinkTestState();
+ waypointCount = 1;
+ waypointStore[0].action = NAV_WP_ACTION_WAYPOINT;
+ waypointStore[0].lat = 375000000;
+ waypointStore[0].lon = -1222500000;
+ waypointStore[0].alt = 1234;
+ waypointStore[0].p3 = 0;
+
+ mavlink_message_t msg;
+ mavlink_msg_mission_request_pack(
+ 42, 200, &msg,
+ 1, MAV_COMP_ID_MISSIONPLANNER, 0, MAV_MISSION_TYPE_MISSION);
+
+ pushRxMessage(&msg);
+ handleMAVLinkTelemetry(1000);
+
+ mavlink_message_t itemMsg;
+ ASSERT_TRUE(popTxMessage(&itemMsg));
+ ASSERT_EQ(itemMsg.msgid, MAVLINK_MSG_ID_MISSION_ITEM);
+
+ mavlink_mission_item_t item;
+ mavlink_msg_mission_item_decode(&itemMsg, &item);
+
+ EXPECT_EQ(item.seq, 0);
+ EXPECT_EQ(item.command, MAV_CMD_NAV_WAYPOINT);
+ EXPECT_EQ(item.frame, MAV_FRAME_GLOBAL_RELATIVE_ALT);
+ EXPECT_NEAR(item.x, 37.5f, 1e-4f);
+ EXPECT_NEAR(item.y, -122.25f, 1e-4f);
+ EXPECT_NEAR(item.z, 12.34f, 1e-4f);
+}
+
+TEST(MavlinkTelemetryTest, ParamRequestListRespondsWithEmptyParam)
+{
+ initMavlinkTestState();
+
+ mavlink_message_t msg;
+ mavlink_msg_param_request_list_pack(
+ 42, 200, &msg,
+ 1, MAV_COMP_ID_MISSIONPLANNER);
+
+ pushRxMessage(&msg);
+ handleMAVLinkTelemetry(1000);
+
+ mavlink_message_t paramMsg;
+ ASSERT_TRUE(popTxMessage(¶mMsg));
+ ASSERT_EQ(paramMsg.msgid, MAVLINK_MSG_ID_PARAM_VALUE);
+
+ mavlink_param_value_t param;
+ mavlink_msg_param_value_decode(¶mMsg, ¶m);
+
+ EXPECT_EQ(param.param_count, 0);
+ EXPECT_EQ(param.param_index, 0);
+}
+
+TEST(MavlinkTelemetryTest, SetPositionTargetGlobalIntSetsWaypoint)
+{
+ initMavlinkTestState();
+
+ mavlink_message_t msg;
+ mavlink_msg_set_position_target_global_int_pack(
+ 42, 200, &msg,
+ 0, 1, MAV_COMP_ID_MISSIONPLANNER,
+ MAV_FRAME_GLOBAL_RELATIVE_ALT_INT, 0,
+ 375000000, -1222500000, 12.3f,
+ 0, 0, 0, 0, 0, 0, 0, 0);
+
+ pushRxMessage(&msg);
+ handleMAVLinkTelemetry(1000);
+
+ EXPECT_EQ(setWaypointCalls, 1);
+ EXPECT_EQ(lastWaypoint.lat, 375000000);
+ EXPECT_EQ(lastWaypoint.lon, -1222500000);
+ EXPECT_EQ(lastWaypoint.alt, (int32_t)(12.3f * 100.0f));
+}
+
+TEST(MavlinkTelemetryTest, RequestDataStreamStopsStream)
+{
+ initMavlinkTestState();
+
+ mavlink_message_t setMsg;
+ mavlink_msg_request_data_stream_pack(
+ 42, 200, &setMsg,
+ 1, MAV_COMP_ID_MISSIONPLANNER,
+ MAV_DATA_STREAM_RC_CHANNELS, 10, 1);
+
+ pushRxMessage(&setMsg);
+ handleMAVLinkTelemetry(1000);
+
+ serialTxLen = 0;
+
+ mavlink_message_t getMsg;
+ mavlink_msg_command_long_pack(
+ 42, 200, &getMsg,
+ 1, MAV_COMP_ID_MISSIONPLANNER,
+ MAV_CMD_GET_MESSAGE_INTERVAL,
+ 0,
+ (float)MAVLINK_MSG_ID_RC_CHANNELS,
+ 0, 0, 0, 0, 0, 0);
+
+ pushRxMessage(&getMsg);
+ handleMAVLinkTelemetry(1000);
+
+ mavlink_message_t intervalMsg;
+ ASSERT_TRUE(popTxMessage(&intervalMsg));
+ ASSERT_EQ(intervalMsg.msgid, MAVLINK_MSG_ID_MESSAGE_INTERVAL);
+
+ mavlink_message_interval_t interval;
+ mavlink_msg_message_interval_decode(&intervalMsg, &interval);
+
+ EXPECT_EQ(interval.message_id, MAVLINK_MSG_ID_RC_CHANNELS);
+ EXPECT_EQ(interval.interval_us, 100000);
+
+ serialTxLen = 0;
+
+ mavlink_message_t stopMsg;
+ mavlink_msg_request_data_stream_pack(
+ 42, 200, &stopMsg,
+ 1, MAV_COMP_ID_MISSIONPLANNER,
+ MAV_DATA_STREAM_RC_CHANNELS, 0, 0);
+
+ pushRxMessage(&stopMsg);
+ handleMAVLinkTelemetry(1000);
+
+ serialTxLen = 0;
+
+ pushRxMessage(&getMsg);
+ handleMAVLinkTelemetry(1000);
+
+ ASSERT_TRUE(popTxMessage(&intervalMsg));
+ ASSERT_EQ(intervalMsg.msgid, MAVLINK_MSG_ID_MESSAGE_INTERVAL);
+
+ mavlink_msg_message_interval_decode(&intervalMsg, &interval);
+
+ EXPECT_EQ(interval.message_id, MAVLINK_MSG_ID_RC_CHANNELS);
+ EXPECT_EQ(interval.interval_us, -1);
+}
+
+TEST(MavlinkTelemetryTest, RadioStatusUpdatesRxLinkStats)
+{
+ initMavlinkTestState();
+ rxConfigMutable()->receiverType = RX_TYPE_SERIAL;
+ rxConfigMutable()->serialrx_provider = SERIALRX_MAVLINK;
+ telemetryConfigMutable()->mavlink.radio_type = MAVLINK_RADIO_ELRS;
+
+ mavlink_message_t msg;
+ mavlink_msg_radio_status_pack(
+ 42, 200, &msg,
+ 200, 150, 255, 7, 3, 0, 0);
+
+ pushRxMessage(&msg);
+ handleMAVLinkTelemetry(1000);
+
+ EXPECT_EQ(rxLinkStatistics.uplinkRSSI, -150);
+ EXPECT_EQ(rxLinkStatistics.uplinkSNR, 7);
+ EXPECT_EQ(rxLinkStatistics.uplinkLQ, scaleRange(200, 0, 255, 0, 100));
+}
+
+TEST(MavlinkTelemetryTest, RcChannelsOverrideIsForwarded)
+{
+ initMavlinkTestState();
+
+ mavlink_message_t msg;
+ mavlink_msg_rc_channels_override_pack(
+ 42, 200, &msg,
+ 1, MAV_COMP_ID_MISSIONPLANNER,
+ 1500, 1500, 1500, 1500, 1500, 1500, 1500, 1500,
+ 0, 0, 0, 0, 0, 0, 0, 0, 0, 0);
+
+ pushRxMessage(&msg);
+ handleMAVLinkTelemetry(1000);
+
+ EXPECT_EQ(mavlinkRxHandleCalls, 1);
+}
+
+extern "C" {
+
+int32_t debug[DEBUG32_VALUE_COUNT];
+
+uint32_t armingFlags;
+uint32_t stateFlags;
+
+attitudeEulerAngles_t attitude;
+gyro_t gyro;
+gpsSolutionData_t gpsSol;
+gpsLocation_t GPS_home;
+navSystemStatus_t NAV_Status;
+rxRuntimeConfig_t rxRuntimeConfig;
+rxLinkStatistics_t rxLinkStatistics;
+uint16_t averageSystemLoadPercent;
+
+uint32_t micros(void)
+{
+ return 0;
+}
+
+uint32_t millis(void)
+{
+ return 0;
+}
+
+serialPortConfig_t *findSerialPortConfig(serialPortFunction_e function)
+{
+ UNUSED(function);
+ testPortConfig.identifier = SERIAL_PORT_USART1;
+ testPortConfig.telemetry_baudrateIndex = BAUD_115200;
+ return &testPortConfig;
+}
+
+portSharing_e determinePortSharing(const serialPortConfig_t *portConfig, serialPortFunction_e function)
+{
+ UNUSED(portConfig);
+ UNUSED(function);
+ return PORTSHARING_NOT_SHARED;
+}
+
+serialPort_t *openSerialPort(serialPortIdentifier_e identifier, serialPortFunction_e function,
+ serialReceiveCallbackPtr rxCallback, void *rxCallbackData,
+ uint32_t baudRate, portMode_t mode, portOptions_t options)
+{
+ UNUSED(identifier);
+ UNUSED(function);
+ UNUSED(rxCallback);
+ UNUSED(rxCallbackData);
+ UNUSED(baudRate);
+ UNUSED(mode);
+ UNUSED(options);
+ return &testSerialPort;
+}
+
+void closeSerialPort(serialPort_t *serialPort)
+{
+ UNUSED(serialPort);
+}
+
+uint32_t serialRxBytesWaiting(const serialPort_t *instance)
+{
+ UNUSED(instance);
+ return (uint32_t)(serialRxLen - serialRxPos);
+}
+
+uint32_t serialTxBytesFree(const serialPort_t *instance)
+{
+ UNUSED(instance);
+ return 1024;
+}
+
+uint8_t serialRead(serialPort_t *instance)
+{
+ UNUSED(instance);
+ return serialRxBuffer[serialRxPos++];
+}
+
+void serialWrite(serialPort_t *instance, uint8_t ch)
+{
+ UNUSED(instance);
+ serialTxBuffer[serialTxLen++] = ch;
+}
+
+void serialSetMode(serialPort_t *instance, portMode_t mode)
+{
+ UNUSED(instance);
+ UNUSED(mode);
+}
+
+bool telemetryDetermineEnabledState(portSharing_e portSharing)
+{
+ UNUSED(portSharing);
+ return true;
+}
+
+bool sensors(uint32_t mask)
+{
+ UNUSED(mask);
+ return false;
+}
+
+bool isAmperageConfigured(void)
+{
+ return false;
+}
+
+bool feature(uint32_t mask)
+{
+ UNUSED(mask);
+ return false;
+}
+
+int16_t getAmperage(void)
+{
+ return 0;
+}
+
+int32_t getMAhDrawn(void)
+{
+ return 0;
+}
+
+int32_t getMWhDrawn(void)
+{
+ return 0;
+}
+
+uint8_t getBatteryCellCount(void)
+{
+ return 0;
+}
+
+uint16_t getBatteryAverageCellVoltage(void)
+{
+ return 0;
+}
+
+uint16_t getBatteryVoltage(void)
+{
+ return 0;
+}
+
+int16_t getThrottlePercent(bool scaled)
+{
+ UNUSED(scaled);
+ return 0;
+}
+
+bool osdUsingScaledThrottle(void)
+{
+ return false;
+}
+
+float getEstimatedActualPosition(int axis)
+{
+ UNUSED(axis);
+ return 0.0f;
+}
+
+float getEstimatedActualVelocity(int axis)
+{
+ UNUSED(axis);
+ return 0.0f;
+}
+
+float getAirspeedEstimate(void)
+{
+ return 0.0f;
+}
+
+bool pitotIsHealthy(void)
+{
+ return false;
+}
+
+bool rxIsReceivingSignal(void)
+{
+ return false;
+}
+
+bool rxAreFlightChannelsValid(void)
+{
+ return false;
+}
+
+uint16_t getRSSI(void)
+{
+ return 0;
+}
+
+int16_t rxGetChannelValue(unsigned channel)
+{
+ UNUSED(channel);
+ return 1500;
+}
+
+hardwareSensorStatus_e getHwGyroStatus(void) { return HW_SENSOR_NONE; }
+hardwareSensorStatus_e getHwAccelerometerStatus(void) { return HW_SENSOR_NONE; }
+hardwareSensorStatus_e getHwCompassStatus(void) { return HW_SENSOR_NONE; }
+hardwareSensorStatus_e getHwBarometerStatus(void) { return HW_SENSOR_NONE; }
+hardwareSensorStatus_e getHwGPSStatus(void) { return HW_SENSOR_NONE; }
+hardwareSensorStatus_e getHwRangefinderStatus(void) { return HW_SENSOR_NONE; }
+hardwareSensorStatus_e getHwPitotmeterStatus(void) { return HW_SENSOR_NONE; }
+hardwareSensorStatus_e getHwOpticalFlowStatus(void) { return HW_SENSOR_NONE; }
+
+bool getBaroTemperature(int16_t *temperature)
+{
+ *temperature = 0;
+ return false;
+}
+
+bool getIMUTemperature(int16_t *temperature)
+{
+ *temperature = 0;
+ return false;
+}
+
+bool areSensorsCalibrating(void)
+{
+ return false;
+}
+
+bool failsafeIsActive(void)
+{
+ return false;
+}
+
+failsafePhase_e failsafePhase(void)
+{
+ return FAILSAFE_IDLE;
+}
+
+int isGCSValid(void)
+{
+ return gcsValid;
+}
+
+void setWaypoint(uint8_t wpNumber, const navWaypoint_t *wp)
+{
+ UNUSED(wpNumber);
+ lastWaypoint = *wp;
+ setWaypointCalls++;
+}
+
+int getWaypointCount(void)
+{
+ return waypointCount;
+}
+
+void getWaypoint(uint8_t wpNumber, navWaypoint_t *wp)
+{
+ if (wpNumber == 0 || wpNumber > ARRAYLEN(waypointStore)) {
+ memset(wp, 0, sizeof(*wp));
+ return;
+ }
+ *wp = waypointStore[wpNumber - 1];
+}
+
+bool isWaypointListValid(void)
+{
+ return true;
+}
+
+void resetWaypointList(void)
+{
+ resetWaypointCalls++;
+ waypointCount = 0;
+ memset(waypointStore, 0, sizeof(waypointStore));
+}
+
+flightModeForTelemetry_e getFlightModeForTelemetry(void)
+{
+ return FLM_MANUAL;
+}
+
+bool isModeActivationConditionPresent(boxId_e modeId)
+{
+ UNUSED(modeId);
+ return false;
+}
+
+textAttributes_t osdGetSystemMessage(char *message, size_t length, bool remove)
+{
+ UNUSED(length);
+ UNUSED(remove);
+ message[0] = 0x20;
+ message[1] = '\0';
+ return 0;
+}
+
+void mavlinkRxHandleMessage(const mavlink_rc_channels_override_t *msg)
+{
+ UNUSED(msg);
+ mavlinkRxHandleCalls++;
+}
+
+adsbVehicleValues_t* getVehicleForFill(void)
+{
+ return NULL;
+}
+
+void adsbNewVehicle(adsbVehicleValues_t *vehicle)
+{
+ UNUSED(vehicle);
+}
+
+bool adsbHeartbeat(void)
+{
+ return false;
+}
+
+uint8_t calculateBatteryPercentage(void)
+{
+ return 0;
+}
+
+}
From 19fd708bfa351e48568f6bc8ded88a1d3803310b Mon Sep 17 00:00:00 2001
From: frogmane <7685285+xznhj8129@users.noreply.github.com>
Date: Tue, 27 Jan 2026 23:54:00 -0500
Subject: [PATCH 07/46] fix wrong mav version call
---
src/main/telemetry/mavlink.c | 7 ++++---
1 file changed, 4 insertions(+), 3 deletions(-)
diff --git a/src/main/telemetry/mavlink.c b/src/main/telemetry/mavlink.c
index ace1a4061e3..67f539f643f 100644
--- a/src/main/telemetry/mavlink.c
+++ b/src/main/telemetry/mavlink.c
@@ -473,14 +473,15 @@ static void mavlinkSendProtocolVersion(void)
uint8_t specHash[8] = {0};
uint8_t libHash[8] = {0};
+ const uint16_t protocolVersion = (uint16_t)telemetryConfig()->mavlink.version * 100;
mavlink_msg_protocol_version_pack(
mavSystemId,
mavComponentId,
&mavSendMsg,
- MAVLINK_VERSION,
- MAVLINK_VERSION,
- MAVLINK_VERSION,
+ protocolVersion,
+ protocolVersion,
+ protocolVersion,
specHash,
libHash);
From 11d378a83146ec4e549ac9f0dc31207fbb794089 Mon Sep 17 00:00:00 2001
From: frogmane <7685285+xznhj8129@users.noreply.github.com>
Date: Tue, 27 Jan 2026 23:56:16 -0500
Subject: [PATCH 08/46] honor altitude frames for guided
---
src/main/telemetry/mavlink.c | 6 +++---
1 file changed, 3 insertions(+), 3 deletions(-)
diff --git a/src/main/telemetry/mavlink.c b/src/main/telemetry/mavlink.c
index 67f539f643f..659cbad0953 100644
--- a/src/main/telemetry/mavlink.c
+++ b/src/main/telemetry/mavlink.c
@@ -1597,7 +1597,7 @@ static bool handleIncoming_MISSION_ITEM(void)
wp.alt = (int32_t)(msg.z * 100.0f);
wp.p1 = 0;
wp.p2 = 0;
- wp.p3 = 0;
+ wp.p3 = mavlinkFrameUsesAbsoluteAltitude(msg.frame) ? NAV_WP_ALTMODE : 0;
setWaypoint(255, &wp);
mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg,
@@ -1827,7 +1827,7 @@ static bool handleIncoming_COMMAND(uint8_t targetSystem, uint8_t ackTargetSystem
wp.p1 = 0;
}
wp.p2 = 0;
- wp.p3 = 0;
+ wp.p3 = mavlinkFrameUsesAbsoluteAltitude(frame) ? NAV_WP_ALTMODE : 0;
wp.flag = 0;
setWaypoint(255, &wp);
@@ -2147,7 +2147,7 @@ static bool handleIncoming_SET_POSITION_TARGET_GLOBAL_INT(void)
wp.alt = (int32_t)(msg.alt * 100.0f);
wp.p1 = 0;
wp.p2 = 0;
- wp.p3 = 0;
+ wp.p3 = mavlinkFrameUsesAbsoluteAltitude(frame) ? NAV_WP_ALTMODE : 0;
wp.flag = 0;
setWaypoint(255, &wp);
From 3594e2441542636bb58200170ea531a8c9450cd5 Mon Sep 17 00:00:00 2001
From: frogmane <7685285+xznhj8129@users.noreply.github.com>
Date: Tue, 27 Jan 2026 23:57:08 -0500
Subject: [PATCH 09/46] remove duplicate extended sys state
---
src/main/telemetry/mavlink.c | 2 --
1 file changed, 2 deletions(-)
diff --git a/src/main/telemetry/mavlink.c b/src/main/telemetry/mavlink.c
index 659cbad0953..85b9083ff0a 100644
--- a/src/main/telemetry/mavlink.c
+++ b/src/main/telemetry/mavlink.c
@@ -1254,8 +1254,6 @@ void mavlinkSendBatteryTemperatureStatusText(void)
mavlinkSendMessage();
- mavlinkSendExtendedSysState();
-
// FIXME - Status text is limited to boards with USE_OSD
#ifdef USE_OSD
char buff[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN] = {" "};
From ab0c7589a4ec738b054367b9f3622288f9bbd6e9 Mon Sep 17 00:00:00 2001
From: frogmane <7685285+xznhj8129@users.noreply.github.com>
Date: Tue, 27 Jan 2026 23:57:32 -0500
Subject: [PATCH 10/46] align heartbeat type for fixed wing
---
src/main/telemetry/mavlink.c | 8 +++++---
1 file changed, 5 insertions(+), 3 deletions(-)
diff --git a/src/main/telemetry/mavlink.c b/src/main/telemetry/mavlink.c
index 85b9083ff0a..7564f687e87 100644
--- a/src/main/telemetry/mavlink.c
+++ b/src/main/telemetry/mavlink.c
@@ -1118,16 +1118,18 @@ void mavlinkSendHeartbeat(void)
{
uint8_t mavModes = MAV_MODE_FLAG_CUSTOM_MODE_ENABLED;
- uint8_t mavSystemType = mavlinkGetVehicleType();
-
flightModeForTelemetry_e flm = getFlightModeForTelemetry();
uint8_t mavCustomMode;
+ uint8_t mavSystemType;
- if (STATE(FIXED_WING_LEGACY) || mixerConfig()->platformType == PLATFORM_AIRPLANE) {
+ const bool isPlane = (STATE(FIXED_WING_LEGACY) || mixerConfig()->platformType == PLATFORM_AIRPLANE);
+ if (isPlane) {
mavCustomMode = (uint8_t)inavToArduPlaneMap(flm);
+ mavSystemType = MAV_TYPE_FIXED_WING;
}
else {
mavCustomMode = (uint8_t)inavToArduCopterMap(flm);
+ mavSystemType = mavlinkGetVehicleType();
}
const bool manualInputAllowed = !(flm == FLM_MISSION || flm == FLM_RTH || flm == FLM_FAILSAFE);
From 3d4011c79eeb29e2ef361e8b56f81955494516bc Mon Sep 17 00:00:00 2001
From: frogmane <7685285+xznhj8129@users.noreply.github.com>
Date: Tue, 27 Jan 2026 23:59:43 -0500
Subject: [PATCH 11/46] add mavlink protocol and guided tests
---
src/test/unit/mavlink_unittest.cc | 95 +++++++++++++++++++++++++++++++
1 file changed, 95 insertions(+)
diff --git a/src/test/unit/mavlink_unittest.cc b/src/test/unit/mavlink_unittest.cc
index 306e15e8bf4..177e593ec93 100644
--- a/src/test/unit/mavlink_unittest.cc
+++ b/src/test/unit/mavlink_unittest.cc
@@ -72,6 +72,7 @@ extern "C" {
#pragma GCC diagnostic pop
void mavlinkSendAttitude(void);
+ void mavlinkSendBatteryTemperatureStatusText(void);
PG_REGISTER(telemetryConfig_t, telemetryConfig, PG_TELEMETRY_CONFIG, 0);
PG_REGISTER(rxConfig_t, rxConfig, PG_RX_CONFIG, 0);
@@ -214,6 +215,7 @@ TEST(MavlinkTelemetryTest, CommandLongRepositionUsesGlobalFrameAndParams)
EXPECT_EQ(lastWaypoint.lat, (int32_t)(37.5f * 1e7f));
EXPECT_EQ(lastWaypoint.lon, (int32_t)(-122.25f * 1e7f));
EXPECT_EQ(lastWaypoint.alt, (int32_t)(12.3f * 100.0f));
+ EXPECT_EQ(lastWaypoint.p3, NAV_WP_ALTMODE);
EXPECT_EQ(lastWaypoint.p1, 123);
}
@@ -276,6 +278,7 @@ TEST(MavlinkTelemetryTest, CommandIntRepositionScalesCoordinates)
EXPECT_EQ(lastWaypoint.lat, 375000000);
EXPECT_NEAR((double)lastWaypoint.lon, -1222500000.0, 100.0);
EXPECT_EQ(lastWaypoint.alt, (int32_t)(12.3f * 100.0f));
+ EXPECT_EQ(lastWaypoint.p3, 0);
EXPECT_EQ(lastWaypoint.p1, 45);
}
@@ -425,6 +428,28 @@ TEST(MavlinkTelemetryTest, MissionRequestSendsWaypoint)
EXPECT_NEAR(item.z, 12.34f, 1e-4f);
}
+TEST(MavlinkTelemetryTest, LegacyGuidedMissionItemUsesAbsoluteAltitude)
+{
+ initMavlinkTestState();
+ ENABLE_ARMING_FLAG(ARMED);
+
+ mavlink_message_t msg;
+ mavlink_msg_mission_item_pack(
+ 42, 200, &msg,
+ 1, MAV_COMP_ID_MISSIONPLANNER, 0,
+ MAV_FRAME_GLOBAL,
+ MAV_CMD_NAV_WAYPOINT, 2, 1,
+ 0, 0, 0, 0,
+ 37.5f, -122.25f, 12.3f,
+ MAV_MISSION_TYPE_MISSION);
+
+ pushRxMessage(&msg);
+ handleMAVLinkTelemetry(1000);
+
+ EXPECT_EQ(setWaypointCalls, 1);
+ EXPECT_EQ(lastWaypoint.p3, NAV_WP_ALTMODE);
+}
+
TEST(MavlinkTelemetryTest, ParamRequestListRespondsWithEmptyParam)
{
initMavlinkTestState();
@@ -467,6 +492,26 @@ TEST(MavlinkTelemetryTest, SetPositionTargetGlobalIntSetsWaypoint)
EXPECT_EQ(lastWaypoint.lat, 375000000);
EXPECT_EQ(lastWaypoint.lon, -1222500000);
EXPECT_EQ(lastWaypoint.alt, (int32_t)(12.3f * 100.0f));
+ EXPECT_EQ(lastWaypoint.p3, 0);
+}
+
+TEST(MavlinkTelemetryTest, SetPositionTargetGlobalIntUsesAbsoluteAltitude)
+{
+ initMavlinkTestState();
+
+ mavlink_message_t msg;
+ mavlink_msg_set_position_target_global_int_pack(
+ 42, 200, &msg,
+ 0, 1, MAV_COMP_ID_MISSIONPLANNER,
+ MAV_FRAME_GLOBAL_INT, 0,
+ 375000000, -1222500000, 12.3f,
+ 0, 0, 0, 0, 0, 0, 0, 0);
+
+ pushRxMessage(&msg);
+ handleMAVLinkTelemetry(1000);
+
+ EXPECT_EQ(setWaypointCalls, 1);
+ EXPECT_EQ(lastWaypoint.p3, NAV_WP_ALTMODE);
}
TEST(MavlinkTelemetryTest, RequestDataStreamStopsStream)
@@ -531,6 +576,56 @@ TEST(MavlinkTelemetryTest, RequestDataStreamStopsStream)
EXPECT_EQ(interval.interval_us, -1);
}
+TEST(MavlinkTelemetryTest, RequestProtocolVersionUsesConfiguredVersion)
+{
+ initMavlinkTestState();
+
+ mavlink_message_t msg;
+ mavlink_msg_command_long_pack(
+ 42, 200, &msg,
+ 1, MAV_COMP_ID_MISSIONPLANNER,
+ MAV_CMD_REQUEST_PROTOCOL_VERSION,
+ 0,
+ 0, 0, 0, 0, 0, 0, 0);
+
+ pushRxMessage(&msg);
+ handleMAVLinkTelemetry(1000);
+
+ mavlink_message_t versionMsg;
+ ASSERT_TRUE(popTxMessage(&versionMsg));
+ ASSERT_EQ(versionMsg.msgid, MAVLINK_MSG_ID_PROTOCOL_VERSION);
+
+ mavlink_protocol_version_t version;
+ mavlink_msg_protocol_version_decode(&versionMsg, &version);
+
+ EXPECT_EQ(version.version, 200);
+ EXPECT_EQ(version.min_version, 200);
+ EXPECT_EQ(version.max_version, 200);
+}
+
+TEST(MavlinkTelemetryTest, BatteryStatusDoesNotSendExtendedSysState)
+{
+ initMavlinkTestState();
+
+ mavlinkSendBatteryTemperatureStatusText();
+
+ mavlink_status_t status;
+ memset(&status, 0, sizeof(status));
+ mavlink_message_t msg;
+ bool sawExtSysState = false;
+
+ for (size_t i = 0; i < serialTxLen; i++) {
+ if (mavlink_parse_char(0, serialTxBuffer[i], &msg, &status) == MAVLINK_FRAMING_OK) {
+ if (msg.msgid == MAVLINK_MSG_ID_EXTENDED_SYS_STATE) {
+ sawExtSysState = true;
+ break;
+ }
+ }
+ }
+
+ EXPECT_FALSE(sawExtSysState);
+}
+
TEST(MavlinkTelemetryTest, RadioStatusUpdatesRxLinkStats)
{
initMavlinkTestState();
From e50a8780151e877189d829e4e8b881d612cb39c4 Mon Sep 17 00:00:00 2001
From: frogmane <7685285+xznhj8129@users.noreply.github.com>
Date: Wed, 28 Jan 2026 00:03:36 -0500
Subject: [PATCH 12/46] treat guided global altitude as relative
---
src/main/telemetry/mavlink.c | 6 +++---
src/test/unit/mavlink_unittest.cc | 10 +++++-----
2 files changed, 8 insertions(+), 8 deletions(-)
diff --git a/src/main/telemetry/mavlink.c b/src/main/telemetry/mavlink.c
index 7564f687e87..72f5cae72b8 100644
--- a/src/main/telemetry/mavlink.c
+++ b/src/main/telemetry/mavlink.c
@@ -1408,7 +1408,7 @@ static bool mavlinkHandleMissionItemCommon(bool useIntMessages, uint8_t frame, u
wp.alt = coordinateFrame ? (int32_t)(altMeters * 100.0f) : 0;
wp.p1 = 0; // Land if non-zero
wp.p2 = 0;
- wp.p3 = mavlinkFrameUsesAbsoluteAltitude(frame) ? NAV_WP_ALTMODE : 0;
+ wp.p3 = 0;
break;
}
@@ -1597,7 +1597,7 @@ static bool handleIncoming_MISSION_ITEM(void)
wp.alt = (int32_t)(msg.z * 100.0f);
wp.p1 = 0;
wp.p2 = 0;
- wp.p3 = mavlinkFrameUsesAbsoluteAltitude(msg.frame) ? NAV_WP_ALTMODE : 0;
+ wp.p3 = 0;
setWaypoint(255, &wp);
mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg,
@@ -2147,7 +2147,7 @@ static bool handleIncoming_SET_POSITION_TARGET_GLOBAL_INT(void)
wp.alt = (int32_t)(msg.alt * 100.0f);
wp.p1 = 0;
wp.p2 = 0;
- wp.p3 = mavlinkFrameUsesAbsoluteAltitude(frame) ? NAV_WP_ALTMODE : 0;
+ wp.p3 = 0;
wp.flag = 0;
setWaypoint(255, &wp);
diff --git a/src/test/unit/mavlink_unittest.cc b/src/test/unit/mavlink_unittest.cc
index 177e593ec93..e4cf902a390 100644
--- a/src/test/unit/mavlink_unittest.cc
+++ b/src/test/unit/mavlink_unittest.cc
@@ -215,7 +215,7 @@ TEST(MavlinkTelemetryTest, CommandLongRepositionUsesGlobalFrameAndParams)
EXPECT_EQ(lastWaypoint.lat, (int32_t)(37.5f * 1e7f));
EXPECT_EQ(lastWaypoint.lon, (int32_t)(-122.25f * 1e7f));
EXPECT_EQ(lastWaypoint.alt, (int32_t)(12.3f * 100.0f));
- EXPECT_EQ(lastWaypoint.p3, NAV_WP_ALTMODE);
+ EXPECT_EQ(lastWaypoint.p3, 0);
EXPECT_EQ(lastWaypoint.p1, 123);
}
@@ -428,7 +428,7 @@ TEST(MavlinkTelemetryTest, MissionRequestSendsWaypoint)
EXPECT_NEAR(item.z, 12.34f, 1e-4f);
}
-TEST(MavlinkTelemetryTest, LegacyGuidedMissionItemUsesAbsoluteAltitude)
+TEST(MavlinkTelemetryTest, LegacyGuidedMissionItemUsesRelativeAltitude)
{
initMavlinkTestState();
ENABLE_ARMING_FLAG(ARMED);
@@ -447,7 +447,7 @@ TEST(MavlinkTelemetryTest, LegacyGuidedMissionItemUsesAbsoluteAltitude)
handleMAVLinkTelemetry(1000);
EXPECT_EQ(setWaypointCalls, 1);
- EXPECT_EQ(lastWaypoint.p3, NAV_WP_ALTMODE);
+ EXPECT_EQ(lastWaypoint.p3, 0);
}
TEST(MavlinkTelemetryTest, ParamRequestListRespondsWithEmptyParam)
@@ -495,7 +495,7 @@ TEST(MavlinkTelemetryTest, SetPositionTargetGlobalIntSetsWaypoint)
EXPECT_EQ(lastWaypoint.p3, 0);
}
-TEST(MavlinkTelemetryTest, SetPositionTargetGlobalIntUsesAbsoluteAltitude)
+TEST(MavlinkTelemetryTest, SetPositionTargetGlobalIntUsesRelativeAltitude)
{
initMavlinkTestState();
@@ -511,7 +511,7 @@ TEST(MavlinkTelemetryTest, SetPositionTargetGlobalIntUsesAbsoluteAltitude)
handleMAVLinkTelemetry(1000);
EXPECT_EQ(setWaypointCalls, 1);
- EXPECT_EQ(lastWaypoint.p3, NAV_WP_ALTMODE);
+ EXPECT_EQ(lastWaypoint.p3, 0);
}
TEST(MavlinkTelemetryTest, RequestDataStreamStopsStream)
From eceab90881ad6c8aa34ab6729a3a098175772e41 Mon Sep 17 00:00:00 2001
From: frogmane <7685285+xznhj8129@users.noreply.github.com>
Date: Wed, 28 Jan 2026 00:04:21 -0500
Subject: [PATCH 13/46] reject mission upload while armed
---
src/main/telemetry/mavlink.c | 13 +++++------
src/test/unit/mavlink_unittest.cc | 37 +++++++++++++++++++++++++++++++
2 files changed, 43 insertions(+), 7 deletions(-)
diff --git a/src/main/telemetry/mavlink.c b/src/main/telemetry/mavlink.c
index 72f5cae72b8..908ba37e7d3 100644
--- a/src/main/telemetry/mavlink.c
+++ b/src/main/telemetry/mavlink.c
@@ -1548,19 +1548,18 @@ static bool handleIncoming_MISSION_COUNT(void)
// Check if this message is for us
if (msg.target_system == mavSystemId) {
+ if (ARMING_FLAG(ARMED)) {
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, MAV_MISSION_ERROR, MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
+ return true;
+ }
if (msg.count <= NAV_MAX_WAYPOINTS) {
incomingMissionWpCount = msg.count; // We need to know how many items to request
incomingMissionWpSequence = 0;
mavlink_msg_mission_request_int_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, incomingMissionWpSequence, MAV_MISSION_TYPE_MISSION);
mavlinkSendMessage();
return true;
- }
- else if (ARMING_FLAG(ARMED)) {
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, MAV_MISSION_ERROR, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
- return true;
- }
- else {
+ } else {
mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, MAV_MISSION_NO_SPACE, MAV_MISSION_TYPE_MISSION, 0);
mavlinkSendMessage();
return true;
diff --git a/src/test/unit/mavlink_unittest.cc b/src/test/unit/mavlink_unittest.cc
index e4cf902a390..0e7ee34a168 100644
--- a/src/test/unit/mavlink_unittest.cc
+++ b/src/test/unit/mavlink_unittest.cc
@@ -330,6 +330,43 @@ TEST(MavlinkTelemetryTest, MissionCountRequestsFirstItem)
EXPECT_EQ(req.mission_type, MAV_MISSION_TYPE_MISSION);
}
+TEST(MavlinkTelemetryTest, MissionCountWhileArmedIsRejected)
+{
+ initMavlinkTestState();
+ ENABLE_ARMING_FLAG(ARMED);
+
+ mavlink_message_t msg;
+ mavlink_msg_mission_count_pack(
+ 42, 200, &msg,
+ 1, MAV_COMP_ID_MISSIONPLANNER, 1, MAV_MISSION_TYPE_MISSION, 0);
+
+ pushRxMessage(&msg);
+ handleMAVLinkTelemetry(1000);
+
+ mavlink_status_t status;
+ memset(&status, 0, sizeof(status));
+ mavlink_message_t outMsg;
+ bool sawAck = false;
+ bool sawRequest = false;
+
+ for (size_t i = 0; i < serialTxLen; i++) {
+ if (mavlink_parse_char(0, serialTxBuffer[i], &outMsg, &status) == MAVLINK_FRAMING_OK) {
+ if (outMsg.msgid == MAVLINK_MSG_ID_MISSION_ACK) {
+ mavlink_mission_ack_t ack;
+ mavlink_msg_mission_ack_decode(&outMsg, &ack);
+ EXPECT_EQ(ack.type, MAV_MISSION_ERROR);
+ sawAck = true;
+ }
+ if (outMsg.msgid == MAVLINK_MSG_ID_MISSION_REQUEST_INT) {
+ sawRequest = true;
+ }
+ }
+ }
+
+ EXPECT_TRUE(sawAck);
+ EXPECT_FALSE(sawRequest);
+}
+
TEST(MavlinkTelemetryTest, MissionItemIntSingleItemAcksAccepted)
{
initMavlinkTestState();
From f9d27105dc6639fbd3633c9bf2fef8bd09f9c433 Mon Sep 17 00:00:00 2001
From: frogmane <7685285+xznhj8129@users.noreply.github.com>
Date: Wed, 28 Jan 2026 00:07:20 -0500
Subject: [PATCH 14/46] restore guided absolute altitude handling
---
src/main/telemetry/mavlink.c | 6 +++---
src/test/unit/mavlink_unittest.cc | 10 +++++-----
2 files changed, 8 insertions(+), 8 deletions(-)
diff --git a/src/main/telemetry/mavlink.c b/src/main/telemetry/mavlink.c
index 908ba37e7d3..a1edd8a2ce3 100644
--- a/src/main/telemetry/mavlink.c
+++ b/src/main/telemetry/mavlink.c
@@ -1408,7 +1408,7 @@ static bool mavlinkHandleMissionItemCommon(bool useIntMessages, uint8_t frame, u
wp.alt = coordinateFrame ? (int32_t)(altMeters * 100.0f) : 0;
wp.p1 = 0; // Land if non-zero
wp.p2 = 0;
- wp.p3 = 0;
+ wp.p3 = mavlinkFrameUsesAbsoluteAltitude(frame) ? NAV_WP_ALTMODE : 0;
break;
}
@@ -1448,7 +1448,7 @@ static bool mavlinkHandleMissionItemCommon(bool useIntMessages, uint8_t frame, u
wp.action = NAV_WP_ACTION_JUMP;
wp.p1 = (int16_t)lrintf(param1 + 1.0f);
wp.p2 = (int16_t)lrintf(param2);
- wp.p3 = 0;
+ wp.p3 = mavlinkFrameUsesAbsoluteAltitude(msg.frame) ? NAV_WP_ALTMODE : 0;
break;
case MAV_CMD_DO_SET_ROI:
@@ -2146,7 +2146,7 @@ static bool handleIncoming_SET_POSITION_TARGET_GLOBAL_INT(void)
wp.alt = (int32_t)(msg.alt * 100.0f);
wp.p1 = 0;
wp.p2 = 0;
- wp.p3 = 0;
+ wp.p3 = mavlinkFrameUsesAbsoluteAltitude(frame) ? NAV_WP_ALTMODE : 0;
wp.flag = 0;
setWaypoint(255, &wp);
diff --git a/src/test/unit/mavlink_unittest.cc b/src/test/unit/mavlink_unittest.cc
index 0e7ee34a168..56522cfee18 100644
--- a/src/test/unit/mavlink_unittest.cc
+++ b/src/test/unit/mavlink_unittest.cc
@@ -215,7 +215,7 @@ TEST(MavlinkTelemetryTest, CommandLongRepositionUsesGlobalFrameAndParams)
EXPECT_EQ(lastWaypoint.lat, (int32_t)(37.5f * 1e7f));
EXPECT_EQ(lastWaypoint.lon, (int32_t)(-122.25f * 1e7f));
EXPECT_EQ(lastWaypoint.alt, (int32_t)(12.3f * 100.0f));
- EXPECT_EQ(lastWaypoint.p3, 0);
+ EXPECT_EQ(lastWaypoint.p3, NAV_WP_ALTMODE);
EXPECT_EQ(lastWaypoint.p1, 123);
}
@@ -465,7 +465,7 @@ TEST(MavlinkTelemetryTest, MissionRequestSendsWaypoint)
EXPECT_NEAR(item.z, 12.34f, 1e-4f);
}
-TEST(MavlinkTelemetryTest, LegacyGuidedMissionItemUsesRelativeAltitude)
+TEST(MavlinkTelemetryTest, LegacyGuidedMissionItemUsesAbsoluteAltitude)
{
initMavlinkTestState();
ENABLE_ARMING_FLAG(ARMED);
@@ -484,7 +484,7 @@ TEST(MavlinkTelemetryTest, LegacyGuidedMissionItemUsesRelativeAltitude)
handleMAVLinkTelemetry(1000);
EXPECT_EQ(setWaypointCalls, 1);
- EXPECT_EQ(lastWaypoint.p3, 0);
+ EXPECT_EQ(lastWaypoint.p3, NAV_WP_ALTMODE);
}
TEST(MavlinkTelemetryTest, ParamRequestListRespondsWithEmptyParam)
@@ -532,7 +532,7 @@ TEST(MavlinkTelemetryTest, SetPositionTargetGlobalIntSetsWaypoint)
EXPECT_EQ(lastWaypoint.p3, 0);
}
-TEST(MavlinkTelemetryTest, SetPositionTargetGlobalIntUsesRelativeAltitude)
+TEST(MavlinkTelemetryTest, SetPositionTargetGlobalIntUsesAbsoluteAltitude)
{
initMavlinkTestState();
@@ -548,7 +548,7 @@ TEST(MavlinkTelemetryTest, SetPositionTargetGlobalIntUsesRelativeAltitude)
handleMAVLinkTelemetry(1000);
EXPECT_EQ(setWaypointCalls, 1);
- EXPECT_EQ(lastWaypoint.p3, 0);
+ EXPECT_EQ(lastWaypoint.p3, NAV_WP_ALTMODE);
}
TEST(MavlinkTelemetryTest, RequestDataStreamStopsStream)
From ecf96f043ffe9ae4eab3b6340ea95f19d90eb175 Mon Sep 17 00:00:00 2001
From: frogmane <7685285+xznhj8129@users.noreply.github.com>
Date: Wed, 28 Jan 2026 00:10:58 -0500
Subject: [PATCH 15/46] support guided mission_item_int
---
src/main/telemetry/mavlink.c | 32 ++++++++++++++++++++++++++++---
src/test/unit/mavlink_unittest.cc | 25 ++++++++++++++++++++++++
2 files changed, 54 insertions(+), 3 deletions(-)
diff --git a/src/main/telemetry/mavlink.c b/src/main/telemetry/mavlink.c
index a1edd8a2ce3..6b9df606ef9 100644
--- a/src/main/telemetry/mavlink.c
+++ b/src/main/telemetry/mavlink.c
@@ -2050,9 +2050,35 @@ static bool handleIncoming_MISSION_ITEM_INT(void)
}
if (ARMING_FLAG(ARMED)) {
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, MAV_MISSION_ERROR, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
- return true;
+ if (isGCSValid() && (msg.command == MAV_CMD_NAV_WAYPOINT) && (msg.current == 2)) {
+ if (!(msg.frame == MAV_FRAME_GLOBAL_INT || msg.frame == MAV_FRAME_GLOBAL_RELATIVE_ALT_INT)) {
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg,
+ mavRecvMsg.sysid, mavRecvMsg.compid,
+ MAV_MISSION_UNSUPPORTED_FRAME, MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
+ return true;
+ }
+
+ navWaypoint_t wp;
+ wp.action = NAV_WP_ACTION_WAYPOINT;
+ wp.lat = msg.x;
+ wp.lon = msg.y;
+ wp.alt = (int32_t)(msg.z * 100.0f);
+ wp.p1 = 0;
+ wp.p2 = 0;
+ wp.p3 = mavlinkFrameUsesAbsoluteAltitude(msg.frame) ? NAV_WP_ALTMODE : 0;
+ setWaypoint(255, &wp);
+
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg,
+ mavRecvMsg.sysid, mavRecvMsg.compid,
+ MAV_MISSION_ACCEPTED, MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
+ return true;
+ } else {
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, MAV_MISSION_ERROR, MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
+ return true;
+ }
}
return mavlinkHandleMissionItemCommon(true, msg.frame, msg.command, msg.autocontinue, msg.seq, msg.param1, msg.param2, msg.param3, msg.param4, msg.x, msg.y, msg.z);
diff --git a/src/test/unit/mavlink_unittest.cc b/src/test/unit/mavlink_unittest.cc
index 56522cfee18..6e09307247f 100644
--- a/src/test/unit/mavlink_unittest.cc
+++ b/src/test/unit/mavlink_unittest.cc
@@ -408,6 +408,31 @@ TEST(MavlinkTelemetryTest, MissionItemIntSingleItemAcksAccepted)
EXPECT_EQ(lastWaypoint.alt, (int32_t)(12.3f * 100.0f));
}
+TEST(MavlinkTelemetryTest, MissionItemIntGuidedWhileArmedUpdatesWaypoint)
+{
+ initMavlinkTestState();
+ ENABLE_ARMING_FLAG(ARMED);
+
+ mavlink_message_t msg;
+ mavlink_msg_mission_item_int_pack(
+ 42, 200, &msg,
+ 1, MAV_COMP_ID_MISSIONPLANNER, 0,
+ MAV_FRAME_GLOBAL_RELATIVE_ALT_INT,
+ MAV_CMD_NAV_WAYPOINT, 2, 1,
+ 0, 0, 0, 0,
+ 375000000, -1222500000, 12.3f,
+ MAV_MISSION_TYPE_MISSION);
+
+ pushRxMessage(&msg);
+ handleMAVLinkTelemetry(1000);
+
+ EXPECT_EQ(setWaypointCalls, 1);
+ EXPECT_EQ(lastWaypoint.lat, 375000000);
+ EXPECT_EQ(lastWaypoint.lon, -1222500000);
+ EXPECT_EQ(lastWaypoint.alt, (int32_t)(12.3f * 100.0f));
+ EXPECT_EQ(lastWaypoint.p3, 0);
+}
+
TEST(MavlinkTelemetryTest, MissionRequestListSendsCount)
{
initMavlinkTestState();
From 4e2ca11209fd8ade0f44311e1d5820af31a750d8 Mon Sep 17 00:00:00 2001
From: frogmane <7685285+xznhj8129@users.noreply.github.com>
Date: Wed, 28 Jan 2026 00:17:06 -0500
Subject: [PATCH 16/46] map mavlink modes to box config
---
src/main/telemetry/mavlink.c | 10 ++++++++--
1 file changed, 8 insertions(+), 2 deletions(-)
diff --git a/src/main/telemetry/mavlink.c b/src/main/telemetry/mavlink.c
index 6b9df606ef9..85964597ea1 100644
--- a/src/main/telemetry/mavlink.c
+++ b/src/main/telemetry/mavlink.c
@@ -579,7 +579,9 @@ static bool mavlinkPlaneModeIsConfigured(uint8_t customMode)
case PLANE_MODE_FLY_BY_WIRE_B:
return isModeActivationConditionPresent(BOXNAVALTHOLD);
case PLANE_MODE_CRUISE:
- return isModeActivationConditionPresent(BOXNAVCRUISE);
+ return isModeActivationConditionPresent(BOXNAVCRUISE) ||
+ (isModeActivationConditionPresent(BOXNAVCOURSEHOLD) &&
+ isModeActivationConditionPresent(BOXNAVALTHOLD));
case PLANE_MODE_AUTO:
return isModeActivationConditionPresent(BOXNAVWP);
case PLANE_MODE_RTL:
@@ -608,14 +610,18 @@ static bool mavlinkCopterModeIsConfigured(uint8_t customMode)
case COPTER_MODE_ALT_HOLD:
return isModeActivationConditionPresent(BOXNAVALTHOLD);
case COPTER_MODE_POSHOLD:
- case COPTER_MODE_GUIDED:
return isModeActivationConditionPresent(BOXNAVPOSHOLD);
+ case COPTER_MODE_GUIDED:
+ return isModeActivationConditionPresent(BOXNAVPOSHOLD) &&
+ isModeActivationConditionPresent(BOXGCSNAV);
case COPTER_MODE_RTL:
return isModeActivationConditionPresent(BOXNAVRTH);
case COPTER_MODE_AUTO:
return isModeActivationConditionPresent(BOXNAVWP);
case COPTER_MODE_THROW:
return isModeActivationConditionPresent(BOXNAVLAUNCH);
+ case COPTER_MODE_BRAKE:
+ return isModeActivationConditionPresent(BOXBRAKING);
default:
return false;
}
From 2b2bfb9bfa8013b37fdd8e834d7e7587c385c2bd Mon Sep 17 00:00:00 2001
From: frogmane <7685285+xznhj8129@users.noreply.github.com>
Date: Wed, 28 Jan 2026 00:25:57 -0500
Subject: [PATCH 17/46] fix do_jump waypoint p3
---
src/main/telemetry/mavlink.c | 2 +-
1 file changed, 1 insertion(+), 1 deletion(-)
diff --git a/src/main/telemetry/mavlink.c b/src/main/telemetry/mavlink.c
index 85964597ea1..e23efca244c 100644
--- a/src/main/telemetry/mavlink.c
+++ b/src/main/telemetry/mavlink.c
@@ -1454,7 +1454,7 @@ static bool mavlinkHandleMissionItemCommon(bool useIntMessages, uint8_t frame, u
wp.action = NAV_WP_ACTION_JUMP;
wp.p1 = (int16_t)lrintf(param1 + 1.0f);
wp.p2 = (int16_t)lrintf(param2);
- wp.p3 = mavlinkFrameUsesAbsoluteAltitude(msg.frame) ? NAV_WP_ALTMODE : 0;
+ wp.p3 = 0;
break;
case MAV_CMD_DO_SET_ROI:
From 6bc963bb8f6396bede1f5e7567b6b5a979add696 Mon Sep 17 00:00:00 2001
From: frogmane <7685285+xznhj8129@users.noreply.github.com>
Date: Wed, 28 Jan 2026 00:27:07 -0500
Subject: [PATCH 18/46] set guided mission_item altitude mode
---
src/main/telemetry/mavlink.c | 2 +-
1 file changed, 1 insertion(+), 1 deletion(-)
diff --git a/src/main/telemetry/mavlink.c b/src/main/telemetry/mavlink.c
index e23efca244c..fe0aebe26b7 100644
--- a/src/main/telemetry/mavlink.c
+++ b/src/main/telemetry/mavlink.c
@@ -1602,7 +1602,7 @@ static bool handleIncoming_MISSION_ITEM(void)
wp.alt = (int32_t)(msg.z * 100.0f);
wp.p1 = 0;
wp.p2 = 0;
- wp.p3 = 0;
+ wp.p3 = mavlinkFrameUsesAbsoluteAltitude(msg.frame) ? NAV_WP_ALTMODE : 0;
setWaypoint(255, &wp);
mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg,
From e2656b8e2ecb6cea52f44949fe3f09455be50b17 Mon Sep 17 00:00:00 2001
From: frogmane <7685285+xznhj8129@users.noreply.github.com>
Date: Mon, 23 Feb 2026 22:13:00 -0500
Subject: [PATCH 19/46] mode fixgit status!
---
docs/development/msp/inav_enums.json | 3822 ++++++++++++++++++++++++
docs/development/msp/inav_enums_ref.md | 14 +
src/main/telemetry/mavlink.c | 76 +-
3 files changed, 3878 insertions(+), 34 deletions(-)
create mode 100644 docs/development/msp/inav_enums.json
diff --git a/docs/development/msp/inav_enums.json b/docs/development/msp/inav_enums.json
new file mode 100644
index 00000000000..6262cc2ed47
--- /dev/null
+++ b/docs/development/msp/inav_enums.json
@@ -0,0 +1,3822 @@
+{
+ "accelerationSensor_e": {
+ "_source": "../../../src/main/sensors/acceleration.h",
+ "ACC_NONE": "0",
+ "ACC_AUTODETECT": "1",
+ "ACC_MPU6000": "2",
+ "ACC_MPU6500": "3",
+ "ACC_MPU9250": "4",
+ "ACC_BMI160": "5",
+ "ACC_ICM20689": "6",
+ "ACC_BMI088": "7",
+ "ACC_ICM42605": "8",
+ "ACC_BMI270": "9",
+ "ACC_LSM6DXX": "10",
+ "ACC_FAKE": "11",
+ "ACC_MAX": "ACC_FAKE"
+ },
+ "accEvent_t": {
+ "_source": "../../../src/main/telemetry/sim.c",
+ "ACC_EVENT_NONE": "0",
+ "ACC_EVENT_HIGH": "1",
+ "ACC_EVENT_LOW": "2",
+ "ACC_EVENT_NEG_X": "3"
+ },
+ "adcChannel_e": {
+ "_source": "../../../src/main/drivers/adc.h",
+ "ADC_CHN_NONE": "0",
+ "ADC_CHN_1": "1",
+ "ADC_CHN_2": "2",
+ "ADC_CHN_3": "3",
+ "ADC_CHN_4": "4",
+ "ADC_CHN_5": "5",
+ "ADC_CHN_6": "6",
+ "ADC_CHN_MAX": "ADC_CHN_6",
+ "ADC_CHN_COUNT": ""
+ },
+ "adcFunction_e": {
+ "_source": "../../../src/main/drivers/adc.h",
+ "ADC_BATTERY": "0",
+ "ADC_RSSI": "1",
+ "ADC_CURRENT": "2",
+ "ADC_AIRSPEED": "3",
+ "ADC_FUNCTION_COUNT": "4"
+ },
+ "adjustmentFunction_e": {
+ "_source": "../../../src/main/fc/rc_adjustments.h",
+ "ADJUSTMENT_NONE": "0",
+ "ADJUSTMENT_RC_RATE": "1",
+ "ADJUSTMENT_RC_EXPO": "2",
+ "ADJUSTMENT_THROTTLE_EXPO": "3",
+ "ADJUSTMENT_PITCH_ROLL_RATE": "4",
+ "ADJUSTMENT_YAW_RATE": "5",
+ "ADJUSTMENT_PITCH_ROLL_P": "6",
+ "ADJUSTMENT_PITCH_ROLL_I": "7",
+ "ADJUSTMENT_PITCH_ROLL_D": "8",
+ "ADJUSTMENT_PITCH_ROLL_FF": "9",
+ "ADJUSTMENT_PITCH_P": "10",
+ "ADJUSTMENT_PITCH_I": "11",
+ "ADJUSTMENT_PITCH_D": "12",
+ "ADJUSTMENT_PITCH_FF": "13",
+ "ADJUSTMENT_ROLL_P": "14",
+ "ADJUSTMENT_ROLL_I": "15",
+ "ADJUSTMENT_ROLL_D": "16",
+ "ADJUSTMENT_ROLL_FF": "17",
+ "ADJUSTMENT_YAW_P": "18",
+ "ADJUSTMENT_YAW_I": "19",
+ "ADJUSTMENT_YAW_D": "20",
+ "ADJUSTMENT_YAW_FF": "21",
+ "ADJUSTMENT_RATE_PROFILE": "22",
+ "ADJUSTMENT_PITCH_RATE": "23",
+ "ADJUSTMENT_ROLL_RATE": "24",
+ "ADJUSTMENT_RC_YAW_EXPO": "25",
+ "ADJUSTMENT_MANUAL_RC_EXPO": "26",
+ "ADJUSTMENT_MANUAL_RC_YAW_EXPO": "27",
+ "ADJUSTMENT_MANUAL_PITCH_ROLL_RATE": "28",
+ "ADJUSTMENT_MANUAL_ROLL_RATE": "29",
+ "ADJUSTMENT_MANUAL_PITCH_RATE": "30",
+ "ADJUSTMENT_MANUAL_YAW_RATE": "31",
+ "ADJUSTMENT_NAV_FW_CRUISE_THR": "32",
+ "ADJUSTMENT_NAV_FW_PITCH2THR": "33",
+ "ADJUSTMENT_ROLL_BOARD_ALIGNMENT": "34",
+ "ADJUSTMENT_PITCH_BOARD_ALIGNMENT": "35",
+ "ADJUSTMENT_LEVEL_P": "36",
+ "ADJUSTMENT_LEVEL_I": "37",
+ "ADJUSTMENT_LEVEL_D": "38",
+ "ADJUSTMENT_POS_XY_P": "39",
+ "ADJUSTMENT_POS_XY_I": "40",
+ "ADJUSTMENT_POS_XY_D": "41",
+ "ADJUSTMENT_POS_Z_P": "42",
+ "ADJUSTMENT_POS_Z_I": "43",
+ "ADJUSTMENT_POS_Z_D": "44",
+ "ADJUSTMENT_HEADING_P": "45",
+ "ADJUSTMENT_VEL_XY_P": "46",
+ "ADJUSTMENT_VEL_XY_I": "47",
+ "ADJUSTMENT_VEL_XY_D": "48",
+ "ADJUSTMENT_VEL_Z_P": "49",
+ "ADJUSTMENT_VEL_Z_I": "50",
+ "ADJUSTMENT_VEL_Z_D": "51",
+ "ADJUSTMENT_FW_MIN_THROTTLE_DOWN_PITCH_ANGLE": "52",
+ "ADJUSTMENT_VTX_POWER_LEVEL": "53",
+ "ADJUSTMENT_TPA": "54",
+ "ADJUSTMENT_TPA_BREAKPOINT": "55",
+ "ADJUSTMENT_NAV_FW_CONTROL_SMOOTHNESS": "56",
+ "ADJUSTMENT_FW_TPA_TIME_CONSTANT": "57",
+ "ADJUSTMENT_FW_LEVEL_TRIM": "58",
+ "ADJUSTMENT_NAV_WP_MULTI_MISSION_INDEX": "59",
+ "ADJUSTMENT_NAV_FW_ALT_CONTROL_RESPONSE": "60",
+ "ADJUSTMENT_FUNCTION_COUNT": "61"
+ },
+ "adjustmentMode_e": {
+ "_source": "../../../src/main/fc/rc_adjustments.h",
+ "ADJUSTMENT_MODE_STEP": "0",
+ "ADJUSTMENT_MODE_SELECT": "1"
+ },
+ "afatfsAppendFreeClusterPhase_e": {
+ "_source": "../../../src/main/io/asyncfatfs/asyncfatfs.c",
+ "AFATFS_APPEND_FREE_CLUSTER_PHASE_INITIAL": "0",
+ "AFATFS_APPEND_FREE_CLUSTER_PHASE_FIND_FREESPACE": "0",
+ "AFATFS_APPEND_FREE_CLUSTER_PHASE_UPDATE_FAT1": "1",
+ "AFATFS_APPEND_FREE_CLUSTER_PHASE_UPDATE_FAT2": "2",
+ "AFATFS_APPEND_FREE_CLUSTER_PHASE_UPDATE_FILE_DIRECTORY": "3",
+ "AFATFS_APPEND_FREE_CLUSTER_PHASE_COMPLETE": "4",
+ "AFATFS_APPEND_FREE_CLUSTER_PHASE_FAILURE": "5"
+ },
+ "afatfsAppendSuperclusterPhase_e": {
+ "_source": "../../../src/main/io/asyncfatfs/asyncfatfs.c",
+ "AFATFS_APPEND_SUPERCLUSTER_PHASE_INIT": "0",
+ "AFATFS_APPEND_SUPERCLUSTER_PHASE_UPDATE_FREEFILE_DIRECTORY": "1",
+ "AFATFS_APPEND_SUPERCLUSTER_PHASE_UPDATE_FAT": "2",
+ "AFATFS_APPEND_SUPERCLUSTER_PHASE_UPDATE_FILE_DIRECTORY": "3"
+ },
+ "afatfsCacheBlockState_e": {
+ "_source": "../../../src/main/io/asyncfatfs/asyncfatfs.c",
+ "AFATFS_CACHE_STATE_EMPTY": "0",
+ "AFATFS_CACHE_STATE_IN_SYNC": "1",
+ "AFATFS_CACHE_STATE_READING": "2",
+ "AFATFS_CACHE_STATE_WRITING": "3",
+ "AFATFS_CACHE_STATE_DIRTY": "4"
+ },
+ "afatfsClusterSearchCondition_e": {
+ "_source": "../../../src/main/io/asyncfatfs/asyncfatfs.c",
+ "CLUSTER_SEARCH_FREE_AT_BEGINNING_OF_FAT_SECTOR": "0",
+ "CLUSTER_SEARCH_FREE": "1",
+ "CLUSTER_SEARCH_OCCUPIED": "2"
+ },
+ "afatfsDeleteFilePhase_e": {
+ "_source": "../../../src/main/io/asyncfatfs/asyncfatfs.c",
+ "AFATFS_DELETE_FILE_DELETE_DIRECTORY_ENTRY": "0",
+ "AFATFS_DELETE_FILE_DEALLOCATE_CLUSTERS": "1"
+ },
+ "afatfsError_e": {
+ "_source": "../../../src/main/io/asyncfatfs/asyncfatfs.h",
+ "AFATFS_ERROR_NONE": "0",
+ "AFATFS_ERROR_GENERIC": "1",
+ "AFATFS_ERROR_BAD_MBR": "2",
+ "AFATFS_ERROR_BAD_FILESYSTEM_HEADER": "3"
+ },
+ "afatfsExtendSubdirectoryPhase_e": {
+ "_source": "../../../src/main/io/asyncfatfs/asyncfatfs.c",
+ "AFATFS_EXTEND_SUBDIRECTORY_PHASE_INITIAL": "0",
+ "AFATFS_EXTEND_SUBDIRECTORY_PHASE_ADD_FREE_CLUSTER": "0",
+ "AFATFS_EXTEND_SUBDIRECTORY_PHASE_WRITE_SECTORS": "1",
+ "AFATFS_EXTEND_SUBDIRECTORY_PHASE_SUCCESS": "2",
+ "AFATFS_EXTEND_SUBDIRECTORY_PHASE_FAILURE": "3"
+ },
+ "afatfsFATPattern_e": {
+ "_source": "../../../src/main/io/asyncfatfs/asyncfatfs.c",
+ "AFATFS_FAT_PATTERN_UNTERMINATED_CHAIN": "0",
+ "AFATFS_FAT_PATTERN_TERMINATED_CHAIN": "1",
+ "AFATFS_FAT_PATTERN_FREE": "2"
+ },
+ "afatfsFileOperation_e": {
+ "_source": "../../../src/main/io/asyncfatfs/asyncfatfs.c",
+ "AFATFS_FILE_OPERATION_NONE": "0",
+ "AFATFS_FILE_OPERATION_CREATE_FILE": "1",
+ "AFATFS_FILE_OPERATION_SEEK": "2",
+ "AFATFS_FILE_OPERATION_CLOSE": "3",
+ "AFATFS_FILE_OPERATION_TRUNCATE": "4",
+ "AFATFS_FILE_OPERATION_UNLINK": "5",
+ "AFATFS_FILE_OPERATION_APPEND_SUPERCLUSTER": [
+ "(6)",
+ "AFATFS_USE_FREEFILE"
+ ],
+ "AFATFS_FILE_OPERATION_LOCKED": [
+ "(7)",
+ "AFATFS_USE_FREEFILE"
+ ],
+ "AFATFS_FILE_OPERATION_APPEND_FREE_CLUSTER": "8",
+ "AFATFS_FILE_OPERATION_EXTEND_SUBDIRECTORY": "9"
+ },
+ "afatfsFilesystemState_e": {
+ "_source": "../../../src/main/io/asyncfatfs/asyncfatfs.h",
+ "AFATFS_FILESYSTEM_STATE_UNKNOWN": "0",
+ "AFATFS_FILESYSTEM_STATE_FATAL": "1",
+ "AFATFS_FILESYSTEM_STATE_INITIALIZATION": "2",
+ "AFATFS_FILESYSTEM_STATE_READY": "3"
+ },
+ "afatfsFileType_e": {
+ "_source": "../../../src/main/io/asyncfatfs/asyncfatfs.c",
+ "AFATFS_FILE_TYPE_NONE": "0",
+ "AFATFS_FILE_TYPE_NORMAL": "1",
+ "AFATFS_FILE_TYPE_FAT16_ROOT_DIRECTORY": "2",
+ "AFATFS_FILE_TYPE_DIRECTORY": "3"
+ },
+ "afatfsFindClusterStatus_e": {
+ "_source": "../../../src/main/io/asyncfatfs/asyncfatfs.c",
+ "AFATFS_FIND_CLUSTER_IN_PROGRESS": "0",
+ "AFATFS_FIND_CLUSTER_FOUND": "1",
+ "AFATFS_FIND_CLUSTER_FATAL": "2",
+ "AFATFS_FIND_CLUSTER_NOT_FOUND": "3"
+ },
+ "afatfsFreeSpaceSearchPhase_e": {
+ "_source": "../../../src/main/io/asyncfatfs/asyncfatfs.c",
+ "AFATFS_FREE_SPACE_SEARCH_PHASE_FIND_HOLE": "0",
+ "AFATFS_FREE_SPACE_SEARCH_PHASE_GROW_HOLE": "1"
+ },
+ "afatfsInitializationPhase_e": {
+ "_source": "../../../src/main/io/asyncfatfs/asyncfatfs.c",
+ "AFATFS_INITIALIZATION_READ_MBR": "0",
+ "AFATFS_INITIALIZATION_READ_VOLUME_ID": "1",
+ "AFATFS_INITIALIZATION_FREEFILE_CREATE": [
+ "(2)",
+ "AFATFS_USE_FREEFILE"
+ ],
+ "AFATFS_INITIALIZATION_FREEFILE_CREATING": [
+ "(3)",
+ "AFATFS_USE_FREEFILE"
+ ],
+ "AFATFS_INITIALIZATION_FREEFILE_FAT_SEARCH": [
+ "(4)",
+ "AFATFS_USE_FREEFILE"
+ ],
+ "AFATFS_INITIALIZATION_FREEFILE_UPDATE_FAT": [
+ "(5)",
+ "AFATFS_USE_FREEFILE"
+ ],
+ "AFATFS_INITIALIZATION_FREEFILE_SAVE_DIR_ENTRY": [
+ "(6)",
+ "AFATFS_USE_FREEFILE"
+ ],
+ "AFATFS_INITIALIZATION_FREEFILE_LAST": [
+ "AFATFS_INITIALIZATION_FREEFILE_SAVE_DIR_ENTRY",
+ "AFATFS_USE_FREEFILE"
+ ],
+ "AFATFS_INITIALIZATION_DONE": ""
+ },
+ "afatfsOperationStatus_e": {
+ "_source": "../../../src/main/io/asyncfatfs/asyncfatfs.h",
+ "AFATFS_OPERATION_IN_PROGRESS": "0",
+ "AFATFS_OPERATION_SUCCESS": "1",
+ "AFATFS_OPERATION_FAILURE": "2"
+ },
+ "afatfsSaveDirectoryEntryMode_e": {
+ "_source": "../../../src/main/io/asyncfatfs/asyncfatfs.c",
+ "AFATFS_SAVE_DIRECTORY_NORMAL": "0",
+ "AFATFS_SAVE_DIRECTORY_FOR_CLOSE": "1",
+ "AFATFS_SAVE_DIRECTORY_DELETED": "2"
+ },
+ "afatfsSeek_e": {
+ "_source": "../../../src/main/io/asyncfatfs/asyncfatfs.h",
+ "AFATFS_SEEK_SET": "0",
+ "AFATFS_SEEK_CUR": "1",
+ "AFATFS_SEEK_END": "2"
+ },
+ "afatfsTruncateFilePhase_e": {
+ "_source": "../../../src/main/io/asyncfatfs/asyncfatfs.c",
+ "AFATFS_TRUNCATE_FILE_INITIAL": "0",
+ "AFATFS_TRUNCATE_FILE_UPDATE_DIRECTORY": "0",
+ "AFATFS_TRUNCATE_FILE_ERASE_FAT_CHAIN_NORMAL": "1",
+ "AFATFS_TRUNCATE_FILE_ERASE_FAT_CHAIN_CONTIGUOUS": [
+ "(2)",
+ "AFATFS_USE_FREEFILE"
+ ],
+ "AFATFS_TRUNCATE_FILE_PREPEND_TO_FREEFILE": [
+ "(3)",
+ "AFATFS_USE_FREEFILE"
+ ],
+ "AFATFS_TRUNCATE_FILE_SUCCESS": "4"
+ },
+ "airmodeHandlingType_e": {
+ "_source": "../../../src/main/fc/rc_controls.h",
+ "STICK_CENTER": "0",
+ "THROTTLE_THRESHOLD": "1",
+ "STICK_CENTER_ONCE": "2"
+ },
+ "angle_index_t": {
+ "_source": "../../../src/main/common/axis.h",
+ "AI_ROLL": "0",
+ "AI_PITCH": "1"
+ },
+ "armingFlag_e": {
+ "_source": "../../../src/main/fc/runtime_config.h",
+ "ARMED": "(1 << 2)",
+ "WAS_EVER_ARMED": "(1 << 3)",
+ "SIMULATOR_MODE_HITL": "(1 << 4)",
+ "SIMULATOR_MODE_SITL": "(1 << 5)",
+ "ARMING_DISABLED_GEOZONE": "(1 << 6)",
+ "ARMING_DISABLED_FAILSAFE_SYSTEM": "(1 << 7)",
+ "ARMING_DISABLED_NOT_LEVEL": "(1 << 8)",
+ "ARMING_DISABLED_SENSORS_CALIBRATING": "(1 << 9)",
+ "ARMING_DISABLED_SYSTEM_OVERLOADED": "(1 << 10)",
+ "ARMING_DISABLED_NAVIGATION_UNSAFE": "(1 << 11)",
+ "ARMING_DISABLED_COMPASS_NOT_CALIBRATED": "(1 << 12)",
+ "ARMING_DISABLED_ACCELEROMETER_NOT_CALIBRATED": "(1 << 13)",
+ "ARMING_DISABLED_ARM_SWITCH": "(1 << 14)",
+ "ARMING_DISABLED_HARDWARE_FAILURE": "(1 << 15)",
+ "ARMING_DISABLED_BOXFAILSAFE": "(1 << 16)",
+ "ARMING_DISABLED_RC_LINK": "(1 << 18)",
+ "ARMING_DISABLED_THROTTLE": "(1 << 19)",
+ "ARMING_DISABLED_CLI": "(1 << 20)",
+ "ARMING_DISABLED_CMS_MENU": "(1 << 21)",
+ "ARMING_DISABLED_OSD_MENU": "(1 << 22)",
+ "ARMING_DISABLED_ROLLPITCH_NOT_CENTERED": "(1 << 23)",
+ "ARMING_DISABLED_SERVO_AUTOTRIM": "(1 << 24)",
+ "ARMING_DISABLED_OOM": "(1 << 25)",
+ "ARMING_DISABLED_INVALID_SETTING": "(1 << 26)",
+ "ARMING_DISABLED_PWM_OUTPUT_ERROR": "(1 << 27)",
+ "ARMING_DISABLED_NO_PREARM": "(1 << 28)",
+ "ARMING_DISABLED_DSHOT_BEEPER": "(1 << 29)",
+ "ARMING_DISABLED_LANDING_DETECTED": "(1 << 30)",
+ "ARMING_DISABLED_ALL_FLAGS": "(ARMING_DISABLED_GEOZONE | ARMING_DISABLED_FAILSAFE_SYSTEM | ARMING_DISABLED_NOT_LEVEL | ARMING_DISABLED_SENSORS_CALIBRATING | ARMING_DISABLED_SYSTEM_OVERLOADED | ARMING_DISABLED_NAVIGATION_UNSAFE | ARMING_DISABLED_COMPASS_NOT_CALIBRATED | ARMING_DISABLED_ACCELEROMETER_NOT_CALIBRATED | ARMING_DISABLED_ARM_SWITCH | ARMING_DISABLED_HARDWARE_FAILURE | ARMING_DISABLED_BOXFAILSAFE | ARMING_DISABLED_RC_LINK | ARMING_DISABLED_THROTTLE | ARMING_DISABLED_CLI | ARMING_DISABLED_CMS_MENU | ARMING_DISABLED_OSD_MENU | ARMING_DISABLED_ROLLPITCH_NOT_CENTERED | ARMING_DISABLED_SERVO_AUTOTRIM | ARMING_DISABLED_OOM | ARMING_DISABLED_INVALID_SETTING | ARMING_DISABLED_PWM_OUTPUT_ERROR | ARMING_DISABLED_NO_PREARM | ARMING_DISABLED_DSHOT_BEEPER | ARMING_DISABLED_LANDING_DETECTED)"
+ },
+ "axis_e": {
+ "_source": "../../../src/main/common/axis.h",
+ "X": "0",
+ "Y": "1",
+ "Z": "2"
+ },
+ "barometerState_e": {
+ "_source": "../../../src/main/sensors/barometer.c",
+ "BAROMETER_NEEDS_SAMPLES": "0",
+ "BAROMETER_NEEDS_CALCULATION": "1"
+ },
+ "baroSensor_e": {
+ "_source": "../../../src/main/sensors/barometer.h",
+ "BARO_NONE": "0",
+ "BARO_AUTODETECT": "1",
+ "BARO_BMP085": "2",
+ "BARO_MS5611": "3",
+ "BARO_BMP280": "4",
+ "BARO_MS5607": "5",
+ "BARO_LPS25H": "6",
+ "BARO_SPL06": "7",
+ "BARO_BMP388": "8",
+ "BARO_DPS310": "9",
+ "BARO_B2SMPB": "10",
+ "BARO_MSP": "11",
+ "BARO_FAKE": "12",
+ "BARO_MAX": "BARO_FAKE"
+ },
+ "batCapacityUnit_e": {
+ "_source": "../../../src/main/sensors/battery_config_structs.h",
+ "BAT_CAPACITY_UNIT_MAH": "0",
+ "BAT_CAPACITY_UNIT_MWH": "1"
+ },
+ "batteryState_e": {
+ "_source": "../../../src/main/sensors/battery.h",
+ "BATTERY_OK": "0",
+ "BATTERY_WARNING": "1",
+ "BATTERY_CRITICAL": "2",
+ "BATTERY_NOT_PRESENT": "3"
+ },
+ "batVoltageSource_e": {
+ "_source": "../../../src/main/sensors/battery_config_structs.h",
+ "BAT_VOLTAGE_RAW": "0",
+ "BAT_VOLTAGE_SAG_COMP": "1"
+ },
+ "baudRate_e": {
+ "_source": "../../../src/main/io/serial.h",
+ "BAUD_AUTO": "0",
+ "BAUD_1200": "1",
+ "BAUD_2400": "2",
+ "BAUD_4800": "3",
+ "BAUD_9600": "4",
+ "BAUD_19200": "5",
+ "BAUD_38400": "6",
+ "BAUD_57600": "7",
+ "BAUD_115200": "8",
+ "BAUD_230400": "9",
+ "BAUD_250000": "10",
+ "BAUD_460800": "11",
+ "BAUD_921600": "12",
+ "BAUD_1000000": "13",
+ "BAUD_1500000": "14",
+ "BAUD_2000000": "15",
+ "BAUD_2470000": "16",
+ "BAUD_MIN": "BAUD_AUTO",
+ "BAUD_MAX": "BAUD_2470000"
+ },
+ "beeperMode_e": {
+ "_source": "../../../src/main/io/beeper.h",
+ "BEEPER_SILENCE": "0",
+ "BEEPER_RUNTIME_CALIBRATION_DONE": "1",
+ "BEEPER_HARDWARE_FAILURE": "2",
+ "BEEPER_RX_LOST": "3",
+ "BEEPER_RX_LOST_LANDING": "4",
+ "BEEPER_DISARMING": "5",
+ "BEEPER_ARMING": "6",
+ "BEEPER_ARMING_GPS_FIX": "7",
+ "BEEPER_BAT_CRIT_LOW": "8",
+ "BEEPER_BAT_LOW": "9",
+ "BEEPER_GPS_STATUS": "10",
+ "BEEPER_RX_SET": "11",
+ "BEEPER_ACTION_SUCCESS": "12",
+ "BEEPER_ACTION_FAIL": "13",
+ "BEEPER_READY_BEEP": "14",
+ "BEEPER_MULTI_BEEPS": "15",
+ "BEEPER_DISARM_REPEAT": "16",
+ "BEEPER_ARMED": "17",
+ "BEEPER_SYSTEM_INIT": "18",
+ "BEEPER_USB": "19",
+ "BEEPER_LAUNCH_MODE_ENABLED": "20",
+ "BEEPER_LAUNCH_MODE_LOW_THROTTLE": "21",
+ "BEEPER_LAUNCH_MODE_IDLE_START": "22",
+ "BEEPER_CAM_CONNECTION_OPEN": "23",
+ "BEEPER_CAM_CONNECTION_CLOSE": "24",
+ "BEEPER_ALL": "25",
+ "BEEPER_PREFERENCE": "26"
+ },
+ "biquadFilterType_e": {
+ "_source": "../../../src/main/common/filter.h",
+ "FILTER_LPF": "0",
+ "FILTER_NOTCH": "1"
+ },
+ "blackboxBufferReserveStatus_e": {
+ "_source": "../../../src/main/blackbox/blackbox_io.h",
+ "BLACKBOX_RESERVE_SUCCESS": "0",
+ "BLACKBOX_RESERVE_TEMPORARY_FAILURE": "1",
+ "BLACKBOX_RESERVE_PERMANENT_FAILURE": "2"
+ },
+ "blackboxFeatureMask_e": {
+ "_source": "../../../src/main/blackbox/blackbox.h",
+ "BLACKBOX_FEATURE_NAV_ACC": "1 << 0",
+ "BLACKBOX_FEATURE_NAV_POS": "1 << 1",
+ "BLACKBOX_FEATURE_NAV_PID": "1 << 2",
+ "BLACKBOX_FEATURE_MAG": "1 << 3",
+ "BLACKBOX_FEATURE_ACC": "1 << 4",
+ "BLACKBOX_FEATURE_ATTITUDE": "1 << 5",
+ "BLACKBOX_FEATURE_RC_DATA": "1 << 6",
+ "BLACKBOX_FEATURE_RC_COMMAND": "1 << 7",
+ "BLACKBOX_FEATURE_MOTORS": "1 << 8",
+ "BLACKBOX_FEATURE_GYRO_RAW": "1 << 9",
+ "BLACKBOX_FEATURE_GYRO_PEAKS_ROLL": "1 << 10",
+ "BLACKBOX_FEATURE_GYRO_PEAKS_PITCH": "1 << 11",
+ "BLACKBOX_FEATURE_GYRO_PEAKS_YAW": "1 << 12",
+ "BLACKBOX_FEATURE_SERVOS": "1 << 13"
+ },
+ "bmi270Register_e": {
+ "_source": "../../../src/main/drivers/accgyro/accgyro_bmi270.c",
+ "BMI270_REG_CHIP_ID": "0",
+ "BMI270_REG_ERR_REG": "2",
+ "BMI270_REG_STATUS": "3",
+ "BMI270_REG_ACC_DATA_X_LSB": "12",
+ "BMI270_REG_GYR_DATA_X_LSB": "18",
+ "BMI270_REG_SENSORTIME_0": "24",
+ "BMI270_REG_SENSORTIME_1": "25",
+ "BMI270_REG_SENSORTIME_2": "26",
+ "BMI270_REG_EVENT": "27",
+ "BMI270_REG_INT_STATUS_0": "28",
+ "BMI270_REG_INT_STATUS_1": "29",
+ "BMI270_REG_INTERNAL_STATUS": "33",
+ "BMI270_REG_TEMPERATURE_LSB": "34",
+ "BMI270_REG_TEMPERATURE_MSB": "35",
+ "BMI270_REG_FIFO_LENGTH_LSB": "36",
+ "BMI270_REG_FIFO_LENGTH_MSB": "37",
+ "BMI270_REG_FIFO_DATA": "38",
+ "BMI270_REG_ACC_CONF": "64",
+ "BMI270_REG_ACC_RANGE": "65",
+ "BMI270_REG_GYRO_CONF": "66",
+ "BMI270_REG_GYRO_RANGE": "67",
+ "BMI270_REG_AUX_CONF": "68",
+ "BMI270_REG_FIFO_DOWNS": "69",
+ "BMI270_REG_FIFO_WTM_0": "70",
+ "BMI270_REG_FIFO_WTM_1": "71",
+ "BMI270_REG_FIFO_CONFIG_0": "72",
+ "BMI270_REG_FIFO_CONFIG_1": "73",
+ "BMI270_REG_SATURATION": "74",
+ "BMI270_REG_INT1_IO_CTRL": "83",
+ "BMI270_REG_INT2_IO_CTRL": "84",
+ "BMI270_REG_INT_LATCH": "85",
+ "BMI270_REG_INT1_MAP_FEAT": "86",
+ "BMI270_REG_INT2_MAP_FEAT": "87",
+ "BMI270_REG_INT_MAP_DATA": "88",
+ "BMI270_REG_INIT_CTRL": "89",
+ "BMI270_REG_INIT_DATA": "94",
+ "BMI270_REG_ACC_SELF_TEST": "109",
+ "BMI270_REG_GYR_SELF_TEST_AXES": "110",
+ "BMI270_REG_PWR_CONF": "124",
+ "BMI270_REG_PWR_CTRL": "125",
+ "BMI270_REG_CMD": "126"
+ },
+ "bootLogEventCode_e": {
+ "_source": "../../../src/main/drivers/logging_codes.h",
+ "BOOT_EVENT_CONFIG_LOADED": "0",
+ "BOOT_EVENT_SYSTEM_INIT_DONE": "1",
+ "BOOT_EVENT_PWM_INIT_DONE": "2",
+ "BOOT_EVENT_EXTRA_BOOT_DELAY": "3",
+ "BOOT_EVENT_SENSOR_INIT_DONE": "4",
+ "BOOT_EVENT_GPS_INIT_DONE": "5",
+ "BOOT_EVENT_LEDSTRIP_INIT_DONE": "6",
+ "BOOT_EVENT_TELEMETRY_INIT_DONE": "7",
+ "BOOT_EVENT_SYSTEM_READY": "8",
+ "BOOT_EVENT_GYRO_DETECTION": "9",
+ "BOOT_EVENT_ACC_DETECTION": "10",
+ "BOOT_EVENT_BARO_DETECTION": "11",
+ "BOOT_EVENT_MAG_DETECTION": "12",
+ "BOOT_EVENT_RANGEFINDER_DETECTION": "13",
+ "BOOT_EVENT_MAG_INIT_FAILED": "14",
+ "BOOT_EVENT_HMC5883L_READ_OK_COUNT": "15",
+ "BOOT_EVENT_HMC5883L_READ_FAILED": "16",
+ "BOOT_EVENT_HMC5883L_SATURATION": "17",
+ "BOOT_EVENT_TIMER_CH_SKIPPED": "18",
+ "BOOT_EVENT_TIMER_CH_MAPPED": "19",
+ "BOOT_EVENT_PITOT_DETECTION": "20",
+ "BOOT_EVENT_TEMP_SENSOR_DETECTION": "21",
+ "BOOT_EVENT_1WIRE_DETECTION": "22",
+ "BOOT_EVENT_HARDWARE_IO_CONFLICT": "23",
+ "BOOT_EVENT_OPFLOW_DETECTION": "24",
+ "BOOT_EVENT_CODE_COUNT": "25"
+ },
+ "bootLogFlags_e": {
+ "_source": "../../../src/main/drivers/logging_codes.h",
+ "BOOT_EVENT_FLAGS_NONE": "0",
+ "BOOT_EVENT_FLAGS_WARNING": "1 << 0",
+ "BOOT_EVENT_FLAGS_ERROR": "1 << 1",
+ "BOOT_EVENT_FLAGS_PARAM16": "1 << 14",
+ "BOOT_EVENT_FLAGS_PARAM32": "1 << 15"
+ },
+ "boxId_e": {
+ "_source": "../../../src/main/fc/rc_modes.h",
+ "BOXARM": "0",
+ "BOXANGLE": "1",
+ "BOXHORIZON": "2",
+ "BOXNAVALTHOLD": "3",
+ "BOXHEADINGHOLD": "4",
+ "BOXHEADFREE": "5",
+ "BOXHEADADJ": "6",
+ "BOXCAMSTAB": "7",
+ "BOXNAVRTH": "8",
+ "BOXNAVPOSHOLD": "9",
+ "BOXMANUAL": "10",
+ "BOXBEEPERON": "11",
+ "BOXLEDLOW": "12",
+ "BOXLIGHTS": "13",
+ "BOXNAVLAUNCH": "14",
+ "BOXOSD": "15",
+ "BOXTELEMETRY": "16",
+ "BOXBLACKBOX": "17",
+ "BOXFAILSAFE": "18",
+ "BOXNAVWP": "19",
+ "BOXAIRMODE": "20",
+ "BOXHOMERESET": "21",
+ "BOXGCSNAV": "22",
+ "BOXSURFACE": "24",
+ "BOXFLAPERON": "25",
+ "BOXTURNASSIST": "26",
+ "BOXAUTOTRIM": "27",
+ "BOXAUTOTUNE": "28",
+ "BOXCAMERA1": "29",
+ "BOXCAMERA2": "30",
+ "BOXCAMERA3": "31",
+ "BOXOSDALT1": "32",
+ "BOXOSDALT2": "33",
+ "BOXOSDALT3": "34",
+ "BOXNAVCOURSEHOLD": "35",
+ "BOXBRAKING": "36",
+ "BOXUSER1": "37",
+ "BOXUSER2": "38",
+ "BOXFPVANGLEMIX": "39",
+ "BOXLOITERDIRCHN": "40",
+ "BOXMSPRCOVERRIDE": "41",
+ "BOXPREARM": "42",
+ "BOXTURTLE": "43",
+ "BOXNAVCRUISE": "44",
+ "BOXAUTOLEVEL": "45",
+ "BOXPLANWPMISSION": "46",
+ "BOXSOARING": "47",
+ "BOXUSER3": "48",
+ "BOXUSER4": "49",
+ "BOXCHANGEMISSION": "50",
+ "BOXBEEPERMUTE": "51",
+ "BOXMULTIFUNCTION": "52",
+ "BOXMIXERPROFILE": "53",
+ "BOXMIXERTRANSITION": "54",
+ "BOXANGLEHOLD": "55",
+ "BOXGIMBALTLOCK": "56",
+ "BOXGIMBALRLOCK": "57",
+ "BOXGIMBALCENTER": "58",
+ "BOXGIMBALHTRK": "59",
+ "CHECKBOX_ITEM_COUNT": "60"
+ },
+ "busIndex_e": {
+ "_source": "../../../src/main/drivers/bus.h",
+ "BUSINDEX_1": "0",
+ "BUSINDEX_2": "1",
+ "BUSINDEX_3": "2",
+ "BUSINDEX_4": "3"
+ },
+ "busSpeed_e": {
+ "_source": "../../../src/main/drivers/bus.h",
+ "BUS_SPEED_INITIALIZATION": "0",
+ "BUS_SPEED_SLOW": "1",
+ "BUS_SPEED_STANDARD": "2",
+ "BUS_SPEED_FAST": "3",
+ "BUS_SPEED_ULTRAFAST": "4"
+ },
+ "busType_e": {
+ "_source": "../../../src/main/drivers/bus.h",
+ "BUSTYPE_ANY": "0",
+ "BUSTYPE_NONE": "0",
+ "BUSTYPE_I2C": "1",
+ "BUSTYPE_SPI": "2",
+ "BUSTYPE_SDIO": "3"
+ },
+ "channelType_t": {
+ "_source": "../../../src/main/drivers/timer.h",
+ "TYPE_FREE": "0",
+ "TYPE_PWMINPUT": "1",
+ "TYPE_PPMINPUT": "2",
+ "TYPE_PWMOUTPUT_MOTOR": "3",
+ "TYPE_PWMOUTPUT_FAST": "4",
+ "TYPE_PWMOUTPUT_SERVO": "5",
+ "TYPE_SOFTSERIAL_RX": "6",
+ "TYPE_SOFTSERIAL_TX": "7",
+ "TYPE_SOFTSERIAL_RXTX": "8",
+ "TYPE_SOFTSERIAL_AUXTIMER": "9",
+ "TYPE_ADC": "10",
+ "TYPE_SERIAL_RX": "11",
+ "TYPE_SERIAL_TX": "12",
+ "TYPE_SERIAL_RXTX": "13",
+ "TYPE_TIMER": "14"
+ },
+ "climbRateToAltitudeControllerMode_e": {
+ "_source": "../../../src/main/navigation/navigation_private.h",
+ "ROC_TO_ALT_CURRENT": "0",
+ "ROC_TO_ALT_CONSTANT": "1",
+ "ROC_TO_ALT_TARGET": "2"
+ },
+ "colorComponent_e": {
+ "_source": "../../../src/main/common/color.h",
+ "RGB_RED": "0",
+ "RGB_GREEN": "1",
+ "RGB_BLUE": "2"
+ },
+ "colorId_e": {
+ "_source": "../../../src/main/io/ledstrip.h",
+ "COLOR_BLACK": "0",
+ "COLOR_WHITE": "1",
+ "COLOR_RED": "2",
+ "COLOR_ORANGE": "3",
+ "COLOR_YELLOW": "4",
+ "COLOR_LIME_GREEN": "5",
+ "COLOR_GREEN": "6",
+ "COLOR_MINT_GREEN": "7",
+ "COLOR_CYAN": "8",
+ "COLOR_LIGHT_BLUE": "9",
+ "COLOR_BLUE": "10",
+ "COLOR_DARK_VIOLET": "11",
+ "COLOR_MAGENTA": "12",
+ "COLOR_DEEP_PINK": "13"
+ },
+ "crsfActiveAntenna_e": {
+ "_source": "../../../src/main/telemetry/crsf.c",
+ "CRSF_ACTIVE_ANTENNA1": "0",
+ "CRSF_ACTIVE_ANTENNA2": "1"
+ },
+ "crsfAddress_e": {
+ "_source": "../../../src/main/rx/crsf.h",
+ "CRSF_ADDRESS_BROADCAST": "0",
+ "CRSF_ADDRESS_USB": "16",
+ "CRSF_ADDRESS_TBS_CORE_PNP_PRO": "128",
+ "CRSF_ADDRESS_RESERVED1": "138",
+ "CRSF_ADDRESS_CURRENT_SENSOR": "192",
+ "CRSF_ADDRESS_GPS": "194",
+ "CRSF_ADDRESS_TBS_BLACKBOX": "196",
+ "CRSF_ADDRESS_FLIGHT_CONTROLLER": "200",
+ "CRSF_ADDRESS_RESERVED2": "202",
+ "CRSF_ADDRESS_RACE_TAG": "204",
+ "CRSF_ADDRESS_RADIO_TRANSMITTER": "234",
+ "CRSF_ADDRESS_CRSF_RECEIVER": "236",
+ "CRSF_ADDRESS_CRSF_TRANSMITTER": "238"
+ },
+ "crsfFrameType_e": {
+ "_source": "../../../src/main/rx/crsf.h",
+ "CRSF_FRAMETYPE_GPS": "2",
+ "CRSF_FRAMETYPE_VARIO_SENSOR": "7",
+ "CRSF_FRAMETYPE_BATTERY_SENSOR": "8",
+ "CRSF_FRAMETYPE_BAROMETER_ALTITUDE": "9",
+ "CRSF_FRAMETYPE_LINK_STATISTICS": "20",
+ "CRSF_FRAMETYPE_RC_CHANNELS_PACKED": "22",
+ "CRSF_FRAMETYPE_ATTITUDE": "30",
+ "CRSF_FRAMETYPE_FLIGHT_MODE": "33",
+ "CRSF_FRAMETYPE_DEVICE_PING": "40",
+ "CRSF_FRAMETYPE_DEVICE_INFO": "41",
+ "CRSF_FRAMETYPE_PARAMETER_SETTINGS_ENTRY": "43",
+ "CRSF_FRAMETYPE_PARAMETER_READ": "44",
+ "CRSF_FRAMETYPE_PARAMETER_WRITE": "45",
+ "CRSF_FRAMETYPE_COMMAND": "50",
+ "CRSF_FRAMETYPE_MSP_REQ": "122",
+ "CRSF_FRAMETYPE_MSP_RESP": "123",
+ "CRSF_FRAMETYPE_MSP_WRITE": "124",
+ "CRSF_FRAMETYPE_DISPLAYPORT_CMD": "125"
+ },
+ "crsfFrameTypeIndex_e": {
+ "_source": "../../../src/main/telemetry/crsf.c",
+ "CRSF_FRAME_START_INDEX": "0",
+ "CRSF_FRAME_ATTITUDE_INDEX": "CRSF_FRAME_START_INDEX",
+ "CRSF_FRAME_BATTERY_SENSOR_INDEX": "",
+ "CRSF_FRAME_FLIGHT_MODE_INDEX": "",
+ "CRSF_FRAME_GPS_INDEX": "",
+ "CRSF_FRAME_VARIO_SENSOR_INDEX": "",
+ "CRSF_FRAME_BAROMETER_ALTITUDE_INDEX": "",
+ "CRSF_SCHEDULE_COUNT_MAX": ""
+ },
+ "crsrRfMode_e": {
+ "_source": "../../../src/main/telemetry/crsf.c",
+ "CRSF_RF_MODE_4_HZ": "0",
+ "CRSF_RF_MODE_50_HZ": "1",
+ "CRSF_RF_MODE_150_HZ": "2"
+ },
+ "crsrRfPower_e": {
+ "_source": "../../../src/main/telemetry/crsf.c",
+ "CRSF_RF_POWER_0_mW": "0",
+ "CRSF_RF_POWER_10_mW": "1",
+ "CRSF_RF_POWER_25_mW": "2",
+ "CRSF_RF_POWER_100_mW": "3",
+ "CRSF_RF_POWER_500_mW": "4",
+ "CRSF_RF_POWER_1000_mW": "5",
+ "CRSF_RF_POWER_2000_mW": "6",
+ "CRSF_RF_POWER_250_mW": "7"
+ },
+ "currentSensor_e": {
+ "_source": "../../../src/main/sensors/battery_config_structs.h",
+ "CURRENT_SENSOR_NONE": "0",
+ "CURRENT_SENSOR_ADC": "1",
+ "CURRENT_SENSOR_VIRTUAL": "2",
+ "CURRENT_SENSOR_FAKE": "3",
+ "CURRENT_SENSOR_ESC": "4",
+ "CURRENT_SENSOR_SMARTPORT": "5",
+ "CURRENT_SENSOR_MAX": "CURRENT_SENSOR_SMARTPORT"
+ },
+ "devHardwareType_e": {
+ "_source": "../../../src/main/drivers/bus.h",
+ "DEVHW_NONE": "0",
+ "DEVHW_MPU6000": "1",
+ "DEVHW_MPU6500": "2",
+ "DEVHW_BMI160": "3",
+ "DEVHW_BMI088_GYRO": "4",
+ "DEVHW_BMI088_ACC": "5",
+ "DEVHW_ICM20689": "6",
+ "DEVHW_ICM42605": "7",
+ "DEVHW_BMI270": "8",
+ "DEVHW_LSM6D": "9",
+ "DEVHW_MPU9250": "10",
+ "DEVHW_BMP085": "11",
+ "DEVHW_BMP280": "12",
+ "DEVHW_MS5611": "13",
+ "DEVHW_MS5607": "14",
+ "DEVHW_LPS25H": "15",
+ "DEVHW_SPL06": "16",
+ "DEVHW_BMP388": "17",
+ "DEVHW_DPS310": "18",
+ "DEVHW_B2SMPB": "19",
+ "DEVHW_HMC5883": "20",
+ "DEVHW_AK8963": "21",
+ "DEVHW_AK8975": "22",
+ "DEVHW_IST8310_0": "23",
+ "DEVHW_IST8310_1": "24",
+ "DEVHW_IST8308": "25",
+ "DEVHW_QMC5883": "26",
+ "DEVHW_QMC5883P": "27",
+ "DEVHW_MAG3110": "28",
+ "DEVHW_LIS3MDL": "29",
+ "DEVHW_RM3100": "30",
+ "DEVHW_VCM5883": "31",
+ "DEVHW_MLX90393": "32",
+ "DEVHW_LM75_0": "33",
+ "DEVHW_LM75_1": "34",
+ "DEVHW_LM75_2": "35",
+ "DEVHW_LM75_3": "36",
+ "DEVHW_LM75_4": "37",
+ "DEVHW_LM75_5": "38",
+ "DEVHW_LM75_6": "39",
+ "DEVHW_LM75_7": "40",
+ "DEVHW_DS2482": "41",
+ "DEVHW_MAX7456": "42",
+ "DEVHW_SRF10": "43",
+ "DEVHW_VL53L0X": "44",
+ "DEVHW_VL53L1X": "45",
+ "DEVHW_US42": "46",
+ "DEVHW_TOF10120_I2C": "47",
+ "DEVHW_TERARANGER_EVO_I2C": "48",
+ "DEVHW_MS4525": "49",
+ "DEVHW_DLVR": "50",
+ "DEVHW_M25P16": "51",
+ "DEVHW_W25N": "52",
+ "DEVHW_UG2864": "53",
+ "DEVHW_SDCARD": "54",
+ "DEVHW_IRLOCK": "55",
+ "DEVHW_PCF8574": "56"
+ },
+ "deviceFlags_e": {
+ "_source": "../../../src/main/drivers/bus.h",
+ "DEVFLAGS_NONE": "0",
+ "DEVFLAGS_USE_RAW_REGISTERS": "(1 << 0)",
+ "DEVFLAGS_USE_MANUAL_DEVICE_SELECT": "(1 << 1)",
+ "DEVFLAGS_SPI_MODE_0": "(1 << 2)"
+ },
+ "displayCanvasBitmapOption_t": {
+ "_source": "../../../src/main/drivers/display_canvas.h",
+ "DISPLAY_CANVAS_BITMAP_OPT_INVERT_COLORS": "1 << 0",
+ "DISPLAY_CANVAS_BITMAP_OPT_SOLID_BACKGROUND": "1 << 1",
+ "DISPLAY_CANVAS_BITMAP_OPT_ERASE_TRANSPARENT": "1 << 2"
+ },
+ "displayCanvasColor_e": {
+ "_source": "../../../src/main/drivers/display_canvas.h",
+ "DISPLAY_CANVAS_COLOR_BLACK": "0",
+ "DISPLAY_CANVAS_COLOR_TRANSPARENT": "1",
+ "DISPLAY_CANVAS_COLOR_WHITE": "2",
+ "DISPLAY_CANVAS_COLOR_GRAY": "3"
+ },
+ "displayCanvasOutlineType_e": {
+ "_source": "../../../src/main/drivers/display_canvas.h",
+ "DISPLAY_CANVAS_OUTLINE_TYPE_NONE": "0",
+ "DISPLAY_CANVAS_OUTLINE_TYPE_TOP": "1 << 0",
+ "DISPLAY_CANVAS_OUTLINE_TYPE_RIGHT": "1 << 1",
+ "DISPLAY_CANVAS_OUTLINE_TYPE_BOTTOM": "1 << 2",
+ "DISPLAY_CANVAS_OUTLINE_TYPE_LEFT": "1 << 3"
+ },
+ "displayportMspCommand_e": {
+ "_source": "../../../src/main/io/displayport_msp.h",
+ "MSP_DP_HEARTBEAT": "0",
+ "MSP_DP_RELEASE": "1",
+ "MSP_DP_CLEAR_SCREEN": "2",
+ "MSP_DP_WRITE_STRING": "3",
+ "MSP_DP_DRAW_SCREEN": "4",
+ "MSP_DP_OPTIONS": "5",
+ "MSP_DP_SYS": "6",
+ "MSP_DP_COUNT": "7"
+ },
+ "displayTransactionOption_e": {
+ "_source": "../../../src/main/drivers/display.h",
+ "DISPLAY_TRANSACTION_OPT_NONE": "0",
+ "DISPLAY_TRANSACTION_OPT_PROFILED": "1 << 0",
+ "DISPLAY_TRANSACTION_OPT_RESET_DRAWING": "1 << 1"
+ },
+ "displayWidgetType_e": {
+ "_source": "../../../src/main/drivers/display_widgets.h",
+ "DISPLAY_WIDGET_TYPE_AHI": "0",
+ "DISPLAY_WIDGET_TYPE_SIDEBAR": "1"
+ },
+ "DjiCraftNameElements_t": {
+ "_source": "../../../src/main/io/osd_dji_hd.c",
+ "DJI_OSD_CN_MESSAGES": "0",
+ "DJI_OSD_CN_THROTTLE": "1",
+ "DJI_OSD_CN_THROTTLE_AUTO_THR": "2",
+ "DJI_OSD_CN_AIR_SPEED": "3",
+ "DJI_OSD_CN_EFFICIENCY": "4",
+ "DJI_OSD_CN_DISTANCE": "5",
+ "DJI_OSD_CN_ADJUSTEMNTS": "6",
+ "DJI_OSD_CN_MAX_ELEMENTS": "7"
+ },
+ "dshotCommands_e": {
+ "_source": "../../../src/main/drivers/pwm_output.h",
+ "DSHOT_CMD_SPIN_DIRECTION_NORMAL": "20",
+ "DSHOT_CMD_SPIN_DIRECTION_REVERSED": "21"
+ },
+ "dumpFlags_e": {
+ "_source": "../../../src/main/fc/cli.c",
+ "DUMP_MASTER": "(1 << 0)",
+ "DUMP_CONTROL_PROFILE": "(1 << 1)",
+ "DUMP_BATTERY_PROFILE": "(1 << 2)",
+ "DUMP_MIXER_PROFILE": "(1 << 3)",
+ "DUMP_ALL": "(1 << 4)",
+ "DO_DIFF": "(1 << 5)",
+ "SHOW_DEFAULTS": "(1 << 6)",
+ "HIDE_UNUSED": "(1 << 7)"
+ },
+ "dynamicGyroNotchMode_e": {
+ "_source": "../../../src/main/sensors/gyro.h",
+ "DYNAMIC_NOTCH_MODE_2D": "0",
+ "DYNAMIC_NOTCH_MODE_3D": "1"
+ },
+ "emergLandState_e": {
+ "_source": "../../../src/main/flight/failsafe.h",
+ "EMERG_LAND_IDLE": "0",
+ "EMERG_LAND_IN_PROGRESS": "1",
+ "EMERG_LAND_HAS_LANDED": "2"
+ },
+ "escSensorFrameStatus_t": {
+ "_source": "../../../src/main/sensors/esc_sensor.c",
+ "ESC_SENSOR_FRAME_PENDING": "0",
+ "ESC_SENSOR_FRAME_COMPLETE": "1",
+ "ESC_SENSOR_FRAME_FAILED": "2"
+ },
+ "escSensorState_t": {
+ "_source": "../../../src/main/sensors/esc_sensor.c",
+ "ESC_SENSOR_WAIT_STARTUP": "0",
+ "ESC_SENSOR_READY": "1",
+ "ESC_SENSOR_WAITING": "2"
+ },
+ "failsafeChannelBehavior_e": {
+ "_source": "../../../src/main/flight/failsafe.c",
+ "FAILSAFE_CHANNEL_HOLD": "0",
+ "FAILSAFE_CHANNEL_NEUTRAL": "1"
+ },
+ "failsafePhase_e": {
+ "_source": "../../../src/main/flight/failsafe.h",
+ "FAILSAFE_IDLE": "0",
+ "FAILSAFE_RX_LOSS_DETECTED": "1",
+ "FAILSAFE_RX_LOSS_IDLE": "2",
+ "FAILSAFE_RETURN_TO_HOME": "3",
+ "FAILSAFE_LANDING": "4",
+ "FAILSAFE_LANDED": "5",
+ "FAILSAFE_RX_LOSS_MONITORING": "6",
+ "FAILSAFE_RX_LOSS_RECOVERED": "7"
+ },
+ "failsafeProcedure_e": {
+ "_source": "../../../src/main/flight/failsafe.h",
+ "FAILSAFE_PROCEDURE_AUTO_LANDING": "0",
+ "FAILSAFE_PROCEDURE_DROP_IT": "1",
+ "FAILSAFE_PROCEDURE_RTH": "2",
+ "FAILSAFE_PROCEDURE_NONE": "3"
+ },
+ "failsafeRxLinkState_e": {
+ "_source": "../../../src/main/flight/failsafe.h",
+ "FAILSAFE_RXLINK_DOWN": "0",
+ "FAILSAFE_RXLINK_UP": "1"
+ },
+ "failureMode_e": {
+ "_source": "../../../src/main/drivers/system.h",
+ "FAILURE_DEVELOPER": "0",
+ "FAILURE_MISSING_ACC": "1",
+ "FAILURE_ACC_INIT": "2",
+ "FAILURE_ACC_INCOMPATIBLE": "3",
+ "FAILURE_INVALID_EEPROM_CONTENTS": "4",
+ "FAILURE_FLASH_WRITE_FAILED": "5",
+ "FAILURE_GYRO_INIT_FAILED": "6",
+ "FAILURE_FLASH_READ_FAILED": "7"
+ },
+ "fatFilesystemType_e": {
+ "_source": "../../../src/main/io/asyncfatfs/fat_standard.h",
+ "FAT_FILESYSTEM_TYPE_INVALID": "0",
+ "FAT_FILESYSTEM_TYPE_FAT12": "1",
+ "FAT_FILESYSTEM_TYPE_FAT16": "2",
+ "FAT_FILESYSTEM_TYPE_FAT32": "3"
+ },
+ "features_e": {
+ "_source": "../../../src/main/fc/config.h",
+ "FEATURE_THR_VBAT_COMP": "1 << 0",
+ "FEATURE_VBAT": "1 << 1",
+ "FEATURE_TX_PROF_SEL": "1 << 2",
+ "FEATURE_BAT_PROFILE_AUTOSWITCH": "1 << 3",
+ "FEATURE_GEOZONE": "1 << 4",
+ "FEATURE_UNUSED_1": "1 << 5",
+ "FEATURE_SOFTSERIAL": "1 << 6",
+ "FEATURE_GPS": "1 << 7",
+ "FEATURE_UNUSED_3": "1 << 8",
+ "FEATURE_UNUSED_4": "1 << 9",
+ "FEATURE_TELEMETRY": "1 << 10",
+ "FEATURE_CURRENT_METER": "1 << 11",
+ "FEATURE_REVERSIBLE_MOTORS": "1 << 12",
+ "FEATURE_UNUSED_5": "1 << 13",
+ "FEATURE_UNUSED_6": "1 << 14",
+ "FEATURE_RSSI_ADC": "1 << 15",
+ "FEATURE_LED_STRIP": "1 << 16",
+ "FEATURE_DASHBOARD": "1 << 17",
+ "FEATURE_UNUSED_7": "1 << 18",
+ "FEATURE_BLACKBOX": "1 << 19",
+ "FEATURE_UNUSED_10": "1 << 20",
+ "FEATURE_TRANSPONDER": "1 << 21",
+ "FEATURE_AIRMODE": "1 << 22",
+ "FEATURE_SUPEREXPO_RATES": "1 << 23",
+ "FEATURE_VTX": "1 << 24",
+ "FEATURE_UNUSED_8": "1 << 25",
+ "FEATURE_UNUSED_9": "1 << 26",
+ "FEATURE_UNUSED_11": "1 << 27",
+ "FEATURE_PWM_OUTPUT_ENABLE": "1 << 28",
+ "FEATURE_OSD": "1 << 29",
+ "FEATURE_FW_LAUNCH": "1 << 30",
+ "FEATURE_FW_AUTOTRIM": "1 << 31"
+ },
+ "filterType_e": {
+ "_source": "../../../src/main/common/filter.h",
+ "FILTER_PT1": "0",
+ "FILTER_BIQUAD": "1",
+ "FILTER_PT2": "2",
+ "FILTER_PT3": "3",
+ "FILTER_LULU": "4"
+ },
+ "fixedWingLaunchEvent_t": {
+ "_source": "../../../src/main/navigation/navigation_fw_launch.c",
+ "FW_LAUNCH_EVENT_NONE": "0",
+ "FW_LAUNCH_EVENT_SUCCESS": "1",
+ "FW_LAUNCH_EVENT_GOTO_DETECTION": "2",
+ "FW_LAUNCH_EVENT_ABORT": "3",
+ "FW_LAUNCH_EVENT_THROTTLE_LOW": "4",
+ "FW_LAUNCH_EVENT_COUNT": "5"
+ },
+ "fixedWingLaunchMessage_t": {
+ "_source": "../../../src/main/navigation/navigation_fw_launch.c",
+ "FW_LAUNCH_MESSAGE_TYPE_NONE": "0",
+ "FW_LAUNCH_MESSAGE_TYPE_WAIT_THROTTLE": "1",
+ "FW_LAUNCH_MESSAGE_TYPE_WAIT_IDLE": "2",
+ "FW_LAUNCH_MESSAGE_TYPE_WAIT_DETECTION": "3",
+ "FW_LAUNCH_MESSAGE_TYPE_IN_PROGRESS": "4",
+ "FW_LAUNCH_MESSAGE_TYPE_FINISHING": "5"
+ },
+ "fixedWingLaunchState_t": {
+ "_source": "../../../src/main/navigation/navigation_fw_launch.c",
+ "FW_LAUNCH_STATE_WAIT_THROTTLE": "0",
+ "FW_LAUNCH_STATE_IDLE_WIGGLE_WAIT": "1",
+ "FW_LAUNCH_STATE_IDLE_MOTOR_DELAY": "2",
+ "FW_LAUNCH_STATE_MOTOR_IDLE": "3",
+ "FW_LAUNCH_STATE_WAIT_DETECTION": "4",
+ "FW_LAUNCH_STATE_DETECTED": "5",
+ "FW_LAUNCH_STATE_MOTOR_DELAY": "6",
+ "FW_LAUNCH_STATE_MOTOR_SPINUP": "7",
+ "FW_LAUNCH_STATE_IN_PROGRESS": "8",
+ "FW_LAUNCH_STATE_FINISH": "9",
+ "FW_LAUNCH_STATE_ABORTED": "10",
+ "FW_LAUNCH_STATE_FLYING": "11",
+ "FW_LAUNCH_STATE_COUNT": "12"
+ },
+ "flashPartitionType_e": {
+ "_source": "../../../src/main/drivers/flash.h",
+ "FLASH_PARTITION_TYPE_UNKNOWN": "0",
+ "FLASH_PARTITION_TYPE_PARTITION_TABLE": "1",
+ "FLASH_PARTITION_TYPE_FLASHFS": "2",
+ "FLASH_PARTITION_TYPE_BADBLOCK_MANAGEMENT": "3",
+ "FLASH_PARTITION_TYPE_FIRMWARE": "4",
+ "FLASH_PARTITION_TYPE_CONFIG": "5",
+ "FLASH_PARTITION_TYPE_FULL_BACKUP": "6",
+ "FLASH_PARTITION_TYPE_FIRMWARE_UPDATE_META": "7",
+ "FLASH_PARTITION_TYPE_UPDATE_FIRMWARE": "8",
+ "FLASH_MAX_PARTITIONS": "9"
+ },
+ "flashType_e": {
+ "_source": "../../../src/main/drivers/flash.h",
+ "FLASH_TYPE_NOR": "0",
+ "FLASH_TYPE_NAND": "1"
+ },
+ "flight_dynamics_index_t": {
+ "_source": "../../../src/main/common/axis.h",
+ "FD_ROLL": "0",
+ "FD_PITCH": "1",
+ "FD_YAW": "2"
+ },
+ "flightModeFlags_e": {
+ "_source": "../../../src/main/fc/runtime_config.h",
+ "ANGLE_MODE": "(1 << 0)",
+ "HORIZON_MODE": "(1 << 1)",
+ "HEADING_MODE": "(1 << 2)",
+ "NAV_ALTHOLD_MODE": "(1 << 3)",
+ "NAV_RTH_MODE": "(1 << 4)",
+ "NAV_POSHOLD_MODE": "(1 << 5)",
+ "HEADFREE_MODE": "(1 << 6)",
+ "NAV_LAUNCH_MODE": "(1 << 7)",
+ "MANUAL_MODE": "(1 << 8)",
+ "FAILSAFE_MODE": "(1 << 9)",
+ "AUTO_TUNE": "(1 << 10)",
+ "NAV_WP_MODE": "(1 << 11)",
+ "NAV_COURSE_HOLD_MODE": "(1 << 12)",
+ "FLAPERON": "(1 << 13)",
+ "TURN_ASSISTANT": "(1 << 14)",
+ "TURTLE_MODE": "(1 << 15)",
+ "SOARING_MODE": "(1 << 16)",
+ "ANGLEHOLD_MODE": "(1 << 17)",
+ "NAV_FW_AUTOLAND": "(1 << 18)",
+ "NAV_SEND_TO": "(1 << 19)"
+ },
+ "flightModeForTelemetry_e": {
+ "_source": "../../../src/main/fc/runtime_config.h",
+ "FLM_MANUAL": "0",
+ "FLM_ACRO": "1",
+ "FLM_ACRO_AIR": "2",
+ "FLM_ANGLE": "3",
+ "FLM_HORIZON": "4",
+ "FLM_ALTITUDE_HOLD": "5",
+ "FLM_POSITION_HOLD": "6",
+ "FLM_RTH": "7",
+ "FLM_MISSION": "8",
+ "FLM_COURSE_HOLD": "9",
+ "FLM_CRUISE": "10",
+ "FLM_LAUNCH": "11",
+ "FLM_FAILSAFE": "12",
+ "FLM_ANGLEHOLD": "13",
+ "FLM_COUNT": "14"
+ },
+ "flyingPlatformType_e": {
+ "_source": "../../../src/main/flight/mixer.h",
+ "PLATFORM_MULTIROTOR": "0",
+ "PLATFORM_AIRPLANE": "1",
+ "PLATFORM_HELICOPTER": "2",
+ "PLATFORM_TRICOPTER": "3",
+ "PLATFORM_ROVER": "4",
+ "PLATFORM_BOAT": "5"
+ },
+ "fport2_control_frame_type_e": {
+ "_source": "../../../src/main/rx/fport2.c",
+ "CFT_RC": "255",
+ "CFT_OTA_START": "240",
+ "CFT_OTA_DATA": "241",
+ "CFT_OTA_STOP": "242"
+ },
+ "frame_state_e": {
+ "_source": "../../../src/main/rx/fport2.c",
+ "FS_CONTROL_FRAME_START": "0",
+ "FS_CONTROL_FRAME_TYPE": "1",
+ "FS_CONTROL_FRAME_DATA": "2",
+ "FS_DOWNLINK_FRAME_START": "3",
+ "FS_DOWNLINK_FRAME_DATA": "4"
+ },
+ "frame_type_e": {
+ "_source": "../../../src/main/rx/fport2.c",
+ "FT_CONTROL": "0",
+ "FT_DOWNLINK": "1"
+ },
+ "frskyOSDColor_e": {
+ "_source": "../../../src/main/io/frsky_osd.h",
+ "FRSKY_OSD_COLOR_BLACK": "0",
+ "FRSKY_OSD_COLOR_TRANSPARENT": "1",
+ "FRSKY_OSD_COLOR_WHITE": "2",
+ "FRSKY_OSD_COLOR_GRAY": "3"
+ },
+ "frskyOSDLineOutlineType_e": {
+ "_source": "../../../src/main/io/frsky_osd.h",
+ "FRSKY_OSD_OUTLINE_TYPE_NONE": "0",
+ "FRSKY_OSD_OUTLINE_TYPE_TOP": "1 << 0",
+ "FRSKY_OSD_OUTLINE_TYPE_RIGHT": "1 << 1",
+ "FRSKY_OSD_OUTLINE_TYPE_BOTTOM": "1 << 2",
+ "FRSKY_OSD_OUTLINE_TYPE_LEFT": "1 << 3"
+ },
+ "frskyOSDRecvState_e": {
+ "_source": "../../../src/main/io/frsky_osd.c",
+ "RECV_STATE_NONE": "0",
+ "RECV_STATE_SYNC": "1",
+ "RECV_STATE_LENGTH": "2",
+ "RECV_STATE_DATA": "3",
+ "RECV_STATE_CHECKSUM": "4",
+ "RECV_STATE_DONE": "5"
+ },
+ "frskyOSDTransactionOptions_e": {
+ "_source": "../../../src/main/io/frsky_osd.h",
+ "FRSKY_OSD_TRANSACTION_OPT_PROFILED": "1 << 0",
+ "FRSKY_OSD_TRANSACTION_OPT_RESET_DRAWING": "1 << 1"
+ },
+ "fw_autotune_rate_adjustment_e": {
+ "_source": "../../../src/main/flight/pid.h",
+ "FIXED": "0",
+ "LIMIT": "1",
+ "AUTO": "2"
+ },
+ "fwAutolandApproachDirection_e": {
+ "_source": "../../../src/main/navigation/navigation.h",
+ "FW_AUTOLAND_APPROACH_DIRECTION_LEFT": "0",
+ "FW_AUTOLAND_APPROACH_DIRECTION_RIGHT": "1"
+ },
+ "fwAutolandState_t": {
+ "_source": "../../../src/main/navigation/navigation.h",
+ "FW_AUTOLAND_STATE_IDLE": "0",
+ "FW_AUTOLAND_STATE_LOITER": "1",
+ "FW_AUTOLAND_STATE_DOWNWIND": "2",
+ "FW_AUTOLAND_STATE_BASE_LEG": "3",
+ "FW_AUTOLAND_STATE_FINAL_APPROACH": "4",
+ "FW_AUTOLAND_STATE_GLIDE": "5",
+ "FW_AUTOLAND_STATE_FLARE": "6"
+ },
+ "fwAutolandWaypoint_t": {
+ "_source": "../../../src/main/navigation/navigation_private.h",
+ "FW_AUTOLAND_WP_TURN": "0",
+ "FW_AUTOLAND_WP_FINAL_APPROACH": "1",
+ "FW_AUTOLAND_WP_LAND": "2",
+ "FW_AUTOLAND_WP_COUNT": "3"
+ },
+ "geoAltitudeConversionMode_e": {
+ "_source": "../../../src/main/navigation/navigation.h",
+ "GEO_ALT_ABSOLUTE": "0",
+ "GEO_ALT_RELATIVE": "1"
+ },
+ "geoAltitudeDatumFlag_e": {
+ "_source": "../../../src/main/navigation/navigation.h",
+ "NAV_WP_TAKEOFF_DATUM": "0",
+ "NAV_WP_MSL_DATUM": "1"
+ },
+ "geoOriginResetMode_e": {
+ "_source": "../../../src/main/navigation/navigation.h",
+ "GEO_ORIGIN_SET": "0",
+ "GEO_ORIGIN_RESET_ALTITUDE": "1"
+ },
+ "geozoneActionState_e": {
+ "_source": "../../../src/main/navigation/navigation_geozone.c",
+ "GEOZONE_ACTION_STATE_NONE": "0",
+ "GEOZONE_ACTION_STATE_AVOIDING": "1",
+ "GEOZONE_ACTION_STATE_AVOIDING_UPWARD": "2",
+ "GEOZONE_ACTION_STATE_AVOIDING_ALTITUDE": "3",
+ "GEOZONE_ACTION_STATE_RETURN_TO_FZ": "4",
+ "GEOZONE_ACTION_STATE_FLYOUT_NFZ": "5",
+ "GEOZONE_ACTION_STATE_POSHOLD": "6",
+ "GEOZONE_ACTION_STATE_RTH": "7"
+ },
+ "geozoneMessageState_e": {
+ "_source": "../../../src/main/navigation/navigation.h",
+ "GEOZONE_MESSAGE_STATE_NONE": "0",
+ "GEOZONE_MESSAGE_STATE_NFZ": "1",
+ "GEOZONE_MESSAGE_STATE_LEAVING_FZ": "2",
+ "GEOZONE_MESSAGE_STATE_OUTSIDE_FZ": "3",
+ "GEOZONE_MESSAGE_STATE_ENTERING_NFZ": "4",
+ "GEOZONE_MESSAGE_STATE_AVOIDING_FB": "5",
+ "GEOZONE_MESSAGE_STATE_RETURN_TO_ZONE": "6",
+ "GEOZONE_MESSAGE_STATE_FLYOUT_NFZ": "7",
+ "GEOZONE_MESSAGE_STATE_AVOIDING_ALTITUDE_BREACH": "8",
+ "GEOZONE_MESSAGE_STATE_POS_HOLD": "9"
+ },
+ "ghstAddr_e": {
+ "_source": "../../../src/main/rx/ghst_protocol.h",
+ "GHST_ADDR_RADIO": "128",
+ "GHST_ADDR_TX_MODULE_SYM": "129",
+ "GHST_ADDR_TX_MODULE_ASYM": "136",
+ "GHST_ADDR_FC": "130",
+ "GHST_ADDR_GOGGLES": "131",
+ "GHST_ADDR_QUANTUM_TEE1": "132",
+ "GHST_ADDR_QUANTUM_TEE2": "133",
+ "GHST_ADDR_QUANTUM_GW1": "134",
+ "GHST_ADDR_5G_CLK": "135",
+ "GHST_ADDR_RX": "137"
+ },
+ "ghstDl_e": {
+ "_source": "../../../src/main/rx/ghst_protocol.h",
+ "GHST_DL_OPENTX_SYNC": "32",
+ "GHST_DL_LINK_STAT": "33",
+ "GHST_DL_VTX_STAT": "34",
+ "GHST_DL_PACK_STAT": "35",
+ "GHST_DL_GPS_PRIMARY": "37",
+ "GHST_DL_GPS_SECONDARY": "38"
+ },
+ "ghstFrameTypeIndex_e": {
+ "_source": "../../../src/main/telemetry/ghst.c",
+ "GHST_FRAME_START_INDEX": "0",
+ "GHST_FRAME_PACK_INDEX": "GHST_FRAME_START_INDEX",
+ "GHST_FRAME_GPS_PRIMARY_INDEX": "",
+ "GHST_FRAME_GPS_SECONDARY_INDEX": "",
+ "GHST_SCHEDULE_COUNT_MAX": ""
+ },
+ "ghstUl_e": {
+ "_source": "../../../src/main/rx/ghst_protocol.h",
+ "GHST_UL_RC_CHANS_HS4_FIRST": "16",
+ "GHST_UL_RC_CHANS_HS4_5TO8": "16",
+ "GHST_UL_RC_CHANS_HS4_9TO12": "17",
+ "GHST_UL_RC_CHANS_HS4_13TO16": "18",
+ "GHST_UL_RC_CHANS_HS4_RSSI": "19",
+ "GHST_UL_RC_CHANS_HS4_LAST": "31"
+ },
+ "gimbal_htk_mode_e": {
+ "_source": "../../../src/main/drivers/gimbal_common.h",
+ "GIMBAL_MODE_FOLLOW": "0",
+ "GIMBAL_MODE_TILT_LOCK": "(1<<0)",
+ "GIMBAL_MODE_ROLL_LOCK": "(1<<1)",
+ "GIMBAL_MODE_PAN_LOCK": "(1<<2)"
+ },
+ "gimbalDevType_e": {
+ "_source": "../../../src/main/drivers/gimbal_common.h",
+ "GIMBAL_DEV_UNSUPPORTED": "0",
+ "GIMBAL_DEV_SERIAL": "1",
+ "GIMBAL_DEV_UNKNOWN": "255"
+ },
+ "gimbalHeadtrackerState_e": {
+ "_source": "../../../src/main/io/gimbal_serial.h",
+ "WAITING_HDR1": "0",
+ "WAITING_HDR2": "1",
+ "WAITING_PAYLOAD": "2",
+ "WAITING_CRCH": "3",
+ "WAITING_CRCL": "4"
+ },
+ "gpsAutoBaud_e": {
+ "_source": "../../../src/main/io/gps.h",
+ "GPS_AUTOBAUD_OFF": "0",
+ "GPS_AUTOBAUD_ON": "1"
+ },
+ "gpsAutoConfig_e": {
+ "_source": "../../../src/main/io/gps.h",
+ "GPS_AUTOCONFIG_OFF": "0",
+ "GPS_AUTOCONFIG_ON": "1"
+ },
+ "gpsBaudRate_e": {
+ "_source": "../../../src/main/io/gps.h",
+ "GPS_BAUDRATE_115200": "0",
+ "GPS_BAUDRATE_57600": "1",
+ "GPS_BAUDRATE_38400": "2",
+ "GPS_BAUDRATE_19200": "3",
+ "GPS_BAUDRATE_9600": "4",
+ "GPS_BAUDRATE_230400": "5",
+ "GPS_BAUDRATE_460800": "6",
+ "GPS_BAUDRATE_921600": "7",
+ "GPS_BAUDRATE_COUNT": "8"
+ },
+ "gpsDynModel_e": {
+ "_source": "../../../src/main/io/gps.h",
+ "GPS_DYNMODEL_PEDESTRIAN": "0",
+ "GPS_DYNMODEL_AUTOMOTIVE": "1",
+ "GPS_DYNMODEL_AIR_1G": "2",
+ "GPS_DYNMODEL_AIR_2G": "3",
+ "GPS_DYNMODEL_AIR_4G": "4",
+ "GPS_DYNMODEL_SEA": "5",
+ "GPS_DYNMODEL_MOWER": "6"
+ },
+ "gpsFixChar_e": {
+ "_source": "../../../src/main/telemetry/hott.c",
+ "GPS_FIX_CHAR_NONE": "'-'",
+ "GPS_FIX_CHAR_2D": "'2'",
+ "GPS_FIX_CHAR_3D": "'3'",
+ "GPS_FIX_CHAR_DGPS": "'D'"
+ },
+ "gpsFixType_e": {
+ "_source": "../../../src/main/io/gps.h",
+ "GPS_NO_FIX": "0",
+ "GPS_FIX_2D": "1",
+ "GPS_FIX_3D": "2"
+ },
+ "gpsProvider_e": {
+ "_source": "../../../src/main/io/gps.h",
+ "GPS_UBLOX": "0",
+ "GPS_MSP": "1",
+ "GPS_FAKE": "2",
+ "GPS_PROVIDER_COUNT": "3"
+ },
+ "gpsState_e": {
+ "_source": "../../../src/main/io/gps_private.h",
+ "GPS_UNKNOWN": "0",
+ "GPS_INITIALIZING": "1",
+ "GPS_RUNNING": "2",
+ "GPS_LOST_COMMUNICATION": "3"
+ },
+ "gyroFilterMode_e": {
+ "_source": "../../../src/main/sensors/gyro.h",
+ "GYRO_FILTER_MODE_OFF": "0",
+ "GYRO_FILTER_MODE_STATIC": "1",
+ "GYRO_FILTER_MODE_DYNAMIC": "2",
+ "GYRO_FILTER_MODE_ADAPTIVE": "3"
+ },
+ "gyroHardwareLpf_e": {
+ "_source": "../../../src/main/drivers/accgyro/accgyro_lsm6dxx.h",
+ "GYRO_HARDWARE_LPF_NORMAL": "0",
+ "GYRO_HARDWARE_LPF_OPTION_1": "1",
+ "GYRO_HARDWARE_LPF_OPTION_2": "2",
+ "GYRO_HARDWARE_LPF_EXPERIMENTAL": "3",
+ "GYRO_HARDWARE_LPF_COUNT": "4"
+ },
+ "gyroSensor_e": {
+ "_source": "../../../src/main/sensors/gyro.h",
+ "GYRO_NONE": "0",
+ "GYRO_AUTODETECT": "1",
+ "GYRO_MPU6000": "2",
+ "GYRO_MPU6500": "3",
+ "GYRO_MPU9250": "4",
+ "GYRO_BMI160": "5",
+ "GYRO_ICM20689": "6",
+ "GYRO_BMI088": "7",
+ "GYRO_ICM42605": "8",
+ "GYRO_BMI270": "9",
+ "GYRO_LSM6DXX": "10",
+ "GYRO_FAKE": "11"
+ },
+ "HardwareMotorTypes_e": {
+ "_source": "../../../src/main/drivers/pwm_esc_detect.h",
+ "MOTOR_UNKNOWN": "0",
+ "MOTOR_BRUSHED": "1",
+ "MOTOR_BRUSHLESS": "2"
+ },
+ "hardwareSensorStatus_e": {
+ "_source": "../../../src/main/sensors/diagnostics.h",
+ "HW_SENSOR_NONE": "0",
+ "HW_SENSOR_OK": "1",
+ "HW_SENSOR_UNAVAILABLE": "2",
+ "HW_SENSOR_UNHEALTHY": "3"
+ },
+ "headTrackerDevType_e": {
+ "_source": "../../../src/main/drivers/headtracker_common.h",
+ "HEADTRACKER_NONE": "0",
+ "HEADTRACKER_SERIAL": "1",
+ "HEADTRACKER_MSP": "2",
+ "HEADTRACKER_UNKNOWN": "255"
+ },
+ "hottEamAlarm1Flag_e": {
+ "_source": "../../../src/main/telemetry/hott.h",
+ "HOTT_EAM_ALARM1_FLAG_NONE": "0",
+ "HOTT_EAM_ALARM1_FLAG_MAH": "(1 << 0)",
+ "HOTT_EAM_ALARM1_FLAG_BATTERY_1": "(1 << 1)",
+ "HOTT_EAM_ALARM1_FLAG_BATTERY_2": "(1 << 2)",
+ "HOTT_EAM_ALARM1_FLAG_TEMPERATURE_1": "(1 << 3)",
+ "HOTT_EAM_ALARM1_FLAG_TEMPERATURE_2": "(1 << 4)",
+ "HOTT_EAM_ALARM1_FLAG_ALTITUDE": "(1 << 5)",
+ "HOTT_EAM_ALARM1_FLAG_CURRENT": "(1 << 6)",
+ "HOTT_EAM_ALARM1_FLAG_MAIN_VOLTAGE": "(1 << 7)"
+ },
+ "hottEamAlarm2Flag_e": {
+ "_source": "../../../src/main/telemetry/hott.h",
+ "HOTT_EAM_ALARM2_FLAG_NONE": "0",
+ "HOTT_EAM_ALARM2_FLAG_MS": "(1 << 0)",
+ "HOTT_EAM_ALARM2_FLAG_M3S": "(1 << 1)",
+ "HOTT_EAM_ALARM2_FLAG_ALTITUDE_DUPLICATE": "(1 << 2)",
+ "HOTT_EAM_ALARM2_FLAG_MS_DUPLICATE": "(1 << 3)",
+ "HOTT_EAM_ALARM2_FLAG_M3S_DUPLICATE": "(1 << 4)",
+ "HOTT_EAM_ALARM2_FLAG_UNKNOWN_1": "(1 << 5)",
+ "HOTT_EAM_ALARM2_FLAG_UNKNOWN_2": "(1 << 6)",
+ "HOTT_EAM_ALARM2_FLAG_ON_SIGN_OR_TEXT_ACTIVE": "(1 << 7)"
+ },
+ "hottState_e": {
+ "_source": "../../../src/main/telemetry/hott.c",
+ "HOTT_WAITING_FOR_REQUEST": "0",
+ "HOTT_RECEIVING_REQUEST": "1",
+ "HOTT_WAITING_FOR_TX_WINDOW": "2",
+ "HOTT_TRANSMITTING": "3",
+ "HOTT_ENDING_TRANSMISSION": "4"
+ },
+ "hsvColorComponent_e": {
+ "_source": "../../../src/main/common/color.h",
+ "HSV_HUE": "0",
+ "HSV_SATURATION": "1",
+ "HSV_VALUE": "2"
+ },
+ "I2CSpeed": {
+ "_source": "../../../src/main/drivers/bus_i2c.h",
+ "I2C_SPEED_100KHZ": "2",
+ "I2C_SPEED_200KHZ": "3",
+ "I2C_SPEED_400KHZ": "0",
+ "I2C_SPEED_800KHZ": "1"
+ },
+ "i2cState_t": {
+ "_source": "../../../src/main/drivers/bus_i2c_stm32f40x.c",
+ "I2C_STATE_STOPPED": "0",
+ "I2C_STATE_STOPPING": "1",
+ "I2C_STATE_STARTING": "2",
+ "I2C_STATE_STARTING_WAIT": "3",
+ "I2C_STATE_R_ADDR": "4",
+ "I2C_STATE_R_ADDR_WAIT": "5",
+ "I2C_STATE_R_REGISTER": "6",
+ "I2C_STATE_R_REGISTER_WAIT": "7",
+ "I2C_STATE_R_RESTARTING": "8",
+ "I2C_STATE_R_RESTARTING_WAIT": "9",
+ "I2C_STATE_R_RESTART_ADDR": "10",
+ "I2C_STATE_R_RESTART_ADDR_WAIT": "11",
+ "I2C_STATE_R_TRANSFER_EQ1": "12",
+ "I2C_STATE_R_TRANSFER_EQ2": "13",
+ "I2C_STATE_R_TRANSFER_GE2": "14",
+ "I2C_STATE_W_ADDR": "15",
+ "I2C_STATE_W_ADDR_WAIT": "16",
+ "I2C_STATE_W_REGISTER": "17",
+ "I2C_STATE_W_TRANSFER_WAIT": "18",
+ "I2C_STATE_W_TRANSFER": "19",
+ "I2C_STATE_NACK": "20",
+ "I2C_STATE_BUS_ERROR": "21"
+ },
+ "i2cTransferDirection_t": {
+ "_source": "../../../src/main/drivers/bus_i2c_stm32f40x.c",
+ "I2C_TXN_READ": "0",
+ "I2C_TXN_WRITE": "1"
+ },
+ "ibusCommand_e": {
+ "_source": "../../../src/main/telemetry/ibus_shared.c",
+ "IBUS_COMMAND_DISCOVER_SENSOR": "128",
+ "IBUS_COMMAND_SENSOR_TYPE": "144",
+ "IBUS_COMMAND_MEASUREMENT": "160"
+ },
+ "ibusSensorType1_e": {
+ "_source": "../../../src/main/telemetry/ibus_shared.h",
+ "IBUS_MEAS_TYPE1_INTV": "0",
+ "IBUS_MEAS_TYPE1_TEM": "1",
+ "IBUS_MEAS_TYPE1_MOT": "2",
+ "IBUS_MEAS_TYPE1_EXTV": "3",
+ "IBUS_MEAS_TYPE1_CELL": "4",
+ "IBUS_MEAS_TYPE1_BAT_CURR": "5",
+ "IBUS_MEAS_TYPE1_FUEL": "6",
+ "IBUS_MEAS_TYPE1_RPM": "7",
+ "IBUS_MEAS_TYPE1_CMP_HEAD": "8",
+ "IBUS_MEAS_TYPE1_CLIMB_RATE": "9",
+ "IBUS_MEAS_TYPE1_COG": "10",
+ "IBUS_MEAS_TYPE1_GPS_STATUS": "11",
+ "IBUS_MEAS_TYPE1_ACC_X": "12",
+ "IBUS_MEAS_TYPE1_ACC_Y": "13",
+ "IBUS_MEAS_TYPE1_ACC_Z": "14",
+ "IBUS_MEAS_TYPE1_ROLL": "15",
+ "IBUS_MEAS_TYPE1_PITCH": "16",
+ "IBUS_MEAS_TYPE1_YAW": "17",
+ "IBUS_MEAS_TYPE1_VERTICAL_SPEED": "18",
+ "IBUS_MEAS_TYPE1_GROUND_SPEED": "19",
+ "IBUS_MEAS_TYPE1_GPS_DIST": "20",
+ "IBUS_MEAS_TYPE1_ARMED": "21",
+ "IBUS_MEAS_TYPE1_FLIGHT_MODE": "22",
+ "IBUS_MEAS_TYPE1_PRES": "65",
+ "IBUS_MEAS_TYPE1_SPE": "126",
+ "IBUS_MEAS_TYPE1_GPS_LAT": "128",
+ "IBUS_MEAS_TYPE1_GPS_LON": "129",
+ "IBUS_MEAS_TYPE1_GPS_ALT": "130",
+ "IBUS_MEAS_TYPE1_ALT": "131",
+ "IBUS_MEAS_TYPE1_S84": "132",
+ "IBUS_MEAS_TYPE1_S85": "133",
+ "IBUS_MEAS_TYPE1_S86": "134",
+ "IBUS_MEAS_TYPE1_S87": "135",
+ "IBUS_MEAS_TYPE1_S88": "136",
+ "IBUS_MEAS_TYPE1_S89": "137",
+ "IBUS_MEAS_TYPE1_S8a": "138"
+ },
+ "ibusSensorType_e": {
+ "_source": "../../../src/main/telemetry/ibus_shared.h",
+ "IBUS_MEAS_TYPE_INTERNAL_VOLTAGE": "0",
+ "IBUS_MEAS_TYPE_TEMPERATURE": "1",
+ "IBUS_MEAS_TYPE_RPM": "2",
+ "IBUS_MEAS_TYPE_EXTERNAL_VOLTAGE": "3",
+ "IBUS_MEAS_TYPE_HEADING": "4",
+ "IBUS_MEAS_TYPE_CURRENT": "5",
+ "IBUS_MEAS_TYPE_CLIMB": "6",
+ "IBUS_MEAS_TYPE_ACC_Z": "7",
+ "IBUS_MEAS_TYPE_ACC_Y": "8",
+ "IBUS_MEAS_TYPE_ACC_X": "9",
+ "IBUS_MEAS_TYPE_VSPEED": "10",
+ "IBUS_MEAS_TYPE_SPEED": "11",
+ "IBUS_MEAS_TYPE_DIST": "12",
+ "IBUS_MEAS_TYPE_ARMED": "13",
+ "IBUS_MEAS_TYPE_MODE": "14",
+ "IBUS_MEAS_TYPE_PRES": "65",
+ "IBUS_MEAS_TYPE_SPE": "126",
+ "IBUS_MEAS_TYPE_COG": "128",
+ "IBUS_MEAS_TYPE_GPS_STATUS": "129",
+ "IBUS_MEAS_TYPE_GPS_LON": "130",
+ "IBUS_MEAS_TYPE_GPS_LAT": "131",
+ "IBUS_MEAS_TYPE_ALT": "132",
+ "IBUS_MEAS_TYPE_S85": "133",
+ "IBUS_MEAS_TYPE_S86": "134",
+ "IBUS_MEAS_TYPE_S87": "135",
+ "IBUS_MEAS_TYPE_S88": "136",
+ "IBUS_MEAS_TYPE_S89": "137",
+ "IBUS_MEAS_TYPE_S8A": "138",
+ "IBUS_MEAS_TYPE_GALT": "249",
+ "IBUS_MEAS_TYPE_GPS": "253"
+ },
+ "ibusSensorValue_e": {
+ "_source": "../../../src/main/telemetry/ibus_shared.h",
+ "IBUS_MEAS_VALUE_NONE": "0",
+ "IBUS_MEAS_VALUE_TEMPERATURE": "1",
+ "IBUS_MEAS_VALUE_MOT": "2",
+ "IBUS_MEAS_VALUE_EXTERNAL_VOLTAGE": "3",
+ "IBUS_MEAS_VALUE_CELL": "4",
+ "IBUS_MEAS_VALUE_CURRENT": "5",
+ "IBUS_MEAS_VALUE_FUEL": "6",
+ "IBUS_MEAS_VALUE_RPM": "7",
+ "IBUS_MEAS_VALUE_HEADING": "8",
+ "IBUS_MEAS_VALUE_CLIMB": "9",
+ "IBUS_MEAS_VALUE_COG": "10",
+ "IBUS_MEAS_VALUE_GPS_STATUS": "11",
+ "IBUS_MEAS_VALUE_ACC_X": "12",
+ "IBUS_MEAS_VALUE_ACC_Y": "13",
+ "IBUS_MEAS_VALUE_ACC_Z": "14",
+ "IBUS_MEAS_VALUE_ROLL": "15",
+ "IBUS_MEAS_VALUE_PITCH": "16",
+ "IBUS_MEAS_VALUE_YAW": "17",
+ "IBUS_MEAS_VALUE_VSPEED": "18",
+ "IBUS_MEAS_VALUE_SPEED": "19",
+ "IBUS_MEAS_VALUE_DIST": "20",
+ "IBUS_MEAS_VALUE_ARMED": "21",
+ "IBUS_MEAS_VALUE_MODE": "22",
+ "IBUS_MEAS_VALUE_PRES": "65",
+ "IBUS_MEAS_VALUE_SPE": "126",
+ "IBUS_MEAS_VALUE_GPS_LAT": "128",
+ "IBUS_MEAS_VALUE_GPS_LON": "129",
+ "IBUS_MEAS_VALUE_GALT4": "130",
+ "IBUS_MEAS_VALUE_ALT4": "131",
+ "IBUS_MEAS_VALUE_GALT": "132",
+ "IBUS_MEAS_VALUE_ALT": "133",
+ "IBUS_MEAS_VALUE_STATUS": "135",
+ "IBUS_MEAS_VALUE_GPS_LAT1": "136",
+ "IBUS_MEAS_VALUE_GPS_LON1": "137",
+ "IBUS_MEAS_VALUE_GPS_LAT2": "144",
+ "IBUS_MEAS_VALUE_GPS_LON2": "145",
+ "IBUS_MEAS_VALUE_GPS": "253"
+ },
+ "inputSource_e": {
+ "_source": "../../../src/main/flight/servos.h",
+ "INPUT_STABILIZED_ROLL": "0",
+ "INPUT_STABILIZED_PITCH": "1",
+ "INPUT_STABILIZED_YAW": "2",
+ "INPUT_STABILIZED_THROTTLE": "3",
+ "INPUT_RC_ROLL": "4",
+ "INPUT_RC_PITCH": "5",
+ "INPUT_RC_YAW": "6",
+ "INPUT_RC_THROTTLE": "7",
+ "INPUT_RC_CH5": "8",
+ "INPUT_RC_CH6": "9",
+ "INPUT_RC_CH7": "10",
+ "INPUT_RC_CH8": "11",
+ "INPUT_GIMBAL_PITCH": "12",
+ "INPUT_GIMBAL_ROLL": "13",
+ "INPUT_FEATURE_FLAPS": "14",
+ "INPUT_RC_CH9": "15",
+ "INPUT_RC_CH10": "16",
+ "INPUT_RC_CH11": "17",
+ "INPUT_RC_CH12": "18",
+ "INPUT_RC_CH13": "19",
+ "INPUT_RC_CH14": "20",
+ "INPUT_RC_CH15": "21",
+ "INPUT_RC_CH16": "22",
+ "INPUT_STABILIZED_ROLL_PLUS": "23",
+ "INPUT_STABILIZED_ROLL_MINUS": "24",
+ "INPUT_STABILIZED_PITCH_PLUS": "25",
+ "INPUT_STABILIZED_PITCH_MINUS": "26",
+ "INPUT_STABILIZED_YAW_PLUS": "27",
+ "INPUT_STABILIZED_YAW_MINUS": "28",
+ "INPUT_MAX": "29",
+ "INPUT_GVAR_0": "30",
+ "INPUT_GVAR_1": "31",
+ "INPUT_GVAR_2": "32",
+ "INPUT_GVAR_3": "33",
+ "INPUT_GVAR_4": "34",
+ "INPUT_GVAR_5": "35",
+ "INPUT_GVAR_6": "36",
+ "INPUT_GVAR_7": "37",
+ "INPUT_MIXER_TRANSITION": "38",
+ "INPUT_HEADTRACKER_PAN": "39",
+ "INPUT_HEADTRACKER_TILT": "40",
+ "INPUT_HEADTRACKER_ROLL": "41",
+ "INPUT_RC_CH17": "42",
+ "INPUT_RC_CH18": "43",
+ "INPUT_RC_CH19": "44",
+ "INPUT_RC_CH20": "45",
+ "INPUT_RC_CH21": "46",
+ "INPUT_RC_CH22": "47",
+ "INPUT_RC_CH23": "48",
+ "INPUT_RC_CH24": "49",
+ "INPUT_RC_CH25": "50",
+ "INPUT_RC_CH26": "51",
+ "INPUT_RC_CH27": "52",
+ "INPUT_RC_CH28": "53",
+ "INPUT_RC_CH29": "54",
+ "INPUT_RC_CH30": "55",
+ "INPUT_RC_CH31": "56",
+ "INPUT_RC_CH32": "57",
+ "INPUT_RC_CH33": "58",
+ "INPUT_RC_CH34": "59",
+ "INPUT_MIXER_SWITCH_HELPER": "60",
+ "INPUT_SOURCE_COUNT": "61"
+ },
+ "itermRelax_e": {
+ "_source": "../../../src/main/flight/pid.h",
+ "ITERM_RELAX_OFF": "0",
+ "ITERM_RELAX_RP": "1",
+ "ITERM_RELAX_RPY": "2"
+ },
+ "led_pin_pwm_mode_e": {
+ "_source": "../../../src/main/drivers/light_ws2811strip.h",
+ "LED_PIN_PWM_MODE_SHARED_LOW": "0",
+ "LED_PIN_PWM_MODE_SHARED_HIGH": "1",
+ "LED_PIN_PWM_MODE_LOW": "2",
+ "LED_PIN_PWM_MODE_HIGH": "3"
+ },
+ "ledBaseFunctionId_e": {
+ "_source": "../../../src/main/io/ledstrip.h",
+ "LED_FUNCTION_COLOR": "0",
+ "LED_FUNCTION_FLIGHT_MODE": "1",
+ "LED_FUNCTION_ARM_STATE": "2",
+ "LED_FUNCTION_BATTERY": "3",
+ "LED_FUNCTION_RSSI": "4",
+ "LED_FUNCTION_GPS": "5",
+ "LED_FUNCTION_THRUST_RING": "6",
+ "LED_FUNCTION_CHANNEL": "7"
+ },
+ "ledDirectionId_e": {
+ "_source": "../../../src/main/io/ledstrip.h",
+ "LED_DIRECTION_NORTH": "0",
+ "LED_DIRECTION_EAST": "1",
+ "LED_DIRECTION_SOUTH": "2",
+ "LED_DIRECTION_WEST": "3",
+ "LED_DIRECTION_UP": "4",
+ "LED_DIRECTION_DOWN": "5"
+ },
+ "ledModeIndex_e": {
+ "_source": "../../../src/main/io/ledstrip.h",
+ "LED_MODE_ORIENTATION": "0",
+ "LED_MODE_HEADFREE": "1",
+ "LED_MODE_HORIZON": "2",
+ "LED_MODE_ANGLE": "3",
+ "LED_MODE_MAG": "4",
+ "LED_MODE_BARO": "5",
+ "LED_SPECIAL": "6"
+ },
+ "ledOverlayId_e": {
+ "_source": "../../../src/main/io/ledstrip.h",
+ "LED_OVERLAY_THROTTLE": "0",
+ "LED_OVERLAY_LARSON_SCANNER": "1",
+ "LED_OVERLAY_BLINK": "2",
+ "LED_OVERLAY_LANDING_FLASH": "3",
+ "LED_OVERLAY_INDICATOR": "4",
+ "LED_OVERLAY_WARNING": "5",
+ "LED_OVERLAY_STROBE": "6"
+ },
+ "ledSpecialColorIds_e": {
+ "_source": "../../../src/main/io/ledstrip.h",
+ "LED_SCOLOR_DISARMED": "0",
+ "LED_SCOLOR_ARMED": "1",
+ "LED_SCOLOR_ANIMATION": "2",
+ "LED_SCOLOR_BACKGROUND": "3",
+ "LED_SCOLOR_BLINKBACKGROUND": "4",
+ "LED_SCOLOR_GPSNOSATS": "5",
+ "LED_SCOLOR_GPSNOLOCK": "6",
+ "LED_SCOLOR_GPSLOCKED": "7",
+ "LED_SCOLOR_STROBE": "8"
+ },
+ "logicConditionFlags_e": {
+ "_source": "../../../src/main/programming/logic_condition.h",
+ "LOGIC_CONDITION_FLAG_LATCH": "1 << 0",
+ "LOGIC_CONDITION_FLAG_TIMEOUT_SATISFIED": "1 << 1"
+ },
+ "logicConditionsGlobalFlags_t": {
+ "_source": "../../../src/main/programming/logic_condition.h",
+ "LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_ARMING_SAFETY": "(1 << 0)",
+ "LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_THROTTLE_SCALE": "(1 << 1)",
+ "LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_SWAP_ROLL_YAW": "(1 << 2)",
+ "LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_INVERT_ROLL": "(1 << 3)",
+ "LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_INVERT_PITCH": "(1 << 4)",
+ "LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_INVERT_YAW": "(1 << 5)",
+ "LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_THROTTLE": "(1 << 6)",
+ "LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_OSD_LAYOUT": "(1 << 7)",
+ "LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_RC_CHANNEL": "(1 << 8)",
+ "LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_LOITER_RADIUS": "(1 << 9)",
+ "LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_FLIGHT_AXIS": "(1 << 10)",
+ "LOGIC_CONDITION_GLOBAL_FLAG_DISABLE_GPS_FIX": [
+ "(1 << 11)",
+ "USE_GPS_FIX_ESTIMATION"
+ ],
+ "LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_MIN_GROUND_SPEED": "(1 << 12)"
+ },
+ "logicFlightModeOperands_e": {
+ "_source": "../../../src/main/programming/logic_condition.h",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_MODE_FAILSAFE": "0",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_MODE_MANUAL": "1",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_MODE_RTH": "2",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_MODE_POSHOLD": "3",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_MODE_CRUISE": "4",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_MODE_ALTHOLD": "5",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_MODE_ANGLE": "6",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_MODE_HORIZON": "7",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_MODE_AIR": "8",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_MODE_USER1": "9",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_MODE_USER2": "10",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_MODE_COURSE_HOLD": "11",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_MODE_USER3": "12",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_MODE_USER4": "13",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_MODE_ACRO": "14",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_MODE_WAYPOINT_MISSION": "15",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_MODE_ANGLEHOLD": "16"
+ },
+ "logicFlightOperands_e": {
+ "_source": "../../../src/main/programming/logic_condition.h",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_ARM_TIMER": "0",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_HOME_DISTANCE": "1",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_TRIP_DISTANCE": "2",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_RSSI": "3",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_VBAT": "4",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_CELL_VOLTAGE": "5",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_CURRENT": "6",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_MAH_DRAWN": "7",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_GPS_SATS": "8",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_GROUD_SPEED": "9",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_3D_SPEED": "10",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_AIR_SPEED": "11",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_ALTITUDE": "12",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_VERTICAL_SPEED": "13",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_TROTTLE_POS": "14",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_ATTITUDE_ROLL": "15",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_ATTITUDE_PITCH": "16",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_IS_ARMED": "17",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_IS_AUTOLAUNCH": "18",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_IS_ALTITUDE_CONTROL": "19",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_IS_POSITION_CONTROL": "20",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_IS_EMERGENCY_LANDING": "21",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_IS_RTH": "22",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_IS_LANDING": "23",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_IS_FAILSAFE": "24",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_STABILIZED_ROLL": "25",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_STABILIZED_PITCH": "26",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_STABILIZED_YAW": "27",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_3D_HOME_DISTANCE": "28",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_LQ_UPLINK": "29",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_SNR": "30",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_GPS_VALID": "31",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_LOITER_RADIUS": "32",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_ACTIVE_PROFILE": "33",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_BATT_CELLS": "34",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_AGL_STATUS": "35",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_AGL": "36",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_RANGEFINDER_RAW": "37",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_ACTIVE_MIXER_PROFILE": "38",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_MIXER_TRANSITION_ACTIVE": "39",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_ATTITUDE_YAW": "40",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_FW_LAND_STATE": "41",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_BATT_PROFILE": "42",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_FLOWN_LOITER_RADIUS": "43",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_LQ_DOWNLINK": "44",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_UPLINK_RSSI_DBM": "45",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_MIN_GROUND_SPEED": "46",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_HORIZONTAL_WIND_SPEED": "47",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_WIND_DIRECTION": "48",
+ "LOGIC_CONDITION_OPERAND_FLIGHT_RELATIVE_WIND_OFFSET": "49"
+ },
+ "logicOperation_e": {
+ "_source": "../../../src/main/programming/logic_condition.h",
+ "LOGIC_CONDITION_TRUE": "0",
+ "LOGIC_CONDITION_EQUAL": "1",
+ "LOGIC_CONDITION_GREATER_THAN": "2",
+ "LOGIC_CONDITION_LOWER_THAN": "3",
+ "LOGIC_CONDITION_LOW": "4",
+ "LOGIC_CONDITION_MID": "5",
+ "LOGIC_CONDITION_HIGH": "6",
+ "LOGIC_CONDITION_AND": "7",
+ "LOGIC_CONDITION_OR": "8",
+ "LOGIC_CONDITION_XOR": "9",
+ "LOGIC_CONDITION_NAND": "10",
+ "LOGIC_CONDITION_NOR": "11",
+ "LOGIC_CONDITION_NOT": "12",
+ "LOGIC_CONDITION_STICKY": "13",
+ "LOGIC_CONDITION_ADD": "14",
+ "LOGIC_CONDITION_SUB": "15",
+ "LOGIC_CONDITION_MUL": "16",
+ "LOGIC_CONDITION_DIV": "17",
+ "LOGIC_CONDITION_GVAR_SET": "18",
+ "LOGIC_CONDITION_GVAR_INC": "19",
+ "LOGIC_CONDITION_GVAR_DEC": "20",
+ "LOGIC_CONDITION_PORT_SET": "21",
+ "LOGIC_CONDITION_OVERRIDE_ARMING_SAFETY": "22",
+ "LOGIC_CONDITION_OVERRIDE_THROTTLE_SCALE": "23",
+ "LOGIC_CONDITION_SWAP_ROLL_YAW": "24",
+ "LOGIC_CONDITION_SET_VTX_POWER_LEVEL": "25",
+ "LOGIC_CONDITION_INVERT_ROLL": "26",
+ "LOGIC_CONDITION_INVERT_PITCH": "27",
+ "LOGIC_CONDITION_INVERT_YAW": "28",
+ "LOGIC_CONDITION_OVERRIDE_THROTTLE": "29",
+ "LOGIC_CONDITION_SET_VTX_BAND": "30",
+ "LOGIC_CONDITION_SET_VTX_CHANNEL": "31",
+ "LOGIC_CONDITION_SET_OSD_LAYOUT": "32",
+ "LOGIC_CONDITION_SIN": "33",
+ "LOGIC_CONDITION_COS": "34",
+ "LOGIC_CONDITION_TAN": "35",
+ "LOGIC_CONDITION_MAP_INPUT": "36",
+ "LOGIC_CONDITION_MAP_OUTPUT": "37",
+ "LOGIC_CONDITION_RC_CHANNEL_OVERRIDE": "38",
+ "LOGIC_CONDITION_SET_HEADING_TARGET": "39",
+ "LOGIC_CONDITION_MODULUS": "40",
+ "LOGIC_CONDITION_LOITER_OVERRIDE": "41",
+ "LOGIC_CONDITION_SET_PROFILE": "42",
+ "LOGIC_CONDITION_MIN": "43",
+ "LOGIC_CONDITION_MAX": "44",
+ "LOGIC_CONDITION_FLIGHT_AXIS_ANGLE_OVERRIDE": "45",
+ "LOGIC_CONDITION_FLIGHT_AXIS_RATE_OVERRIDE": "46",
+ "LOGIC_CONDITION_EDGE": "47",
+ "LOGIC_CONDITION_DELAY": "48",
+ "LOGIC_CONDITION_TIMER": "49",
+ "LOGIC_CONDITION_DELTA": "50",
+ "LOGIC_CONDITION_APPROX_EQUAL": "51",
+ "LOGIC_CONDITION_LED_PIN_PWM": "52",
+ "LOGIC_CONDITION_DISABLE_GPS_FIX": "53",
+ "LOGIC_CONDITION_RESET_MAG_CALIBRATION": "54",
+ "LOGIC_CONDITION_SET_GIMBAL_SENSITIVITY": "55",
+ "LOGIC_CONDITION_OVERRIDE_MIN_GROUND_SPEED": "56",
+ "LOGIC_CONDITION_LAST": "57"
+ },
+ "logicWaypointOperands_e": {
+ "_source": "../../../src/main/programming/logic_condition.h",
+ "LOGIC_CONDITION_OPERAND_WAYPOINTS_IS_WP": "0",
+ "LOGIC_CONDITION_OPERAND_WAYPOINTS_WAYPOINT_INDEX": "1",
+ "LOGIC_CONDITION_OPERAND_WAYPOINTS_WAYPOINT_ACTION": "2",
+ "LOGIC_CONDITION_OPERAND_WAYPOINTS_NEXT_WAYPOINT_ACTION": "3",
+ "LOGIC_CONDITION_OPERAND_WAYPOINTS_WAYPOINT_DISTANCE": "4",
+ "LOGIC_CONDTIION_OPERAND_WAYPOINTS_DISTANCE_FROM_WAYPOINT": "5",
+ "LOGIC_CONDITION_OPERAND_WAYPOINTS_USER1_ACTION": "6",
+ "LOGIC_CONDITION_OPERAND_WAYPOINTS_USER2_ACTION": "7",
+ "LOGIC_CONDITION_OPERAND_WAYPOINTS_USER3_ACTION": "8",
+ "LOGIC_CONDITION_OPERAND_WAYPOINTS_USER4_ACTION": "9",
+ "LOGIC_CONDITION_OPERAND_WAYPOINTS_USER1_ACTION_NEXT_WP": "10",
+ "LOGIC_CONDITION_OPERAND_WAYPOINTS_USER2_ACTION_NEXT_WP": "11",
+ "LOGIC_CONDITION_OPERAND_WAYPOINTS_USER3_ACTION_NEXT_WP": "12",
+ "LOGIC_CONDITION_OPERAND_WAYPOINTS_USER4_ACTION_NEXT_WP": "13"
+ },
+ "logTopic_e": {
+ "_source": "../../../src/main/common/log.h",
+ "LOG_TOPIC_SYSTEM": "0",
+ "LOG_TOPIC_GYRO": "1",
+ "LOG_TOPIC_BARO": "2",
+ "LOG_TOPIC_PITOT": "3",
+ "LOG_TOPIC_PWM": "4",
+ "LOG_TOPIC_TIMER": "5",
+ "LOG_TOPIC_IMU": "6",
+ "LOG_TOPIC_TEMPERATURE": "7",
+ "LOG_TOPIC_POS_ESTIMATOR": "8",
+ "LOG_TOPIC_VTX": "9",
+ "LOG_TOPIC_OSD": "10",
+ "LOG_TOPIC_COUNT": "11"
+ },
+ "lsm6dxxConfigMasks_e": {
+ "_source": "../../../src/main/drivers/accgyro/accgyro_lsm6dxx.h",
+ "LSM6DXX_MASK_COUNTER_BDR1": "128",
+ "LSM6DXX_MASK_CTRL3_C": "60",
+ "LSM6DXX_MASK_CTRL3_C_RESET": "BIT(0)",
+ "LSM6DXX_MASK_CTRL4_C": "14",
+ "LSM6DXX_MASK_CTRL6_C": "23",
+ "LSM6DXX_MASK_CTRL7_G": "112",
+ "LSM6DXX_MASK_CTRL9_XL": "2",
+ "LSM6DSL_MASK_CTRL6_C": "19"
+ },
+ "lsm6dxxConfigValues_e": {
+ "_source": "../../../src/main/drivers/accgyro/accgyro_lsm6dxx.h",
+ "LSM6DXX_VAL_COUNTER_BDR1_DDRY_PM": "BIT(7)",
+ "LSM6DXX_VAL_INT1_CTRL": "2",
+ "LSM6DXX_VAL_INT2_CTRL": "0",
+ "LSM6DXX_VAL_CTRL1_XL_ODR833": "7",
+ "LSM6DXX_VAL_CTRL1_XL_ODR1667": "8",
+ "LSM6DXX_VAL_CTRL1_XL_ODR3332": "9",
+ "LSM6DXX_VAL_CTRL1_XL_ODR3333": "10",
+ "LSM6DXX_VAL_CTRL1_XL_8G": "3",
+ "LSM6DXX_VAL_CTRL1_XL_16G": "1",
+ "LSM6DXX_VAL_CTRL1_XL_LPF1": "0",
+ "LSM6DXX_VAL_CTRL1_XL_LPF2": "1",
+ "LSM6DXX_VAL_CTRL2_G_ODR6664": "10",
+ "LSM6DXX_VAL_CTRL2_G_2000DPS": "3",
+ "LSM6DXX_VAL_CTRL3_C_H_LACTIVE": "0",
+ "LSM6DXX_VAL_CTRL3_C_PP_OD": "0",
+ "LSM6DXX_VAL_CTRL3_C_SIM": "0",
+ "LSM6DXX_VAL_CTRL3_C_IF_INC": "BIT(2)",
+ "LSM6DXX_VAL_CTRL4_C_DRDY_MASK": "BIT(3)",
+ "LSM6DXX_VAL_CTRL4_C_I2C_DISABLE": "BIT(2)",
+ "LSM6DXX_VAL_CTRL4_C_LPF1_SEL_G": "BIT(1)",
+ "LSM6DXX_VAL_CTRL6_C_XL_HM_MODE": "0",
+ "LSM6DXX_VAL_CTRL6_C_FTYPE_300HZ": "0",
+ "LSM6DXX_VAL_CTRL6_C_FTYPE_201HZ": "1",
+ "LSM6DXX_VAL_CTRL6_C_FTYPE_102HZ": "2",
+ "LSM6DXX_VAL_CTRL6_C_FTYPE_603HZ": "3",
+ "LSM6DXX_VAL_CTRL7_G_HP_EN_G": "BIT(6)",
+ "LSM6DXX_VAL_CTRL7_G_HPM_G_16": "0",
+ "LSM6DXX_VAL_CTRL7_G_HPM_G_65": "1",
+ "LSM6DXX_VAL_CTRL7_G_HPM_G_260": "2",
+ "LSM6DXX_VAL_CTRL7_G_HPM_G_1040": "3",
+ "LSM6DXX_VAL_CTRL9_XL_I3C_DISABLE": "BIT(1)"
+ },
+ "lsm6dxxRegister_e": {
+ "_source": "../../../src/main/drivers/accgyro/accgyro_lsm6dxx.h",
+ "LSM6DXX_REG_COUNTER_BDR1": "11",
+ "LSM6DXX_REG_INT1_CTRL": "13",
+ "LSM6DXX_REG_INT2_CTRL": "14",
+ "LSM6DXX_REG_WHO_AM_I": "15",
+ "LSM6DXX_REG_CTRL1_XL": "16",
+ "LSM6DXX_REG_CTRL2_G": "17",
+ "LSM6DXX_REG_CTRL3_C": "18",
+ "LSM6DXX_REG_CTRL4_C": "19",
+ "LSM6DXX_REG_CTRL5_C": "20",
+ "LSM6DXX_REG_CTRL6_C": "21",
+ "LSM6DXX_REG_CTRL7_G": "22",
+ "LSM6DXX_REG_CTRL8_XL": "23",
+ "LSM6DXX_REG_CTRL9_XL": "24",
+ "LSM6DXX_REG_CTRL10_C": "25",
+ "LSM6DXX_REG_STATUS": "30",
+ "LSM6DXX_REG_OUT_TEMP_L": "32",
+ "LSM6DXX_REG_OUT_TEMP_H": "33",
+ "LSM6DXX_REG_OUTX_L_G": "34",
+ "LSM6DXX_REG_OUTX_H_G": "35",
+ "LSM6DXX_REG_OUTY_L_G": "36",
+ "LSM6DXX_REG_OUTY_H_G": "37",
+ "LSM6DXX_REG_OUTZ_L_G": "38",
+ "LSM6DXX_REG_OUTZ_H_G": "39",
+ "LSM6DXX_REG_OUTX_L_A": "40",
+ "LSM6DXX_REG_OUTX_H_A": "41",
+ "LSM6DXX_REG_OUTY_L_A": "42",
+ "LSM6DXX_REG_OUTY_H_A": "43",
+ "LSM6DXX_REG_OUTZ_L_A": "44",
+ "LSM6DXX_REG_OUTZ_H_A": "45"
+ },
+ "ltm_frame_e": {
+ "_source": "../../../src/main/telemetry/ltm.h",
+ "LTM_FRAME_START": "0",
+ "LTM_AFRAME": "LTM_FRAME_START",
+ "LTM_SFRAME": "",
+ "LTM_GFRAME": [
+ "",
+ "USE_GPS"
+ ],
+ "LTM_OFRAME": [
+ "",
+ "USE_GPS"
+ ],
+ "LTM_XFRAME": [
+ "",
+ "USE_GPS"
+ ],
+ "LTM_NFRAME": "",
+ "LTM_FRAME_COUNT": ""
+ },
+ "ltm_modes_e": {
+ "_source": "../../../src/main/telemetry/ltm.h",
+ "LTM_MODE_MANUAL": "0",
+ "LTM_MODE_RATE": "1",
+ "LTM_MODE_ANGLE": "2",
+ "LTM_MODE_HORIZON": "3",
+ "LTM_MODE_ACRO": "4",
+ "LTM_MODE_STABALIZED1": "5",
+ "LTM_MODE_STABALIZED2": "6",
+ "LTM_MODE_STABILIZED3": "7",
+ "LTM_MODE_ALTHOLD": "8",
+ "LTM_MODE_GPSHOLD": "9",
+ "LTM_MODE_WAYPOINTS": "10",
+ "LTM_MODE_HEADHOLD": "11",
+ "LTM_MODE_CIRCLE": "12",
+ "LTM_MODE_RTH": "13",
+ "LTM_MODE_FOLLOWWME": "14",
+ "LTM_MODE_LAND": "15",
+ "LTM_MODE_FLYBYWIRE1": "16",
+ "LTM_MODE_FLYBYWIRE2": "17",
+ "LTM_MODE_CRUISE": "18",
+ "LTM_MODE_UNKNOWN": "19",
+ "LTM_MODE_LAUNCH": "20",
+ "LTM_MODE_AUTOTUNE": "21"
+ },
+ "ltmUpdateRate_e": {
+ "_source": "../../../src/main/telemetry/telemetry.h",
+ "LTM_RATE_NORMAL": "0",
+ "LTM_RATE_MEDIUM": "1",
+ "LTM_RATE_SLOW": "2"
+ },
+ "magSensor_e": {
+ "_source": "../../../src/main/sensors/compass.h",
+ "MAG_NONE": "0",
+ "MAG_AUTODETECT": "1",
+ "MAG_HMC5883": "2",
+ "MAG_AK8975": "3",
+ "MAG_MAG3110": "4",
+ "MAG_AK8963": "5",
+ "MAG_IST8310": "6",
+ "MAG_QMC5883": "7",
+ "MAG_QMC5883P": "8",
+ "MAG_MPU9250": "9",
+ "MAG_IST8308": "10",
+ "MAG_LIS3MDL": "11",
+ "MAG_MSP": "12",
+ "MAG_RM3100": "13",
+ "MAG_VCM5883": "14",
+ "MAG_MLX90393": "15",
+ "MAG_FAKE": "16",
+ "MAG_MAX": "MAG_FAKE"
+ },
+ "mavFrameSupportMask_e": {
+ "_source": "../../../src/main/telemetry/mavlink.c",
+ "MAV_FRAME_SUPPORTED_NONE": "0",
+ "MAV_FRAME_SUPPORTED_GLOBAL": "(1 << 0)",
+ "MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT": "(1 << 1)",
+ "MAV_FRAME_SUPPORTED_GLOBAL_INT": "(1 << 2)",
+ "MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT_INT": "(1 << 3)"
+ },
+ "mavlinkAutopilotType_e": {
+ "_source": "../../../src/main/telemetry/telemetry.h",
+ "MAVLINK_AUTOPILOT_GENERIC": "0",
+ "MAVLINK_AUTOPILOT_ARDUPILOT": "1"
+ },
+ "mavlinkRadio_e": {
+ "_source": "../../../src/main/telemetry/telemetry.h",
+ "MAVLINK_RADIO_GENERIC": "0",
+ "MAVLINK_RADIO_ELRS": "1",
+ "MAVLINK_RADIO_SIK": "2"
+ },
+ "measurementSteps_e": {
+ "_source": "../../../src/main/drivers/rangefinder/rangefinder_vl53l0x.c",
+ "MEASUREMENT_START": "0",
+ "MEASUREMENT_WAIT": "1",
+ "MEASUREMENT_READ": "2"
+ },
+ "mixerProfileATRequest_e": {
+ "_source": "../../../src/main/flight/mixer_profile.h",
+ "MIXERAT_REQUEST_NONE": "0",
+ "MIXERAT_REQUEST_RTH": "1",
+ "MIXERAT_REQUEST_LAND": "2",
+ "MIXERAT_REQUEST_ABORT": "3"
+ },
+ "mixerProfileATState_e": {
+ "_source": "../../../src/main/flight/mixer_profile.h",
+ "MIXERAT_PHASE_IDLE": "0",
+ "MIXERAT_PHASE_TRANSITION_INITIALIZE": "1",
+ "MIXERAT_PHASE_TRANSITIONING": "2",
+ "MIXERAT_PHASE_DONE": "3"
+ },
+ "modeActivationOperator_e": {
+ "_source": "../../../src/main/fc/rc_modes.h",
+ "MODE_OPERATOR_OR": "0",
+ "MODE_OPERATOR_AND": "1"
+ },
+ "motorPwmProtocolTypes_e": {
+ "_source": "../../../src/main/drivers/pwm_mapping.h",
+ "PWM_TYPE_STANDARD": "0",
+ "PWM_TYPE_ONESHOT125": "1",
+ "PWM_TYPE_MULTISHOT": "2",
+ "PWM_TYPE_BRUSHED": "3",
+ "PWM_TYPE_DSHOT150": "4",
+ "PWM_TYPE_DSHOT300": "5",
+ "PWM_TYPE_DSHOT600": "6"
+ },
+ "motorStatus_e": {
+ "_source": "../../../src/main/flight/mixer.h",
+ "MOTOR_STOPPED_USER": "0",
+ "MOTOR_STOPPED_AUTO": "1",
+ "MOTOR_RUNNING": "2"
+ },
+ "mpu9250CompassReadState_e": {
+ "_source": "../../../src/main/drivers/compass/compass_mpu9250.c",
+ "CHECK_STATUS": "0",
+ "WAITING_FOR_STATUS": "1",
+ "WAITING_FOR_DATA": "2"
+ },
+ "mspFlashfsFlags_e": {
+ "_source": "../../../src/main/fc/fc_msp.c",
+ "MSP_FLASHFS_BIT_READY": "1",
+ "MSP_FLASHFS_BIT_SUPPORTED": "2"
+ },
+ "mspPassthroughType_e": {
+ "_source": "../../../src/main/fc/fc_msp.c",
+ "MSP_PASSTHROUGH_SERIAL_ID": "253",
+ "MSP_PASSTHROUGH_SERIAL_FUNCTION_ID": "254",
+ "MSP_PASSTHROUGH_ESC_4WAY": "255"
+ },
+ "mspSDCardFlags_e": {
+ "_source": "../../../src/main/fc/fc_msp.c",
+ "MSP_SDCARD_FLAG_SUPPORTTED": "1"
+ },
+ "mspSDCardState_e": {
+ "_source": "../../../src/main/fc/fc_msp.c",
+ "MSP_SDCARD_STATE_NOT_PRESENT": "0",
+ "MSP_SDCARD_STATE_FATAL": "1",
+ "MSP_SDCARD_STATE_CARD_INIT": "2",
+ "MSP_SDCARD_STATE_FS_INIT": "3",
+ "MSP_SDCARD_STATE_READY": "4"
+ },
+ "multi_function_e": {
+ "_source": "../../../src/main/fc/multifunction.h",
+ "MULTI_FUNC_NONE": "0",
+ "MULTI_FUNC_1": "1",
+ "MULTI_FUNC_2": "2",
+ "MULTI_FUNC_3": "3",
+ "MULTI_FUNC_4": "4",
+ "MULTI_FUNC_5": "5",
+ "MULTI_FUNC_6": "6",
+ "MULTI_FUNC_END": "7"
+ },
+ "multiFunctionFlags_e": {
+ "_source": "../../../src/main/fc/multifunction.h",
+ "MF_SUSPEND_SAFEHOMES": "(1 << 0)",
+ "MF_SUSPEND_TRACKBACK": "(1 << 1)",
+ "MF_TURTLE_MODE": "(1 << 2)"
+ },
+ "nav_reset_type_e": {
+ "_source": "../../../src/main/navigation/navigation.h",
+ "NAV_RESET_NEVER": "0",
+ "NAV_RESET_ON_FIRST_ARM": "1",
+ "NAV_RESET_ON_EACH_ARM": "2"
+ },
+ "navAGLEstimateQuality_e": {
+ "_source": "../../../src/main/navigation/navigation_pos_estimator_private.h",
+ "SURFACE_QUAL_LOW": "0",
+ "SURFACE_QUAL_MID": "1",
+ "SURFACE_QUAL_HIGH": "2"
+ },
+ "navArmingBlocker_e": {
+ "_source": "../../../src/main/navigation/navigation.h",
+ "NAV_ARMING_BLOCKER_NONE": "0",
+ "NAV_ARMING_BLOCKER_MISSING_GPS_FIX": "1",
+ "NAV_ARMING_BLOCKER_NAV_IS_ALREADY_ACTIVE": "2",
+ "NAV_ARMING_BLOCKER_FIRST_WAYPOINT_TOO_FAR": "3",
+ "NAV_ARMING_BLOCKER_JUMP_WAYPOINT_ERROR": "4"
+ },
+ "navDefaultAltitudeSensor_e": {
+ "_source": "../../../src/main/navigation/navigation_pos_estimator_private.h",
+ "ALTITUDE_SOURCE_GPS": "0",
+ "ALTITUDE_SOURCE_BARO": "1",
+ "ALTITUDE_SOURCE_GPS_ONLY": "2",
+ "ALTITUDE_SOURCE_BARO_ONLY": "3"
+ },
+ "navExtraArmingSafety_e": {
+ "_source": "../../../src/main/navigation/navigation.h",
+ "NAV_EXTRA_ARMING_SAFETY_ON": "0",
+ "NAV_EXTRA_ARMING_SAFETY_ALLOW_BYPASS": "1"
+ },
+ "navFwLaunchStatus_e": {
+ "_source": "../../../src/main/navigation/navigation.h",
+ "FW_LAUNCH_DETECTED": "5",
+ "FW_LAUNCH_ABORTED": "10",
+ "FW_LAUNCH_FLYING": "11"
+ },
+ "navigationEstimateStatus_e": {
+ "_source": "../../../src/main/navigation/navigation_private.h",
+ "EST_NONE": "0",
+ "EST_USABLE": "1",
+ "EST_TRUSTED": "2"
+ },
+ "navigationFSMEvent_t": {
+ "_source": "../../../src/main/navigation/navigation_private.h",
+ "NAV_FSM_EVENT_NONE": "0",
+ "NAV_FSM_EVENT_TIMEOUT": "1",
+ "NAV_FSM_EVENT_SUCCESS": "2",
+ "NAV_FSM_EVENT_ERROR": "3",
+ "NAV_FSM_EVENT_SWITCH_TO_IDLE": "4",
+ "NAV_FSM_EVENT_SWITCH_TO_ALTHOLD": "5",
+ "NAV_FSM_EVENT_SWITCH_TO_POSHOLD_3D": "6",
+ "NAV_FSM_EVENT_SWITCH_TO_RTH": "7",
+ "NAV_FSM_EVENT_SWITCH_TO_WAYPOINT": "8",
+ "NAV_FSM_EVENT_SWITCH_TO_EMERGENCY_LANDING": "9",
+ "NAV_FSM_EVENT_SWITCH_TO_LAUNCH": "10",
+ "NAV_FSM_EVENT_SWITCH_TO_COURSE_HOLD": "11",
+ "NAV_FSM_EVENT_SWITCH_TO_CRUISE": "12",
+ "NAV_FSM_EVENT_SWITCH_TO_COURSE_ADJ": "13",
+ "NAV_FSM_EVENT_SWITCH_TO_MIXERAT": "14",
+ "NAV_FSM_EVENT_SWITCH_TO_NAV_STATE_FW_LANDING": "15",
+ "NAV_FSM_EVENT_SWITCH_TO_SEND_TO": "16",
+ "NAV_FSM_EVENT_STATE_SPECIFIC_1": "17",
+ "NAV_FSM_EVENT_STATE_SPECIFIC_2": "18",
+ "NAV_FSM_EVENT_STATE_SPECIFIC_3": "19",
+ "NAV_FSM_EVENT_STATE_SPECIFIC_4": "20",
+ "NAV_FSM_EVENT_STATE_SPECIFIC_5": "21",
+ "NAV_FSM_EVENT_SWITCH_TO_NAV_STATE_FW_LANDING_ABORT": "NAV_FSM_EVENT_STATE_SPECIFIC_1",
+ "NAV_FSM_EVENT_SWITCH_TO_NAV_STATE_FW_LANDING_FINISHED": "NAV_FSM_EVENT_STATE_SPECIFIC_2",
+ "NAV_FSM_EVENT_SWITCH_TO_WAYPOINT_HOLD_TIME": "NAV_FSM_EVENT_STATE_SPECIFIC_1",
+ "NAV_FSM_EVENT_SWITCH_TO_WAYPOINT_RTH_LAND": "NAV_FSM_EVENT_STATE_SPECIFIC_2",
+ "NAV_FSM_EVENT_SWITCH_TO_WAYPOINT_FINISHED": "NAV_FSM_EVENT_STATE_SPECIFIC_3",
+ "NAV_FSM_EVENT_SWITCH_TO_NAV_STATE_RTH_INITIALIZE": "NAV_FSM_EVENT_STATE_SPECIFIC_1",
+ "NAV_FSM_EVENT_SWITCH_TO_NAV_STATE_RTH_TRACKBACK": "NAV_FSM_EVENT_STATE_SPECIFIC_2",
+ "NAV_FSM_EVENT_SWITCH_TO_RTH_HEAD_HOME": "NAV_FSM_EVENT_STATE_SPECIFIC_3",
+ "NAV_FSM_EVENT_SWITCH_TO_RTH_LOITER_ABOVE_HOME": "NAV_FSM_EVENT_STATE_SPECIFIC_4",
+ "NAV_FSM_EVENT_SWITCH_TO_RTH_LANDING": "NAV_FSM_EVENT_STATE_SPECIFIC_5",
+ "NAV_FSM_EVENT_COUNT": ""
+ },
+ "navigationFSMState_t": {
+ "_source": "../../../src/main/navigation/navigation_private.h",
+ "NAV_STATE_UNDEFINED": "0",
+ "NAV_STATE_IDLE": "1",
+ "NAV_STATE_ALTHOLD_INITIALIZE": "2",
+ "NAV_STATE_ALTHOLD_IN_PROGRESS": "3",
+ "NAV_STATE_POSHOLD_3D_INITIALIZE": "4",
+ "NAV_STATE_POSHOLD_3D_IN_PROGRESS": "5",
+ "NAV_STATE_RTH_INITIALIZE": "6",
+ "NAV_STATE_RTH_CLIMB_TO_SAFE_ALT": "7",
+ "NAV_STATE_RTH_TRACKBACK": "8",
+ "NAV_STATE_RTH_HEAD_HOME": "9",
+ "NAV_STATE_RTH_LOITER_PRIOR_TO_LANDING": "10",
+ "NAV_STATE_RTH_LOITER_ABOVE_HOME": "11",
+ "NAV_STATE_RTH_LANDING": "12",
+ "NAV_STATE_RTH_FINISHING": "13",
+ "NAV_STATE_RTH_FINISHED": "14",
+ "NAV_STATE_WAYPOINT_INITIALIZE": "15",
+ "NAV_STATE_WAYPOINT_PRE_ACTION": "16",
+ "NAV_STATE_WAYPOINT_IN_PROGRESS": "17",
+ "NAV_STATE_WAYPOINT_REACHED": "18",
+ "NAV_STATE_WAYPOINT_HOLD_TIME": "19",
+ "NAV_STATE_WAYPOINT_NEXT": "20",
+ "NAV_STATE_WAYPOINT_FINISHED": "21",
+ "NAV_STATE_WAYPOINT_RTH_LAND": "22",
+ "NAV_STATE_EMERGENCY_LANDING_INITIALIZE": "23",
+ "NAV_STATE_EMERGENCY_LANDING_IN_PROGRESS": "24",
+ "NAV_STATE_EMERGENCY_LANDING_FINISHED": "25",
+ "NAV_STATE_LAUNCH_INITIALIZE": "26",
+ "NAV_STATE_LAUNCH_WAIT": "27",
+ "NAV_STATE_LAUNCH_IN_PROGRESS": "28",
+ "NAV_STATE_COURSE_HOLD_INITIALIZE": "29",
+ "NAV_STATE_COURSE_HOLD_IN_PROGRESS": "30",
+ "NAV_STATE_COURSE_HOLD_ADJUSTING": "31",
+ "NAV_STATE_CRUISE_INITIALIZE": "32",
+ "NAV_STATE_CRUISE_IN_PROGRESS": "33",
+ "NAV_STATE_CRUISE_ADJUSTING": "34",
+ "NAV_STATE_FW_LANDING_CLIMB_TO_LOITER": "35",
+ "NAV_STATE_FW_LANDING_LOITER": "36",
+ "NAV_STATE_FW_LANDING_APPROACH": "37",
+ "NAV_STATE_FW_LANDING_GLIDE": "38",
+ "NAV_STATE_FW_LANDING_FLARE": "39",
+ "NAV_STATE_FW_LANDING_FINISHED": "40",
+ "NAV_STATE_FW_LANDING_ABORT": "41",
+ "NAV_STATE_MIXERAT_INITIALIZE": "42",
+ "NAV_STATE_MIXERAT_IN_PROGRESS": "43",
+ "NAV_STATE_MIXERAT_ABORT": "44",
+ "NAV_STATE_SEND_TO_INITALIZE": "45",
+ "NAV_STATE_SEND_TO_IN_PROGESS": "46",
+ "NAV_STATE_SEND_TO_FINISHED": "47",
+ "NAV_STATE_COUNT": "48"
+ },
+ "navigationFSMStateFlags_t": {
+ "_source": "../../../src/main/navigation/navigation_private.h",
+ "NAV_CTL_ALT": "(1 << 0)",
+ "NAV_CTL_POS": "(1 << 1)",
+ "NAV_CTL_YAW": "(1 << 2)",
+ "NAV_CTL_EMERG": "(1 << 3)",
+ "NAV_CTL_LAUNCH": "(1 << 4)",
+ "NAV_REQUIRE_ANGLE": "(1 << 5)",
+ "NAV_REQUIRE_ANGLE_FW": "(1 << 6)",
+ "NAV_REQUIRE_MAGHOLD": "(1 << 7)",
+ "NAV_REQUIRE_THRTILT": "(1 << 8)",
+ "NAV_AUTO_RTH": "(1 << 9)",
+ "NAV_AUTO_WP": "(1 << 10)",
+ "NAV_RC_ALT": "(1 << 11)",
+ "NAV_RC_POS": "(1 << 12)",
+ "NAV_RC_YAW": "(1 << 13)",
+ "NAV_CTL_LAND": "(1 << 14)",
+ "NAV_AUTO_WP_DONE": "(1 << 15)",
+ "NAV_MIXERAT": "(1 << 16)",
+ "NAV_CTL_HOLD": "(1 << 17)"
+ },
+ "navigationHomeFlags_t": {
+ "_source": "../../../src/main/navigation/navigation_private.h",
+ "NAV_HOME_INVALID": "0",
+ "NAV_HOME_VALID_XY": "1 << 0",
+ "NAV_HOME_VALID_Z": "1 << 1",
+ "NAV_HOME_VALID_HEADING": "1 << 2",
+ "NAV_HOME_VALID_ALL": "NAV_HOME_VALID_XY | NAV_HOME_VALID_Z | NAV_HOME_VALID_HEADING"
+ },
+ "navigationPersistentId_e": {
+ "_source": "../../../src/main/navigation/navigation_private.h",
+ "NAV_PERSISTENT_ID_UNDEFINED": "0",
+ "NAV_PERSISTENT_ID_IDLE": "1",
+ "NAV_PERSISTENT_ID_ALTHOLD_INITIALIZE": "2",
+ "NAV_PERSISTENT_ID_ALTHOLD_IN_PROGRESS": "3",
+ "NAV_PERSISTENT_ID_UNUSED_1": "4",
+ "NAV_PERSISTENT_ID_UNUSED_2": "5",
+ "NAV_PERSISTENT_ID_POSHOLD_3D_INITIALIZE": "6",
+ "NAV_PERSISTENT_ID_POSHOLD_3D_IN_PROGRESS": "7",
+ "NAV_PERSISTENT_ID_RTH_INITIALIZE": "8",
+ "NAV_PERSISTENT_ID_RTH_CLIMB_TO_SAFE_ALT": "9",
+ "NAV_PERSISTENT_ID_RTH_HEAD_HOME": "10",
+ "NAV_PERSISTENT_ID_RTH_LOITER_PRIOR_TO_LANDING": "11",
+ "NAV_PERSISTENT_ID_RTH_LANDING": "12",
+ "NAV_PERSISTENT_ID_RTH_FINISHING": "13",
+ "NAV_PERSISTENT_ID_RTH_FINISHED": "14",
+ "NAV_PERSISTENT_ID_WAYPOINT_INITIALIZE": "15",
+ "NAV_PERSISTENT_ID_WAYPOINT_PRE_ACTION": "16",
+ "NAV_PERSISTENT_ID_WAYPOINT_IN_PROGRESS": "17",
+ "NAV_PERSISTENT_ID_WAYPOINT_REACHED": "18",
+ "NAV_PERSISTENT_ID_WAYPOINT_NEXT": "19",
+ "NAV_PERSISTENT_ID_WAYPOINT_FINISHED": "20",
+ "NAV_PERSISTENT_ID_WAYPOINT_RTH_LAND": "21",
+ "NAV_PERSISTENT_ID_EMERGENCY_LANDING_INITIALIZE": "22",
+ "NAV_PERSISTENT_ID_EMERGENCY_LANDING_IN_PROGRESS": "23",
+ "NAV_PERSISTENT_ID_EMERGENCY_LANDING_FINISHED": "24",
+ "NAV_PERSISTENT_ID_LAUNCH_INITIALIZE": "25",
+ "NAV_PERSISTENT_ID_LAUNCH_WAIT": "26",
+ "NAV_PERSISTENT_ID_UNUSED_3": "27",
+ "NAV_PERSISTENT_ID_LAUNCH_IN_PROGRESS": "28",
+ "NAV_PERSISTENT_ID_COURSE_HOLD_INITIALIZE": "29",
+ "NAV_PERSISTENT_ID_COURSE_HOLD_IN_PROGRESS": "30",
+ "NAV_PERSISTENT_ID_COURSE_HOLD_ADJUSTING": "31",
+ "NAV_PERSISTENT_ID_CRUISE_INITIALIZE": "32",
+ "NAV_PERSISTENT_ID_CRUISE_IN_PROGRESS": "33",
+ "NAV_PERSISTENT_ID_CRUISE_ADJUSTING": "34",
+ "NAV_PERSISTENT_ID_WAYPOINT_HOLD_TIME": "35",
+ "NAV_PERSISTENT_ID_RTH_LOITER_ABOVE_HOME": "36",
+ "NAV_PERSISTENT_ID_UNUSED_4": "37",
+ "NAV_PERSISTENT_ID_RTH_TRACKBACK": "38",
+ "NAV_PERSISTENT_ID_MIXERAT_INITIALIZE": "39",
+ "NAV_PERSISTENT_ID_MIXERAT_IN_PROGRESS": "40",
+ "NAV_PERSISTENT_ID_MIXERAT_ABORT": "41",
+ "NAV_PERSISTENT_ID_FW_LANDING_CLIMB_TO_LOITER": "42",
+ "NAV_PERSISTENT_ID_FW_LANDING_LOITER": "43",
+ "NAV_PERSISTENT_ID_FW_LANDING_APPROACH": "44",
+ "NAV_PERSISTENT_ID_FW_LANDING_GLIDE": "45",
+ "NAV_PERSISTENT_ID_FW_LANDING_FLARE": "46",
+ "NAV_PERSISTENT_ID_FW_LANDING_ABORT": "47",
+ "NAV_PERSISTENT_ID_FW_LANDING_FINISHED": "48",
+ "NAV_PERSISTENT_ID_SEND_TO_INITALIZE": "49",
+ "NAV_PERSISTENT_ID_SEND_TO_IN_PROGRES": "50",
+ "NAV_PERSISTENT_ID_SEND_TO_FINISHED": "51"
+ },
+ "navMcAltHoldThrottle_e": {
+ "_source": "../../../src/main/navigation/navigation.h",
+ "MC_ALT_HOLD_STICK": "0",
+ "MC_ALT_HOLD_MID": "1",
+ "MC_ALT_HOLD_HOVER": "2"
+ },
+ "navMissionRestart_e": {
+ "_source": "../../../src/main/navigation/navigation.h",
+ "WP_MISSION_START": "0",
+ "WP_MISSION_RESUME": "1",
+ "WP_MISSION_SWITCH": "2"
+ },
+ "navOverridesMotorStop_e": {
+ "_source": "../../../src/main/navigation/navigation.h",
+ "NOMS_OFF_ALWAYS": "0",
+ "NOMS_OFF": "1",
+ "NOMS_AUTO_ONLY": "2",
+ "NOMS_ALL_NAV": "3"
+ },
+ "navPositionEstimationFlags_e": {
+ "_source": "../../../src/main/navigation/navigation_pos_estimator_private.h",
+ "EST_GPS_XY_VALID": "(1 << 0)",
+ "EST_GPS_Z_VALID": "(1 << 1)",
+ "EST_BARO_VALID": "(1 << 2)",
+ "EST_SURFACE_VALID": "(1 << 3)",
+ "EST_FLOW_VALID": "(1 << 4)",
+ "EST_XY_VALID": "(1 << 5)",
+ "EST_Z_VALID": "(1 << 6)"
+ },
+ "navRTHAllowLanding_e": {
+ "_source": "../../../src/main/navigation/navigation.h",
+ "NAV_RTH_ALLOW_LANDING_NEVER": "0",
+ "NAV_RTH_ALLOW_LANDING_ALWAYS": "1",
+ "NAV_RTH_ALLOW_LANDING_FS_ONLY": "2"
+ },
+ "navRTHClimbFirst_e": {
+ "_source": "../../../src/main/navigation/navigation.h",
+ "RTH_CLIMB_OFF": "0",
+ "RTH_CLIMB_ON": "1",
+ "RTH_CLIMB_ON_FW_SPIRAL": "2"
+ },
+ "navSetWaypointFlags_t": {
+ "_source": "../../../src/main/navigation/navigation_private.h",
+ "NAV_POS_UPDATE_NONE": "0",
+ "NAV_POS_UPDATE_Z": "1 << 1",
+ "NAV_POS_UPDATE_XY": "1 << 0",
+ "NAV_POS_UPDATE_HEADING": "1 << 2",
+ "NAV_POS_UPDATE_BEARING": "1 << 3",
+ "NAV_POS_UPDATE_BEARING_TAIL_FIRST": "1 << 4"
+ },
+ "navSystemStatus_Error_e": {
+ "_source": "../../../src/main/navigation/navigation.h",
+ "MW_NAV_ERROR_NONE": "0",
+ "MW_NAV_ERROR_TOOFAR": "1",
+ "MW_NAV_ERROR_SPOILED_GPS": "2",
+ "MW_NAV_ERROR_WP_CRC": "3",
+ "MW_NAV_ERROR_FINISH": "4",
+ "MW_NAV_ERROR_TIMEWAIT": "5",
+ "MW_NAV_ERROR_INVALID_JUMP": "6",
+ "MW_NAV_ERROR_INVALID_DATA": "7",
+ "MW_NAV_ERROR_WAIT_FOR_RTH_ALT": "8",
+ "MW_NAV_ERROR_GPS_FIX_LOST": "9",
+ "MW_NAV_ERROR_DISARMED": "10",
+ "MW_NAV_ERROR_LANDING": "11"
+ },
+ "navSystemStatus_Flags_e": {
+ "_source": "../../../src/main/navigation/navigation.h",
+ "MW_NAV_FLAG_ADJUSTING_POSITION": "1 << 0",
+ "MW_NAV_FLAG_ADJUSTING_ALTITUDE": "1 << 1"
+ },
+ "navSystemStatus_Mode_e": {
+ "_source": "../../../src/main/navigation/navigation.h",
+ "MW_GPS_MODE_NONE": "0",
+ "MW_GPS_MODE_HOLD": "1",
+ "MW_GPS_MODE_RTH": "2",
+ "MW_GPS_MODE_NAV": "3",
+ "MW_GPS_MODE_EMERG": "15"
+ },
+ "navSystemStatus_State_e": {
+ "_source": "../../../src/main/navigation/navigation.h",
+ "MW_NAV_STATE_NONE": "0",
+ "MW_NAV_STATE_RTH_START": "1",
+ "MW_NAV_STATE_RTH_ENROUTE": "2",
+ "MW_NAV_STATE_HOLD_INFINIT": "3",
+ "MW_NAV_STATE_HOLD_TIMED": "4",
+ "MW_NAV_STATE_WP_ENROUTE": "5",
+ "MW_NAV_STATE_PROCESS_NEXT": "6",
+ "MW_NAV_STATE_DO_JUMP": "7",
+ "MW_NAV_STATE_LAND_START": "8",
+ "MW_NAV_STATE_LAND_IN_PROGRESS": "9",
+ "MW_NAV_STATE_LANDED": "10",
+ "MW_NAV_STATE_LAND_SETTLE": "11",
+ "MW_NAV_STATE_LAND_START_DESCENT": "12",
+ "MW_NAV_STATE_HOVER_ABOVE_HOME": "13",
+ "MW_NAV_STATE_EMERGENCY_LANDING": "14",
+ "MW_NAV_STATE_RTH_CLIMB": "15"
+ },
+ "navWaypointActions_e": {
+ "_source": "../../../src/main/navigation/navigation.h",
+ "NAV_WP_ACTION_WAYPOINT": "1",
+ "NAV_WP_ACTION_HOLD_TIME": "3",
+ "NAV_WP_ACTION_RTH": "4",
+ "NAV_WP_ACTION_SET_POI": "5",
+ "NAV_WP_ACTION_JUMP": "6",
+ "NAV_WP_ACTION_SET_HEAD": "7",
+ "NAV_WP_ACTION_LAND": "8"
+ },
+ "navWaypointFlags_e": {
+ "_source": "../../../src/main/navigation/navigation.h",
+ "NAV_WP_FLAG_HOME": "72",
+ "NAV_WP_FLAG_LAST": "165"
+ },
+ "navWaypointHeadings_e": {
+ "_source": "../../../src/main/navigation/navigation.h",
+ "NAV_WP_HEAD_MODE_NONE": "0",
+ "NAV_WP_HEAD_MODE_POI": "1",
+ "NAV_WP_HEAD_MODE_FIXED": "2"
+ },
+ "navWaypointP3Flags_e": {
+ "_source": "../../../src/main/navigation/navigation.h",
+ "NAV_WP_ALTMODE": "(1<<0)",
+ "NAV_WP_USER1": "(1<<1)",
+ "NAV_WP_USER2": "(1<<2)",
+ "NAV_WP_USER3": "(1<<3)",
+ "NAV_WP_USER4": "(1<<4)"
+ },
+ "opflowQuality_e": {
+ "_source": "../../../src/main/sensors/opflow.h",
+ "OPFLOW_QUALITY_INVALID": "0",
+ "OPFLOW_QUALITY_VALID": "1"
+ },
+ "opticalFlowSensor_e": {
+ "_source": "../../../src/main/sensors/opflow.h",
+ "OPFLOW_NONE": "0",
+ "OPFLOW_CXOF": "1",
+ "OPFLOW_MSP": "2",
+ "OPFLOW_FAKE": "3"
+ },
+ "osd_adsb_warning_style_e": {
+ "_source": "../../../src/main/io/osd.h",
+ "OSD_ADSB_WARNING_STYLE_COMPACT": "0",
+ "OSD_ADSB_WARNING_STYLE_EXTENDED": "1"
+ },
+ "osd_ahi_style_e": {
+ "_source": "../../../src/main/io/osd.h",
+ "OSD_AHI_STYLE_DEFAULT": "0",
+ "OSD_AHI_STYLE_LINE": "1"
+ },
+ "osd_alignment_e": {
+ "_source": "../../../src/main/io/osd.h",
+ "OSD_ALIGN_LEFT": "0",
+ "OSD_ALIGN_RIGHT": "1"
+ },
+ "osd_crosshairs_style_e": {
+ "_source": "../../../src/main/io/osd.h",
+ "OSD_CROSSHAIRS_STYLE_DEFAULT": "0",
+ "OSD_CROSSHAIRS_STYLE_AIRCRAFT": "1",
+ "OSD_CROSSHAIRS_STYLE_TYPE3": "2",
+ "OSD_CROSSHAIRS_STYLE_TYPE4": "3",
+ "OSD_CROSSHAIRS_STYLE_TYPE5": "4",
+ "OSD_CROSSHAIRS_STYLE_TYPE6": "5",
+ "OSD_CROSSHAIRS_STYLE_TYPE7": "6"
+ },
+ "osd_crsf_lq_format_e": {
+ "_source": "../../../src/main/io/osd.h",
+ "OSD_CRSF_LQ_TYPE1": "0",
+ "OSD_CRSF_LQ_TYPE2": "1",
+ "OSD_CRSF_LQ_TYPE3": "2"
+ },
+ "osd_items_e": {
+ "_source": "../../../src/main/io/osd.h",
+ "OSD_RSSI_VALUE": "0",
+ "OSD_MAIN_BATT_VOLTAGE": "1",
+ "OSD_CROSSHAIRS": "2",
+ "OSD_ARTIFICIAL_HORIZON": "3",
+ "OSD_HORIZON_SIDEBARS": "4",
+ "OSD_ONTIME": "5",
+ "OSD_FLYTIME": "6",
+ "OSD_FLYMODE": "7",
+ "OSD_CRAFT_NAME": "8",
+ "OSD_THROTTLE_POS": "9",
+ "OSD_VTX_CHANNEL": "10",
+ "OSD_CURRENT_DRAW": "11",
+ "OSD_MAH_DRAWN": "12",
+ "OSD_GPS_SPEED": "13",
+ "OSD_GPS_SATS": "14",
+ "OSD_ALTITUDE": "15",
+ "OSD_ROLL_PIDS": "16",
+ "OSD_PITCH_PIDS": "17",
+ "OSD_YAW_PIDS": "18",
+ "OSD_POWER": "19",
+ "OSD_GPS_LON": "20",
+ "OSD_GPS_LAT": "21",
+ "OSD_HOME_DIR": "22",
+ "OSD_HOME_DIST": "23",
+ "OSD_HEADING": "24",
+ "OSD_VARIO": "25",
+ "OSD_VERTICAL_SPEED_INDICATOR": "26",
+ "OSD_AIR_SPEED": "27",
+ "OSD_ONTIME_FLYTIME": "28",
+ "OSD_RTC_TIME": "29",
+ "OSD_MESSAGES": "30",
+ "OSD_GPS_HDOP": "31",
+ "OSD_MAIN_BATT_CELL_VOLTAGE": "32",
+ "OSD_SCALED_THROTTLE_POS": "33",
+ "OSD_HEADING_GRAPH": "34",
+ "OSD_EFFICIENCY_MAH_PER_KM": "35",
+ "OSD_WH_DRAWN": "36",
+ "OSD_BATTERY_REMAINING_CAPACITY": "37",
+ "OSD_BATTERY_REMAINING_PERCENT": "38",
+ "OSD_EFFICIENCY_WH_PER_KM": "39",
+ "OSD_TRIP_DIST": "40",
+ "OSD_ATTITUDE_PITCH": "41",
+ "OSD_ATTITUDE_ROLL": "42",
+ "OSD_MAP_NORTH": "43",
+ "OSD_MAP_TAKEOFF": "44",
+ "OSD_RADAR": "45",
+ "OSD_WIND_SPEED_HORIZONTAL": "46",
+ "OSD_WIND_SPEED_VERTICAL": "47",
+ "OSD_REMAINING_FLIGHT_TIME_BEFORE_RTH": "48",
+ "OSD_REMAINING_DISTANCE_BEFORE_RTH": "49",
+ "OSD_HOME_HEADING_ERROR": "50",
+ "OSD_COURSE_HOLD_ERROR": "51",
+ "OSD_COURSE_HOLD_ADJUSTMENT": "52",
+ "OSD_SAG_COMPENSATED_MAIN_BATT_VOLTAGE": "53",
+ "OSD_MAIN_BATT_SAG_COMPENSATED_CELL_VOLTAGE": "54",
+ "OSD_POWER_SUPPLY_IMPEDANCE": "55",
+ "OSD_LEVEL_PIDS": "56",
+ "OSD_POS_XY_PIDS": "57",
+ "OSD_POS_Z_PIDS": "58",
+ "OSD_VEL_XY_PIDS": "59",
+ "OSD_VEL_Z_PIDS": "60",
+ "OSD_HEADING_P": "61",
+ "OSD_BOARD_ALIGN_ROLL": "62",
+ "OSD_BOARD_ALIGN_PITCH": "63",
+ "OSD_RC_EXPO": "64",
+ "OSD_RC_YAW_EXPO": "65",
+ "OSD_THROTTLE_EXPO": "66",
+ "OSD_PITCH_RATE": "67",
+ "OSD_ROLL_RATE": "68",
+ "OSD_YAW_RATE": "69",
+ "OSD_MANUAL_RC_EXPO": "70",
+ "OSD_MANUAL_RC_YAW_EXPO": "71",
+ "OSD_MANUAL_PITCH_RATE": "72",
+ "OSD_MANUAL_ROLL_RATE": "73",
+ "OSD_MANUAL_YAW_RATE": "74",
+ "OSD_NAV_FW_CRUISE_THR": "75",
+ "OSD_NAV_FW_PITCH2THR": "76",
+ "OSD_FW_MIN_THROTTLE_DOWN_PITCH_ANGLE": "77",
+ "OSD_DEBUG": "78",
+ "OSD_FW_ALT_PID_OUTPUTS": "79",
+ "OSD_FW_POS_PID_OUTPUTS": "80",
+ "OSD_MC_VEL_X_PID_OUTPUTS": "81",
+ "OSD_MC_VEL_Y_PID_OUTPUTS": "82",
+ "OSD_MC_VEL_Z_PID_OUTPUTS": "83",
+ "OSD_MC_POS_XYZ_P_OUTPUTS": "84",
+ "OSD_3D_SPEED": "85",
+ "OSD_IMU_TEMPERATURE": "86",
+ "OSD_BARO_TEMPERATURE": "87",
+ "OSD_TEMP_SENSOR_0_TEMPERATURE": "88",
+ "OSD_TEMP_SENSOR_1_TEMPERATURE": "89",
+ "OSD_TEMP_SENSOR_2_TEMPERATURE": "90",
+ "OSD_TEMP_SENSOR_3_TEMPERATURE": "91",
+ "OSD_TEMP_SENSOR_4_TEMPERATURE": "92",
+ "OSD_TEMP_SENSOR_5_TEMPERATURE": "93",
+ "OSD_TEMP_SENSOR_6_TEMPERATURE": "94",
+ "OSD_TEMP_SENSOR_7_TEMPERATURE": "95",
+ "OSD_ALTITUDE_MSL": "96",
+ "OSD_PLUS_CODE": "97",
+ "OSD_MAP_SCALE": "98",
+ "OSD_MAP_REFERENCE": "99",
+ "OSD_GFORCE": "100",
+ "OSD_GFORCE_X": "101",
+ "OSD_GFORCE_Y": "102",
+ "OSD_GFORCE_Z": "103",
+ "OSD_RC_SOURCE": "104",
+ "OSD_VTX_POWER": "105",
+ "OSD_ESC_RPM": "106",
+ "OSD_ESC_TEMPERATURE": "107",
+ "OSD_AZIMUTH": "108",
+ "OSD_RSSI_DBM": "109",
+ "OSD_LQ_UPLINK": "110",
+ "OSD_SNR_DB": "111",
+ "OSD_TX_POWER_UPLINK": "112",
+ "OSD_GVAR_0": "113",
+ "OSD_GVAR_1": "114",
+ "OSD_GVAR_2": "115",
+ "OSD_GVAR_3": "116",
+ "OSD_TPA": "117",
+ "OSD_NAV_FW_CONTROL_SMOOTHNESS": "118",
+ "OSD_VERSION": "119",
+ "OSD_RANGEFINDER": "120",
+ "OSD_PLIMIT_REMAINING_BURST_TIME": "121",
+ "OSD_PLIMIT_ACTIVE_CURRENT_LIMIT": "122",
+ "OSD_PLIMIT_ACTIVE_POWER_LIMIT": "123",
+ "OSD_GLIDESLOPE": "124",
+ "OSD_GPS_MAX_SPEED": "125",
+ "OSD_3D_MAX_SPEED": "126",
+ "OSD_AIR_MAX_SPEED": "127",
+ "OSD_ACTIVE_PROFILE": "128",
+ "OSD_MISSION": "129",
+ "OSD_SWITCH_INDICATOR_0": "130",
+ "OSD_SWITCH_INDICATOR_1": "131",
+ "OSD_SWITCH_INDICATOR_2": "132",
+ "OSD_SWITCH_INDICATOR_3": "133",
+ "OSD_TPA_TIME_CONSTANT": "134",
+ "OSD_FW_LEVEL_TRIM": "135",
+ "OSD_GLIDE_TIME_REMAINING": "136",
+ "OSD_GLIDE_RANGE": "137",
+ "OSD_CLIMB_EFFICIENCY": "138",
+ "OSD_NAV_WP_MULTI_MISSION_INDEX": "139",
+ "OSD_GROUND_COURSE": "140",
+ "OSD_CROSS_TRACK_ERROR": "141",
+ "OSD_PILOT_NAME": "142",
+ "OSD_PAN_SERVO_CENTRED": "143",
+ "OSD_MULTI_FUNCTION": "144",
+ "OSD_ODOMETER": "145",
+ "OSD_PILOT_LOGO": "146",
+ "OSD_CUSTOM_ELEMENT_1": "147",
+ "OSD_CUSTOM_ELEMENT_2": "148",
+ "OSD_CUSTOM_ELEMENT_3": "149",
+ "OSD_ADSB_WARNING": "150",
+ "OSD_ADSB_INFO": "151",
+ "OSD_BLACKBOX": "152",
+ "OSD_FORMATION_FLIGHT": "153",
+ "OSD_CUSTOM_ELEMENT_4": "154",
+ "OSD_CUSTOM_ELEMENT_5": "155",
+ "OSD_CUSTOM_ELEMENT_6": "156",
+ "OSD_CUSTOM_ELEMENT_7": "157",
+ "OSD_CUSTOM_ELEMENT_8": "158",
+ "OSD_LQ_DOWNLINK": "159",
+ "OSD_RX_POWER_DOWNLINK": "160",
+ "OSD_RX_BAND": "161",
+ "OSD_RX_MODE": "162",
+ "OSD_COURSE_TO_FENCE": "163",
+ "OSD_H_DIST_TO_FENCE": "164",
+ "OSD_V_DIST_TO_FENCE": "165",
+ "OSD_NAV_FW_ALT_CONTROL_RESPONSE": "166",
+ "OSD_NAV_MIN_GROUND_SPEED": "167",
+ "OSD_THROTTLE_GAUGE": "168",
+ "OSD_ITEM_COUNT": "169"
+ },
+ "osd_sidebar_arrow_e": {
+ "_source": "../../../src/main/io/osd_grid.c",
+ "OSD_SIDEBAR_ARROW_NONE": "0",
+ "OSD_SIDEBAR_ARROW_UP": "1",
+ "OSD_SIDEBAR_ARROW_DOWN": "2"
+ },
+ "osd_sidebar_scroll_e": {
+ "_source": "../../../src/main/io/osd.h",
+ "OSD_SIDEBAR_SCROLL_NONE": "0",
+ "OSD_SIDEBAR_SCROLL_ALTITUDE": "1",
+ "OSD_SIDEBAR_SCROLL_SPEED": "2",
+ "OSD_SIDEBAR_SCROLL_HOME_DISTANCE": "3",
+ "OSD_SIDEBAR_SCROLL_MAX": "OSD_SIDEBAR_SCROLL_HOME_DISTANCE"
+ },
+ "osd_SpeedTypes_e": {
+ "_source": "../../../src/main/io/osd.h",
+ "OSD_SPEED_TYPE_GROUND": "0",
+ "OSD_SPEED_TYPE_AIR": "1",
+ "OSD_SPEED_TYPE_3D": "2",
+ "OSD_SPEED_TYPE_MIN_GROUND": "3"
+ },
+ "osd_stats_energy_unit_e": {
+ "_source": "../../../src/main/io/osd.h",
+ "OSD_STATS_ENERGY_UNIT_MAH": "0",
+ "OSD_STATS_ENERGY_UNIT_WH": "1"
+ },
+ "osd_unit_e": {
+ "_source": "../../../src/main/io/osd.h",
+ "OSD_UNIT_IMPERIAL": "0",
+ "OSD_UNIT_METRIC": "1",
+ "OSD_UNIT_METRIC_MPH": "2",
+ "OSD_UNIT_UK": "3",
+ "OSD_UNIT_GA": "4",
+ "OSD_UNIT_MAX": "OSD_UNIT_GA"
+ },
+ "osdCustomElementType_e": {
+ "_source": "../../../src/main/io/osd/custom_elements.h",
+ "CUSTOM_ELEMENT_TYPE_NONE": "0",
+ "CUSTOM_ELEMENT_TYPE_TEXT": "1",
+ "CUSTOM_ELEMENT_TYPE_ICON_STATIC": "2",
+ "CUSTOM_ELEMENT_TYPE_ICON_GV": "3",
+ "CUSTOM_ELEMENT_TYPE_ICON_LC": "4",
+ "CUSTOM_ELEMENT_TYPE_GV_1": "5",
+ "CUSTOM_ELEMENT_TYPE_GV_2": "6",
+ "CUSTOM_ELEMENT_TYPE_GV_3": "7",
+ "CUSTOM_ELEMENT_TYPE_GV_4": "8",
+ "CUSTOM_ELEMENT_TYPE_GV_5": "9",
+ "CUSTOM_ELEMENT_TYPE_GV_FLOAT_1_1": "10",
+ "CUSTOM_ELEMENT_TYPE_GV_FLOAT_1_2": "11",
+ "CUSTOM_ELEMENT_TYPE_GV_FLOAT_2_1": "12",
+ "CUSTOM_ELEMENT_TYPE_GV_FLOAT_2_2": "13",
+ "CUSTOM_ELEMENT_TYPE_GV_FLOAT_3_1": "14",
+ "CUSTOM_ELEMENT_TYPE_GV_FLOAT_3_2": "15",
+ "CUSTOM_ELEMENT_TYPE_GV_FLOAT_4_1": "16",
+ "CUSTOM_ELEMENT_TYPE_LC_1": "17",
+ "CUSTOM_ELEMENT_TYPE_LC_2": "18",
+ "CUSTOM_ELEMENT_TYPE_LC_3": "19",
+ "CUSTOM_ELEMENT_TYPE_LC_4": "20",
+ "CUSTOM_ELEMENT_TYPE_LC_5": "21",
+ "CUSTOM_ELEMENT_TYPE_LC_FLOAT_1_1": "22",
+ "CUSTOM_ELEMENT_TYPE_LC_FLOAT_1_2": "23",
+ "CUSTOM_ELEMENT_TYPE_LC_FLOAT_2_1": "24",
+ "CUSTOM_ELEMENT_TYPE_LC_FLOAT_2_2": "25",
+ "CUSTOM_ELEMENT_TYPE_LC_FLOAT_3_1": "26",
+ "CUSTOM_ELEMENT_TYPE_LC_FLOAT_3_2": "27",
+ "CUSTOM_ELEMENT_TYPE_LC_FLOAT_4_1": "28",
+ "CUSTOM_ELEMENT_TYPE_END": "29"
+ },
+ "osdCustomElementTypeVisibility_e": {
+ "_source": "../../../src/main/io/osd/custom_elements.h",
+ "CUSTOM_ELEMENT_VISIBILITY_ALWAYS": "0",
+ "CUSTOM_ELEMENT_VISIBILITY_GV": "1",
+ "CUSTOM_ELEMENT_VISIBILITY_LOGIC_CON": "2"
+ },
+ "osdDrawPointType_e": {
+ "_source": "../../../src/main/io/osd_common.h",
+ "OSD_DRAW_POINT_TYPE_GRID": "0",
+ "OSD_DRAW_POINT_TYPE_PIXEL": "1"
+ },
+ "osdDriver_e": {
+ "_source": "../../../src/main/drivers/osd.h",
+ "OSD_DRIVER_NONE": "0",
+ "OSD_DRIVER_MAX7456": "1"
+ },
+ "osdSpeedSource_e": {
+ "_source": "../../../src/main/io/osd_common.h",
+ "OSD_SPEED_SOURCE_GROUND": "0",
+ "OSD_SPEED_SOURCE_3D": "1",
+ "OSD_SPEED_SOURCE_AIR": "2"
+ },
+ "outputMode_e": {
+ "_source": "../../../src/main/flight/mixer.h",
+ "OUTPUT_MODE_AUTO": "0",
+ "OUTPUT_MODE_MOTORS": "1",
+ "OUTPUT_MODE_SERVOS": "2",
+ "OUTPUT_MODE_LED": "3"
+ },
+ "pageId_e": {
+ "_source": "../../../src/main/io/dashboard.h",
+ "PAGE_WELCOME": "0",
+ "PAGE_ARMED": "1",
+ "PAGE_STATUS": "2"
+ },
+ "persistentObjectId_e": {
+ "_source": "../../../src/main/drivers/persistent.h",
+ "PERSISTENT_OBJECT_MAGIC": "0",
+ "PERSISTENT_OBJECT_RESET_REASON": "1",
+ "PERSISTENT_OBJECT_COUNT": "2"
+ },
+ "pidAutotuneState_e": {
+ "_source": "../../../src/main/flight/pid_autotune.c",
+ "DEMAND_TOO_LOW": "0",
+ "DEMAND_UNDERSHOOT": "1",
+ "DEMAND_OVERSHOOT": "2",
+ "TUNE_UPDATED": "3"
+ },
+ "pidControllerFlags_e": {
+ "_source": "../../../src/main/common/fp_pid.h",
+ "PID_DTERM_FROM_ERROR": "1 << 0",
+ "PID_ZERO_INTEGRATOR": "1 << 1",
+ "PID_SHRINK_INTEGRATOR": "1 << 2",
+ "PID_LIMIT_INTEGRATOR": "1 << 3",
+ "PID_FREEZE_INTEGRATOR": "1 << 4"
+ },
+ "pidIndex_e": {
+ "_source": "../../../src/main/flight/pid.h",
+ "PID_ROLL": "0",
+ "PID_PITCH": "1",
+ "PID_YAW": "2",
+ "PID_POS_Z": "3",
+ "PID_POS_XY": "4",
+ "PID_VEL_XY": "5",
+ "PID_SURFACE": "6",
+ "PID_LEVEL": "7",
+ "PID_HEADING": "8",
+ "PID_VEL_Z": "9",
+ "PID_POS_HEADING": "10",
+ "PID_ITEM_COUNT": "11"
+ },
+ "pidType_e": {
+ "_source": "../../../src/main/flight/pid.h",
+ "PID_TYPE_NONE": "0",
+ "PID_TYPE_PID": "1",
+ "PID_TYPE_PIFF": "2",
+ "PID_TYPE_AUTO": "3"
+ },
+ "pinLabel_e": {
+ "_source": "../../../src/main/drivers/pwm_mapping.h",
+ "PIN_LABEL_NONE": "0",
+ "PIN_LABEL_LED": "1"
+ },
+ "pitotSensor_e": {
+ "_source": "../../../src/main/sensors/pitotmeter.h",
+ "PITOT_NONE": "0",
+ "PITOT_AUTODETECT": "1",
+ "PITOT_MS4525": "2",
+ "PITOT_ADC": "3",
+ "PITOT_VIRTUAL": "4",
+ "PITOT_FAKE": "5",
+ "PITOT_MSP": "6",
+ "PITOT_DLVR": "7"
+ },
+ "pollType_e": {
+ "_source": "../../../src/main/io/smartport_master.c",
+ "PT_ACTIVE_ID": "0",
+ "PT_INACTIVE_ID": "1"
+ },
+ "portSharing_e": {
+ "_source": "../../../src/main/io/serial.h",
+ "PORTSHARING_UNUSED": "0",
+ "PORTSHARING_NOT_SHARED": "1",
+ "PORTSHARING_SHARED": "2"
+ },
+ "pwmInitError_e": {
+ "_source": "../../../src/main/drivers/pwm_mapping.h",
+ "PWM_INIT_ERROR_NONE": "0",
+ "PWM_INIT_ERROR_TOO_MANY_MOTORS": "1",
+ "PWM_INIT_ERROR_TOO_MANY_SERVOS": "2",
+ "PWM_INIT_ERROR_NOT_ENOUGH_MOTOR_OUTPUTS": "3",
+ "PWM_INIT_ERROR_NOT_ENOUGH_SERVO_OUTPUTS": "4",
+ "PWM_INIT_ERROR_TIMER_INIT_FAILED": "5"
+ },
+ "quadrant_e": {
+ "_source": "../../../src/main/io/ledstrip.c",
+ "QUADRANT_NORTH": "1 << 0",
+ "QUADRANT_SOUTH": "1 << 1",
+ "QUADRANT_EAST": "1 << 2",
+ "QUADRANT_WEST": "1 << 3",
+ "QUADRANT_NORTH_EAST": "1 << 4",
+ "QUADRANT_SOUTH_EAST": "1 << 5",
+ "QUADRANT_NORTH_WEST": "1 << 6",
+ "QUADRANT_SOUTH_WEST": "1 << 7",
+ "QUADRANT_NONE": "1 << 8",
+ "QUADRANT_NOTDIAG": "1 << 9",
+ "QUADRANT_ANY": "QUADRANT_NORTH | QUADRANT_SOUTH | QUADRANT_EAST | QUADRANT_WEST | QUADRANT_NONE"
+ },
+ "QUADSPIClockDivider_e": {
+ "_source": "../../../src/main/drivers/bus_quadspi.h",
+ "QUADSPI_CLOCK_INITIALISATION": "255",
+ "QUADSPI_CLOCK_SLOW": "19",
+ "QUADSPI_CLOCK_STANDARD": "9",
+ "QUADSPI_CLOCK_FAST": "3",
+ "QUADSPI_CLOCK_ULTRAFAST": "1"
+ },
+ "quadSpiMode_e": {
+ "_source": "../../../src/main/drivers/bus_quadspi.h",
+ "QUADSPI_MODE_BK1_ONLY": "0",
+ "QUADSPI_MODE_BK2_ONLY": "1",
+ "QUADSPI_MODE_DUAL_FLASH": "2"
+ },
+ "rangefinderType_e": {
+ "_source": "../../../src/main/sensors/rangefinder.h",
+ "RANGEFINDER_NONE": "0",
+ "RANGEFINDER_SRF10": "1",
+ "RANGEFINDER_VL53L0X": "2",
+ "RANGEFINDER_MSP": "3",
+ "RANGEFINDER_BENEWAKE": "4",
+ "RANGEFINDER_VL53L1X": "5",
+ "RANGEFINDER_US42": "6",
+ "RANGEFINDER_TOF10102I2C": "7",
+ "RANGEFINDER_FAKE": "8",
+ "RANGEFINDER_TERARANGER_EVO": "9",
+ "RANGEFINDER_USD1_V0": "10",
+ "RANGEFINDER_NANORADAR": "11"
+ },
+ "RCDEVICE_5key_connection_event_e": {
+ "_source": "../../../src/main/io/rcdevice.h",
+ "RCDEVICE_PROTOCOL_5KEY_CONNECTION_OPEN": "1",
+ "RCDEVICE_PROTOCOL_5KEY_CONNECTION_CLOSE": "2"
+ },
+ "rcdevice_5key_simulation_operation_e": {
+ "_source": "../../../src/main/io/rcdevice.h",
+ "RCDEVICE_PROTOCOL_5KEY_SIMULATION_NONE": "0",
+ "RCDEVICE_PROTOCOL_5KEY_SIMULATION_SET": "1",
+ "RCDEVICE_PROTOCOL_5KEY_SIMULATION_LEFT": "2",
+ "RCDEVICE_PROTOCOL_5KEY_SIMULATION_RIGHT": "3",
+ "RCDEVICE_PROTOCOL_5KEY_SIMULATION_UP": "4",
+ "RCDEVICE_PROTOCOL_5KEY_SIMULATION_DOWN": "5"
+ },
+ "rcdevice_camera_control_opeation_e": {
+ "_source": "../../../src/main/io/rcdevice.h",
+ "RCDEVICE_PROTOCOL_CAM_CTRL_SIMULATE_WIFI_BTN": "0",
+ "RCDEVICE_PROTOCOL_CAM_CTRL_SIMULATE_POWER_BTN": "1",
+ "RCDEVICE_PROTOCOL_CAM_CTRL_CHANGE_MODE": "2",
+ "RCDEVICE_PROTOCOL_CAM_CTRL_START_RECORDING": "3",
+ "RCDEVICE_PROTOCOL_CAM_CTRL_STOP_RECORDING": "4",
+ "RCDEVICE_PROTOCOL_CAM_CTRL_UNKNOWN_CAMERA_OPERATION": "255"
+ },
+ "rcdevice_features_e": {
+ "_source": "../../../src/main/io/rcdevice.h",
+ "RCDEVICE_PROTOCOL_FEATURE_SIMULATE_POWER_BUTTON": "(1 << 0)",
+ "RCDEVICE_PROTOCOL_FEATURE_SIMULATE_WIFI_BUTTON": "(1 << 1)",
+ "RCDEVICE_PROTOCOL_FEATURE_CHANGE_MODE": "(1 << 2)",
+ "RCDEVICE_PROTOCOL_FEATURE_SIMULATE_5_KEY_OSD_CABLE": "(1 << 3)",
+ "RCDEVICE_PROTOCOL_FEATURE_START_RECORDING": "(1 << 6)",
+ "RCDEVICE_PROTOCOL_FEATURE_STOP_RECORDING": "(1 << 7)",
+ "RCDEVICE_PROTOCOL_FEATURE_CMS_MENU": "(1 << 8)"
+ },
+ "rcdevice_protocol_version_e": {
+ "_source": "../../../src/main/io/rcdevice.h",
+ "RCDEVICE_PROTOCOL_RCSPLIT_VERSION": "0",
+ "RCDEVICE_PROTOCOL_VERSION_1_0": "1",
+ "RCDEVICE_PROTOCOL_UNKNOWN": "2"
+ },
+ "rcdeviceCamSimulationKeyEvent_e": {
+ "_source": "../../../src/main/io/rcdevice.h",
+ "RCDEVICE_CAM_KEY_NONE": "0",
+ "RCDEVICE_CAM_KEY_ENTER": "1",
+ "RCDEVICE_CAM_KEY_LEFT": "2",
+ "RCDEVICE_CAM_KEY_UP": "3",
+ "RCDEVICE_CAM_KEY_RIGHT": "4",
+ "RCDEVICE_CAM_KEY_DOWN": "5",
+ "RCDEVICE_CAM_KEY_CONNECTION_CLOSE": "6",
+ "RCDEVICE_CAM_KEY_CONNECTION_OPEN": "7",
+ "RCDEVICE_CAM_KEY_RELEASE": "8"
+ },
+ "rcdeviceResponseStatus_e": {
+ "_source": "../../../src/main/io/rcdevice.h",
+ "RCDEVICE_RESP_SUCCESS": "0",
+ "RCDEVICE_RESP_INCORRECT_CRC": "1",
+ "RCDEVICE_RESP_TIMEOUT": "2"
+ },
+ "resolutionType_e": {
+ "_source": "../../../src/main/io/displayport_msp_osd.c",
+ "SD_3016": "0",
+ "HD_5018": "1",
+ "HD_3016": "2",
+ "HD_6022": "3",
+ "HD_5320": "4"
+ },
+ "resourceOwner_e": {
+ "_source": "../../../src/main/drivers/resource.h",
+ "OWNER_FREE": "0",
+ "OWNER_PWMIO": "1",
+ "OWNER_MOTOR": "2",
+ "OWNER_SERVO": "3",
+ "OWNER_SOFTSERIAL": "4",
+ "OWNER_ADC": "5",
+ "OWNER_SERIAL": "6",
+ "OWNER_TIMER": "7",
+ "OWNER_RANGEFINDER": "8",
+ "OWNER_SYSTEM": "9",
+ "OWNER_SPI": "10",
+ "OWNER_QUADSPI": "11",
+ "OWNER_I2C": "12",
+ "OWNER_SDCARD": "13",
+ "OWNER_FLASH": "14",
+ "OWNER_USB": "15",
+ "OWNER_BEEPER": "16",
+ "OWNER_OSD": "17",
+ "OWNER_BARO": "18",
+ "OWNER_MPU": "19",
+ "OWNER_INVERTER": "20",
+ "OWNER_LED_STRIP": "21",
+ "OWNER_LED": "22",
+ "OWNER_RX": "23",
+ "OWNER_TX": "24",
+ "OWNER_VTX": "25",
+ "OWNER_SPI_PREINIT": "26",
+ "OWNER_COMPASS": "27",
+ "OWNER_TEMPERATURE": "28",
+ "OWNER_1WIRE": "29",
+ "OWNER_AIRSPEED": "30",
+ "OWNER_OLED_DISPLAY": "31",
+ "OWNER_PINIO": "32",
+ "OWNER_IRLOCK": "33",
+ "OWNER_TOTAL_COUNT": "34"
+ },
+ "resourceType_e": {
+ "_source": "../../../src/main/drivers/resource.h",
+ "RESOURCE_NONE": "0",
+ "RESOURCE_INPUT": "1",
+ "RESOURCE_TIMER": "2",
+ "RESOURCE_UART_TX": "3",
+ "RESOURCE_EXTI": "4",
+ "RESOURCE_I2C_SCL": "5",
+ "RESOURCE_SPI_SCK": "6",
+ "RESOURCE_QUADSPI_CLK": "7",
+ "RESOURCE_QUADSPI_BK1IO2": "8",
+ "RESOURCE_QUADSPI_BK2IO0": "9",
+ "RESOURCE_QUADSPI_BK2IO3": "10",
+ "RESOURCE_ADC_CH1": "11",
+ "RESOURCE_RX_CE": "12",
+ "RESOURCE_TOTAL_COUNT": "13"
+ },
+ "reversibleMotorsThrottleState_e": {
+ "_source": "../../../src/main/flight/mixer.h",
+ "MOTOR_DIRECTION_FORWARD": "0",
+ "MOTOR_DIRECTION_BACKWARD": "1",
+ "MOTOR_DIRECTION_DEADBAND": "2"
+ },
+ "rollPitchStatus_e": {
+ "_source": "../../../src/main/fc/rc_controls.h",
+ "NOT_CENTERED": "0",
+ "CENTERED": "1"
+ },
+ "rssiSource_e": {
+ "_source": "../../../src/main/rx/rx.h",
+ "RSSI_SOURCE_NONE": "0",
+ "RSSI_SOURCE_AUTO": "1",
+ "RSSI_SOURCE_ADC": "2",
+ "RSSI_SOURCE_RX_CHANNEL": "3",
+ "RSSI_SOURCE_RX_PROTOCOL": "4",
+ "RSSI_SOURCE_MSP": "5"
+ },
+ "rthState_e": {
+ "_source": "../../../src/main/flight/failsafe.h",
+ "RTH_IDLE": "0",
+ "RTH_IN_PROGRESS": "1",
+ "RTH_HAS_LANDED": "2"
+ },
+ "rthTargetMode_e": {
+ "_source": "../../../src/main/navigation/navigation_private.h",
+ "RTH_HOME_ENROUTE_INITIAL": "0",
+ "RTH_HOME_ENROUTE_PROPORTIONAL": "1",
+ "RTH_HOME_ENROUTE_FINAL": "2",
+ "RTH_HOME_FINAL_LOITER": "3",
+ "RTH_HOME_FINAL_LAND": "4"
+ },
+ "rthTrackbackMode_e": {
+ "_source": "../../../src/main/navigation/navigation.h",
+ "RTH_TRACKBACK_OFF": "0",
+ "RTH_TRACKBACK_ON": "1",
+ "RTH_TRACKBACK_FS": "2"
+ },
+ "rxFrameState_e": {
+ "_source": "../../../src/main/rx/rx.h",
+ "RX_FRAME_PENDING": "0",
+ "RX_FRAME_COMPLETE": "(1 << 0)",
+ "RX_FRAME_FAILSAFE": "(1 << 1)",
+ "RX_FRAME_PROCESSING_REQUIRED": "(1 << 2)",
+ "RX_FRAME_DROPPED": "(1 << 3)"
+ },
+ "rxReceiverType_e": {
+ "_source": "../../../src/main/rx/rx.h",
+ "RX_TYPE_NONE": "0",
+ "RX_TYPE_SERIAL": "1",
+ "RX_TYPE_MSP": "2",
+ "RX_TYPE_SIM": "3"
+ },
+ "rxSerialReceiverType_e": {
+ "_source": "../../../src/main/rx/rx.h",
+ "SERIALRX_SPEKTRUM1024": "0",
+ "SERIALRX_SPEKTRUM2048": "1",
+ "SERIALRX_SBUS": "2",
+ "SERIALRX_SUMD": "3",
+ "SERIALRX_IBUS": "4",
+ "SERIALRX_JETIEXBUS": "5",
+ "SERIALRX_CRSF": "6",
+ "SERIALRX_FPORT": "7",
+ "SERIALRX_SBUS_FAST": "8",
+ "SERIALRX_FPORT2": "9",
+ "SERIALRX_SRXL2": "10",
+ "SERIALRX_GHST": "11",
+ "SERIALRX_MAVLINK": "12",
+ "SERIALRX_FBUS": "13",
+ "SERIALRX_SBUS2": "14"
+ },
+ "safehomeUsageMode_e": {
+ "_source": "../../../src/main/navigation/navigation.h",
+ "SAFEHOME_USAGE_OFF": "0",
+ "SAFEHOME_USAGE_RTH": "1",
+ "SAFEHOME_USAGE_RTH_FS": "2"
+ },
+ "sbasMode_e": {
+ "_source": "../../../src/main/io/gps.h",
+ "SBAS_AUTO": "0",
+ "SBAS_EGNOS": "1",
+ "SBAS_WAAS": "2",
+ "SBAS_MSAS": "3",
+ "SBAS_GAGAN": "4",
+ "SBAS_SPAN": "5",
+ "SBAS_NONE": "6"
+ },
+ "sbusDecoderState_e": {
+ "_source": "../../../src/main/rx/sbus.c",
+ "STATE_SBUS_SYNC": "0",
+ "STATE_SBUS_PAYLOAD": "1",
+ "STATE_SBUS26_PAYLOAD": "2",
+ "STATE_SBUS_WAIT_SYNC": "3"
+ },
+ "sdcardBlockOperation_e": {
+ "_source": "../../../src/main/drivers/sdcard/sdcard.h",
+ "SDCARD_BLOCK_OPERATION_READ": "0",
+ "SDCARD_BLOCK_OPERATION_WRITE": "1",
+ "SDCARD_BLOCK_OPERATION_ERASE": "2"
+ },
+ "sdcardOperationStatus_e": {
+ "_source": "../../../src/main/drivers/sdcard/sdcard.h",
+ "SDCARD_OPERATION_IN_PROGRESS": "0",
+ "SDCARD_OPERATION_BUSY": "1",
+ "SDCARD_OPERATION_SUCCESS": "2",
+ "SDCARD_OPERATION_FAILURE": "3"
+ },
+ "sdcardReceiveBlockStatus_e": {
+ "_source": "../../../src/main/drivers/sdcard/sdcard_spi.c",
+ "SDCARD_RECEIVE_SUCCESS": "0",
+ "SDCARD_RECEIVE_BLOCK_IN_PROGRESS": "1",
+ "SDCARD_RECEIVE_ERROR": "2"
+ },
+ "sdcardState_e": {
+ "_source": "../../../src/main/drivers/sdcard/sdcard_impl.h",
+ "SDCARD_STATE_NOT_PRESENT": "0",
+ "SDCARD_STATE_RESET": "1",
+ "SDCARD_STATE_CARD_INIT_IN_PROGRESS": "2",
+ "SDCARD_STATE_INITIALIZATION_RECEIVE_CID": "3",
+ "SDCARD_STATE_READY": "4",
+ "SDCARD_STATE_READING": "5",
+ "SDCARD_STATE_SENDING_WRITE": "6",
+ "SDCARD_STATE_WAITING_FOR_WRITE": "7",
+ "SDCARD_STATE_WRITING_MULTIPLE_BLOCKS": "8",
+ "SDCARD_STATE_STOPPING_MULTIPLE_BLOCK_WRITE": "9"
+ },
+ "SDIODevice": {
+ "_source": "../../../src/main/drivers/sdio.h",
+ "SDIOINVALID": "-1",
+ "SDIODEV_1": "0",
+ "SDIODEV_2": "1"
+ },
+ "sensor_align_e": {
+ "_source": "../../../src/main/drivers/sensor.h",
+ "ALIGN_DEFAULT": "0",
+ "CW0_DEG": "1",
+ "CW90_DEG": "2",
+ "CW180_DEG": "3",
+ "CW270_DEG": "4",
+ "CW0_DEG_FLIP": "5",
+ "CW90_DEG_FLIP": "6",
+ "CW180_DEG_FLIP": "7",
+ "CW270_DEG_FLIP": "8"
+ },
+ "sensorIndex_e": {
+ "_source": "../../../src/main/sensors/sensors.h",
+ "SENSOR_INDEX_GYRO": "0",
+ "SENSOR_INDEX_ACC": "1",
+ "SENSOR_INDEX_BARO": "2",
+ "SENSOR_INDEX_MAG": "3",
+ "SENSOR_INDEX_RANGEFINDER": "4",
+ "SENSOR_INDEX_PITOT": "5",
+ "SENSOR_INDEX_OPFLOW": "6",
+ "SENSOR_INDEX_COUNT": "7"
+ },
+ "sensors_e": {
+ "_source": "../../../src/main/sensors/sensors.h",
+ "SENSOR_GYRO": "1 << 0",
+ "SENSOR_ACC": "1 << 1",
+ "SENSOR_BARO": "1 << 2",
+ "SENSOR_MAG": "1 << 3",
+ "SENSOR_RANGEFINDER": "1 << 4",
+ "SENSOR_PITOT": "1 << 5",
+ "SENSOR_OPFLOW": "1 << 6",
+ "SENSOR_GPS": "1 << 7",
+ "SENSOR_GPSMAG": "1 << 8",
+ "SENSOR_TEMP": "1 << 9"
+ },
+ "sensorTempCalState_e": {
+ "_source": "../../../src/main/sensors/sensors.h",
+ "SENSOR_TEMP_CAL_INITIALISE": "0",
+ "SENSOR_TEMP_CAL_IN_PROGRESS": "1",
+ "SENSOR_TEMP_CAL_COMPLETE": "2"
+ },
+ "serialPortFunction_e": {
+ "_source": "../../../src/main/io/serial.h",
+ "FUNCTION_NONE": "0",
+ "FUNCTION_MSP": "(1 << 0)",
+ "FUNCTION_GPS": "(1 << 1)",
+ "FUNCTION_UNUSED_3": "(1 << 2)",
+ "FUNCTION_TELEMETRY_HOTT": "(1 << 3)",
+ "FUNCTION_TELEMETRY_LTM": "(1 << 4)",
+ "FUNCTION_TELEMETRY_SMARTPORT": "(1 << 5)",
+ "FUNCTION_RX_SERIAL": "(1 << 6)",
+ "FUNCTION_BLACKBOX": "(1 << 7)",
+ "FUNCTION_TELEMETRY_MAVLINK": "(1 << 8)",
+ "FUNCTION_TELEMETRY_IBUS": "(1 << 9)",
+ "FUNCTION_RCDEVICE": "(1 << 10)",
+ "FUNCTION_VTX_SMARTAUDIO": "(1 << 11)",
+ "FUNCTION_VTX_TRAMP": "(1 << 12)",
+ "FUNCTION_UNUSED_1": "(1 << 13)",
+ "FUNCTION_OPTICAL_FLOW": "(1 << 14)",
+ "FUNCTION_LOG": "(1 << 15)",
+ "FUNCTION_RANGEFINDER": "(1 << 16)",
+ "FUNCTION_VTX_FFPV": "(1 << 17)",
+ "FUNCTION_ESCSERIAL": "(1 << 18)",
+ "FUNCTION_TELEMETRY_SIM": "(1 << 19)",
+ "FUNCTION_FRSKY_OSD": "(1 << 20)",
+ "FUNCTION_DJI_HD_OSD": "(1 << 21)",
+ "FUNCTION_SERVO_SERIAL": "(1 << 22)",
+ "FUNCTION_TELEMETRY_SMARTPORT_MASTER": "(1 << 23)",
+ "FUNCTION_UNUSED_2": "(1 << 24)",
+ "FUNCTION_MSP_OSD": "(1 << 25)",
+ "FUNCTION_GIMBAL": "(1 << 26)",
+ "FUNCTION_GIMBAL_HEADTRACKER": "(1 << 27)"
+ },
+ "serialPortIdentifier_e": {
+ "_source": "../../../src/main/io/serial.h",
+ "SERIAL_PORT_NONE": "-1",
+ "SERIAL_PORT_USART1": "0",
+ "SERIAL_PORT_USART2": "1",
+ "SERIAL_PORT_USART3": "2",
+ "SERIAL_PORT_USART4": "3",
+ "SERIAL_PORT_USART5": "4",
+ "SERIAL_PORT_USART6": "5",
+ "SERIAL_PORT_USART7": "6",
+ "SERIAL_PORT_USART8": "7",
+ "SERIAL_PORT_USB_VCP": "20",
+ "SERIAL_PORT_SOFTSERIAL1": "30",
+ "SERIAL_PORT_SOFTSERIAL2": "31",
+ "SERIAL_PORT_IDENTIFIER_MAX": "SERIAL_PORT_SOFTSERIAL2"
+ },
+ "servoAutotrimState_e": {
+ "_source": "../../../src/main/flight/servos.c",
+ "AUTOTRIM_IDLE": "0",
+ "AUTOTRIM_COLLECTING": "1",
+ "AUTOTRIM_SAVE_PENDING": "2",
+ "AUTOTRIM_DONE": "3"
+ },
+ "servoIndex_e": {
+ "_source": "../../../src/main/flight/servos.h",
+ "SERVO_GIMBAL_PITCH": "0",
+ "SERVO_GIMBAL_ROLL": "1",
+ "SERVO_ELEVATOR": "2",
+ "SERVO_FLAPPERON_1": "3",
+ "SERVO_FLAPPERON_2": "4",
+ "SERVO_RUDDER": "5",
+ "SERVO_BICOPTER_LEFT": "4",
+ "SERVO_BICOPTER_RIGHT": "5",
+ "SERVO_DUALCOPTER_LEFT": "4",
+ "SERVO_DUALCOPTER_RIGHT": "5",
+ "SERVO_SINGLECOPTER_1": "3",
+ "SERVO_SINGLECOPTER_2": "4",
+ "SERVO_SINGLECOPTER_3": "5",
+ "SERVO_SINGLECOPTER_4": "6"
+ },
+ "servoProtocolType_e": {
+ "_source": "../../../src/main/drivers/pwm_mapping.h",
+ "SERVO_TYPE_PWM": "0",
+ "SERVO_TYPE_SBUS": "1",
+ "SERVO_TYPE_SBUS_PWM": "2"
+ },
+ "setting_mode_e": {
+ "_source": "../../../src/main/fc/settings.h",
+ "MODE_DIRECT": "(0 << SETTING_MODE_OFFSET)",
+ "MODE_LOOKUP": "(1 << SETTING_MODE_OFFSET)"
+ },
+ "setting_section_e": {
+ "_source": "../../../src/main/fc/settings.h",
+ "MASTER_VALUE": "(0 << SETTING_SECTION_OFFSET)",
+ "PROFILE_VALUE": "(1 << SETTING_SECTION_OFFSET)",
+ "CONTROL_VALUE": "(2 << SETTING_SECTION_OFFSET)",
+ "BATTERY_CONFIG_VALUE": "(3 << SETTING_SECTION_OFFSET)",
+ "MIXER_CONFIG_VALUE": "(4 << SETTING_SECTION_OFFSET)",
+ "EZ_TUNE_VALUE": "(5 << SETTING_SECTION_OFFSET)"
+ },
+ "setting_type_e": {
+ "_source": "../../../src/main/fc/settings.h",
+ "VAR_UINT8": "(0 << SETTING_TYPE_OFFSET)",
+ "VAR_INT8": "(1 << SETTING_TYPE_OFFSET)",
+ "VAR_UINT16": "(2 << SETTING_TYPE_OFFSET)",
+ "VAR_INT16": "(3 << SETTING_TYPE_OFFSET)",
+ "VAR_UINT32": "(4 << SETTING_TYPE_OFFSET)",
+ "VAR_FLOAT": "(5 << SETTING_TYPE_OFFSET)",
+ "VAR_STRING": "(6 << SETTING_TYPE_OFFSET)"
+ },
+ "simATCommandState_e": {
+ "_source": "../../../src/main/telemetry/sim.c",
+ "SIM_AT_OK": "0",
+ "SIM_AT_ERROR": "1",
+ "SIM_AT_WAITING_FOR_RESPONSE": "2"
+ },
+ "simModuleState_e": {
+ "_source": "../../../src/main/telemetry/sim.c",
+ "SIM_MODULE_NOT_DETECTED": "0",
+ "SIM_MODULE_NOT_REGISTERED": "1",
+ "SIM_MODULE_REGISTERED": "2"
+ },
+ "simReadState_e": {
+ "_source": "../../../src/main/telemetry/sim.c",
+ "SIM_READSTATE_RESPONSE": "0",
+ "SIM_READSTATE_SMS": "1",
+ "SIM_READSTATE_SKIP": "2"
+ },
+ "simTelemetryState_e": {
+ "_source": "../../../src/main/telemetry/sim.c",
+ "SIM_STATE_INIT": "0",
+ "SIM_STATE_INIT2": "1",
+ "SIM_STATE_INIT_ENTER_PIN": "2",
+ "SIM_STATE_SET_MODES": "3",
+ "SIM_STATE_SEND_SMS": "4",
+ "SIM_STATE_SEND_SMS_ENTER_MESSAGE": "5"
+ },
+ "simTransmissionState_e": {
+ "_source": "../../../src/main/telemetry/sim.c",
+ "SIM_TX_NO": "0",
+ "SIM_TX_FS": "1",
+ "SIM_TX": "2"
+ },
+ "simTxFlags_e": {
+ "_source": "../../../src/main/telemetry/sim.h",
+ "SIM_TX_FLAG": "(1 << 0)",
+ "SIM_TX_FLAG_FAILSAFE": "(1 << 1)",
+ "SIM_TX_FLAG_GPS": "(1 << 2)",
+ "SIM_TX_FLAG_ACC": "(1 << 3)",
+ "SIM_TX_FLAG_LOW_ALT": "(1 << 4)",
+ "SIM_TX_FLAG_RESPONSE": "(1 << 5)"
+ },
+ "simulatorFlags_t": {
+ "_source": "../../../src/main/fc/runtime_config.h",
+ "HITL_RESET_FLAGS": "(0 << 0)",
+ "HITL_ENABLE": "(1 << 0)",
+ "HITL_SIMULATE_BATTERY": "(1 << 1)",
+ "HITL_MUTE_BEEPER": "(1 << 2)",
+ "HITL_USE_IMU": "(1 << 3)",
+ "HITL_HAS_NEW_GPS_DATA": "(1 << 4)",
+ "HITL_EXT_BATTERY_VOLTAGE": "(1 << 5)",
+ "HITL_AIRSPEED": "(1 << 6)",
+ "HITL_EXTENDED_FLAGS": "(1 << 7)",
+ "HITL_GPS_TIMEOUT": "(1 << 8)",
+ "HITL_PITOT_FAILURE": "(1 << 9)"
+ },
+ "smartAudioVersion_e": {
+ "_source": "../../../src/main/io/vtx_smartaudio.h",
+ "SA_UNKNOWN": "0",
+ "SA_1_0": "1",
+ "SA_2_0": "2",
+ "SA_2_1": "3"
+ },
+ "smartportFuelUnit_e": {
+ "_source": "../../../src/main/telemetry/telemetry.h",
+ "SMARTPORT_FUEL_UNIT_PERCENT": "0",
+ "SMARTPORT_FUEL_UNIT_MAH": "1",
+ "SMARTPORT_FUEL_UNIT_MWH": "2"
+ },
+ "softSerialPortIndex_e": {
+ "_source": "../../../src/main/drivers/serial_softserial.h",
+ "SOFTSERIAL1": "0",
+ "SOFTSERIAL2": "1"
+ },
+ "SPIClockSpeed_e": {
+ "_source": "../../../src/main/drivers/bus_spi.h",
+ "SPI_CLOCK_INITIALIZATON": "0",
+ "SPI_CLOCK_SLOW": "1",
+ "SPI_CLOCK_STANDARD": "2",
+ "SPI_CLOCK_FAST": "3",
+ "SPI_CLOCK_ULTRAFAST": "4"
+ },
+ "Srxl2BindRequest": {
+ "_source": "../../../src/main/rx/srxl2_types.h",
+ "EnterBindMode": "235",
+ "RequestBindStatus": "181",
+ "BoundDataReport": "219",
+ "SetBindInfo": "91"
+ },
+ "Srxl2BindType": {
+ "_source": "../../../src/main/rx/srxl2_types.h",
+ "NotBound": "0",
+ "DSM2_1024_22ms": "1",
+ "DSM2_1024_MC24": "2",
+ "DMS2_2048_11ms": "18",
+ "DMSX_22ms": "162",
+ "DMSX_11ms": "178",
+ "Surface_DSM2_16_5ms": "99",
+ "DSMR_11ms_22ms": "226",
+ "DSMR_5_5ms": "228"
+ },
+ "Srxl2ControlDataCommand": {
+ "_source": "../../../src/main/rx/srxl2_types.h",
+ "ChannelData": "0",
+ "FailsafeChannelData": "1",
+ "VTXData": "2"
+ },
+ "Srxl2DeviceId": {
+ "_source": "../../../src/main/rx/srxl2_types.h",
+ "FlightControllerDefault": "48",
+ "FlightControllerMax": "63",
+ "Broadcast": "255"
+ },
+ "Srxl2DeviceType": {
+ "_source": "../../../src/main/rx/srxl2_types.h",
+ "NoDevice": "0",
+ "RemoteReceiver": "1",
+ "Receiver": "2",
+ "FlightController": "3",
+ "ESC": "4",
+ "Reserved": "5",
+ "SRXLServo": "6",
+ "SRXLServo_2": "7",
+ "VTX": "8"
+ },
+ "Srxl2PacketType": {
+ "_source": "../../../src/main/rx/srxl2_types.h",
+ "Handshake": "33",
+ "BindInfo": "65",
+ "ParameterConfiguration": "80",
+ "SignalQuality": "85",
+ "TelemetrySensorData": "128",
+ "ControlData": "205"
+ },
+ "Srxl2State": {
+ "_source": "../../../src/main/rx/srxl2_types.h",
+ "Disabled": "0",
+ "ListenForActivity": "1",
+ "SendHandshake": "2",
+ "ListenForHandshake": "3",
+ "Running": "4"
+ },
+ "stateFlags_t": {
+ "_source": "../../../src/main/fc/runtime_config.h",
+ "GPS_FIX_HOME": "(1 << 0)",
+ "GPS_FIX": "(1 << 1)",
+ "CALIBRATE_MAG": "(1 << 2)",
+ "SMALL_ANGLE": "(1 << 3)",
+ "FIXED_WING_LEGACY": "(1 << 4)",
+ "ANTI_WINDUP": "(1 << 5)",
+ "FLAPERON_AVAILABLE": "(1 << 6)",
+ "NAV_MOTOR_STOP_OR_IDLE": "(1 << 7)",
+ "COMPASS_CALIBRATED": "(1 << 8)",
+ "ACCELEROMETER_CALIBRATED": "(1 << 9)",
+ "GPS_ESTIMATED_FIX": [
+ "(1 << 10)",
+ "USE_GPS_FIX_ESTIMATION"
+ ],
+ "NAV_CRUISE_BRAKING": "(1 << 11)",
+ "NAV_CRUISE_BRAKING_BOOST": "(1 << 12)",
+ "NAV_CRUISE_BRAKING_LOCKED": "(1 << 13)",
+ "NAV_EXTRA_ARMING_SAFETY_BYPASSED": "(1 << 14)",
+ "AIRMODE_ACTIVE": "(1 << 15)",
+ "ESC_SENSOR_ENABLED": "(1 << 16)",
+ "AIRPLANE": "(1 << 17)",
+ "MULTIROTOR": "(1 << 18)",
+ "ROVER": "(1 << 19)",
+ "BOAT": "(1 << 20)",
+ "ALTITUDE_CONTROL": "(1 << 21)",
+ "MOVE_FORWARD_ONLY": "(1 << 22)",
+ "SET_REVERSIBLE_MOTORS_FORWARD": "(1 << 23)",
+ "FW_HEADING_USE_YAW": "(1 << 24)",
+ "ANTI_WINDUP_DEACTIVATED": "(1 << 25)",
+ "LANDING_DETECTED": "(1 << 26)",
+ "IN_FLIGHT_EMERG_REARM": "(1 << 27)",
+ "TAILSITTER": "(1 << 28)"
+ },
+ "stickPositions_e": {
+ "_source": "../../../src/main/fc/rc_controls.h",
+ "ROL_LO": "(1 << (2 * ROLL))",
+ "ROL_CE": "(3 << (2 * ROLL))",
+ "ROL_HI": "(2 << (2 * ROLL))",
+ "PIT_LO": "(1 << (2 * PITCH))",
+ "PIT_CE": "(3 << (2 * PITCH))",
+ "PIT_HI": "(2 << (2 * PITCH))",
+ "YAW_LO": "(1 << (2 * YAW))",
+ "YAW_CE": "(3 << (2 * YAW))",
+ "YAW_HI": "(2 << (2 * YAW))",
+ "THR_LO": "(1 << (2 * THROTTLE))",
+ "THR_CE": "(3 << (2 * THROTTLE))",
+ "THR_HI": "(2 << (2 * THROTTLE))"
+ },
+ "systemState_e": {
+ "_source": "../../../src/main/fc/fc_init.h",
+ "SYSTEM_STATE_INITIALISING": "0",
+ "SYSTEM_STATE_CONFIG_LOADED": "(1 << 0)",
+ "SYSTEM_STATE_SENSORS_READY": "(1 << 1)",
+ "SYSTEM_STATE_MOTORS_READY": "(1 << 2)",
+ "SYSTEM_STATE_TRANSPONDER_ENABLED": "(1 << 3)",
+ "SYSTEM_STATE_READY": "(1 << 7)"
+ },
+ "tchDmaState_e": {
+ "_source": "../../../src/main/drivers/timer.h",
+ "TCH_DMA_IDLE": "0",
+ "TCH_DMA_READY": "1",
+ "TCH_DMA_ACTIVE": "2"
+ },
+ "tempSensorType_e": {
+ "_source": "../../../src/main/sensors/temperature.h",
+ "TEMP_SENSOR_NONE": "0",
+ "TEMP_SENSOR_LM75": "1",
+ "TEMP_SENSOR_DS18B20": "2"
+ },
+ "throttleStatus_e": {
+ "_source": "../../../src/main/fc/rc_controls.h",
+ "THROTTLE_LOW": "0",
+ "THROTTLE_HIGH": "1"
+ },
+ "throttleStatusType_e": {
+ "_source": "../../../src/main/fc/rc_controls.h",
+ "THROTTLE_STATUS_TYPE_RC": "0",
+ "THROTTLE_STATUS_TYPE_COMMAND": "1"
+ },
+ "timerMode_e": {
+ "_source": "../../../src/main/drivers/serial_softserial.c",
+ "TIMER_MODE_SINGLE": "0",
+ "TIMER_MODE_DUAL": "1"
+ },
+ "timerUsageFlag_e": {
+ "_source": "../../../src/main/drivers/timer.h",
+ "TIM_USE_ANY": "0",
+ "TIM_USE_PPM": "(1 << 0)",
+ "TIM_USE_PWM": "(1 << 1)",
+ "TIM_USE_MOTOR": "(1 << 2)",
+ "TIM_USE_SERVO": "(1 << 3)",
+ "TIM_USE_MC_CHNFW": "(1 << 4)",
+ "TIM_USE_LED": "(1 << 24)",
+ "TIM_USE_BEEPER": "(1 << 25)"
+ },
+ "timId_e": {
+ "_source": "../../../src/main/io/ledstrip.c",
+ "timBlink": "0",
+ "timLarson": "1",
+ "timBattery": "2",
+ "timRssi": "3",
+ "timGps": [
+ "(4)",
+ "USE_GPS"
+ ],
+ "timWarning": "5",
+ "timIndicator": "6",
+ "timAnimation": [
+ "(7)",
+ "USE_LED_ANIMATION"
+ ],
+ "timRing": "8",
+ "timTimerCount": "9"
+ },
+ "tristate_e": {
+ "_source": "../../../src/main/common/tristate.h",
+ "TRISTATE_AUTO": "0",
+ "TRISTATE_ON": "1",
+ "TRISTATE_OFF": "2"
+ },
+ "tz_automatic_dst_e": {
+ "_source": "../../../src/main/common/time.h",
+ "TZ_AUTO_DST_OFF": "0",
+ "TZ_AUTO_DST_EU": "1",
+ "TZ_AUTO_DST_USA": "2"
+ },
+ "UARTDevice_e": {
+ "_source": "../../../src/main/drivers/serial_uart.h",
+ "UARTDEV_1": "0",
+ "UARTDEV_2": "1",
+ "UARTDEV_3": "2",
+ "UARTDEV_4": "3",
+ "UARTDEV_5": "4",
+ "UARTDEV_6": "5",
+ "UARTDEV_7": "6",
+ "UARTDEV_8": "7",
+ "UARTDEV_MAX": "8"
+ },
+ "uartInverterLine_e": {
+ "_source": "../../../src/main/drivers/uart_inverter.h",
+ "UART_INVERTER_LINE_NONE": "0",
+ "UART_INVERTER_LINE_RX": "1 << 0",
+ "UART_INVERTER_LINE_TX": "1 << 1"
+ },
+ "ublox_nav_sig_health_e": {
+ "_source": "../../../src/main/io/gps_ublox.h",
+ "UBLOX_SIG_HEALTH_UNKNOWN": "0",
+ "UBLOX_SIG_HEALTH_HEALTHY": "1",
+ "UBLOX_SIG_HEALTH_UNHEALTHY": "2"
+ },
+ "ublox_nav_sig_quality": {
+ "_source": "../../../src/main/io/gps_ublox.h",
+ "UBLOX_SIG_QUALITY_NOSIGNAL": "0",
+ "UBLOX_SIG_QUALITY_SEARCHING": "1",
+ "UBLOX_SIG_QUALITY_ACQUIRED": "2",
+ "UBLOX_SIG_QUALITY_UNUSABLE": "3",
+ "UBLOX_SIG_QUALITY_CODE_LOCK_TIME_SYNC": "4",
+ "UBLOX_SIG_QUALITY_CODE_CARRIER_LOCK_TIME_SYNC": "5",
+ "UBLOX_SIG_QUALITY_CODE_CARRIER_LOCK_TIME_SYNC2": "6",
+ "UBLOX_SIG_QUALITY_CODE_CARRIER_LOCK_TIME_SYNC3": "7"
+ },
+ "ubs_nav_fix_type_t": {
+ "_source": "../../../src/main/io/gps_ublox.h",
+ "FIX_NONE": "0",
+ "FIX_DEAD_RECKONING": "1",
+ "FIX_2D": "2",
+ "FIX_3D": "3",
+ "FIX_GPS_DEAD_RECKONING": "4",
+ "FIX_TIME": "5"
+ },
+ "ubx_ack_state_t": {
+ "_source": "../../../src/main/io/gps_ublox.h",
+ "UBX_ACK_WAITING": "0",
+ "UBX_ACK_GOT_ACK": "1",
+ "UBX_ACK_GOT_NAK": "2"
+ },
+ "ubx_nav_status_bits_t": {
+ "_source": "../../../src/main/io/gps_ublox.h",
+ "NAV_STATUS_FIX_VALID": "1"
+ },
+ "ubx_protocol_bytes_t": {
+ "_source": "../../../src/main/io/gps_ublox.h",
+ "PREAMBLE1": "181",
+ "PREAMBLE2": "98",
+ "CLASS_NAV": "1",
+ "CLASS_ACK": "5",
+ "CLASS_CFG": "6",
+ "CLASS_MON": "10",
+ "MSG_CLASS_UBX": "1",
+ "MSG_CLASS_NMEA": "240",
+ "MSG_VER": "4",
+ "MSG_ACK_NACK": "0",
+ "MSG_ACK_ACK": "1",
+ "MSG_NMEA_GGA": "0",
+ "MSG_NMEA_GLL": "1",
+ "MSG_NMEA_GSA": "2",
+ "MSG_NMEA_GSV": "3",
+ "MSG_NMEA_RMC": "4",
+ "MSG_NMEA_VGS": "5",
+ "MSG_POSLLH": "2",
+ "MSG_STATUS": "3",
+ "MSG_SOL": "6",
+ "MSG_PVT": "7",
+ "MSG_VELNED": "18",
+ "MSG_TIMEUTC": "33",
+ "MSG_SVINFO": "48",
+ "MSG_NAV_SAT": "53",
+ "MSG_CFG_PRT": "0",
+ "MSG_CFG_RATE": "8",
+ "MSG_CFG_SET_RATE": "1",
+ "MSG_CFG_NAV_SETTINGS": "36",
+ "MSG_CFG_SBAS": "22",
+ "MSG_CFG_GNSS": "62",
+ "MSG_MON_GNSS": "40",
+ "MSG_NAV_SIG": "67"
+ },
+ "vcselPeriodType_e": {
+ "_source": "../../../src/main/drivers/rangefinder/rangefinder_vl53l0x.c",
+ "VcselPeriodPreRange": "0",
+ "VcselPeriodFinalRange": "1"
+ },
+ "videoSystem_e": {
+ "_source": "../../../src/main/drivers/osd.h",
+ "VIDEO_SYSTEM_AUTO": "0",
+ "VIDEO_SYSTEM_PAL": "1",
+ "VIDEO_SYSTEM_NTSC": "2",
+ "VIDEO_SYSTEM_HDZERO": "3",
+ "VIDEO_SYSTEM_DJIWTF": "4",
+ "VIDEO_SYSTEM_AVATAR": "5",
+ "VIDEO_SYSTEM_DJICOMPAT": "6",
+ "VIDEO_SYSTEM_DJICOMPAT_HD": "7",
+ "VIDEO_SYSTEM_DJI_NATIVE": "8"
+ },
+ "voltageSensor_e": {
+ "_source": "../../../src/main/sensors/battery_config_structs.h",
+ "VOLTAGE_SENSOR_NONE": "0",
+ "VOLTAGE_SENSOR_ADC": "1",
+ "VOLTAGE_SENSOR_ESC": "2",
+ "VOLTAGE_SENSOR_FAKE": "3",
+ "VOLTAGE_SENSOR_SMARTPORT": "4",
+ "VOLTAGE_SENSOR_MAX": "VOLTAGE_SENSOR_SMARTPORT"
+ },
+ "vs600Band_e": {
+ "_source": "../../../src/main/io/smartport_master.h",
+ "VS600_BAND_A": "0",
+ "VS600_BAND_B": "1",
+ "VS600_BAND_C": "2",
+ "VS600_BAND_D": "3",
+ "VS600_BAND_E": "4",
+ "VS600_BAND_F": "5"
+ },
+ "vs600Power_e": {
+ "_source": "../../../src/main/io/smartport_master.h",
+ "VS600_POWER_PIT": "0",
+ "VS600_POWER_25MW": "1",
+ "VS600_POWER_200MW": "2",
+ "VS600_POWER_600MW": "3"
+ },
+ "vtxDevType_e": {
+ "_source": "../../../src/main/drivers/vtx_common.h",
+ "VTXDEV_UNSUPPORTED": "0",
+ "VTXDEV_RTC6705": "1",
+ "VTXDEV_SMARTAUDIO": "3",
+ "VTXDEV_TRAMP": "4",
+ "VTXDEV_FFPV": "5",
+ "VTXDEV_MSP": "6",
+ "VTXDEV_UNKNOWN": "255"
+ },
+ "vtxFrequencyGroups_e": {
+ "_source": "../../../src/main/drivers/vtx_common.h",
+ "FREQUENCYGROUP_5G8": "0",
+ "FREQUENCYGROUP_2G4": "1",
+ "FREQUENCYGROUP_1G3": "2"
+ },
+ "vtxLowerPowerDisarm_e": {
+ "_source": "../../../src/main/io/vtx.h",
+ "VTX_LOW_POWER_DISARM_OFF": "0",
+ "VTX_LOW_POWER_DISARM_ALWAYS": "1",
+ "VTX_LOW_POWER_DISARM_UNTIL_FIRST_ARM": "2"
+ },
+ "vtxProtoResponseType_e": {
+ "_source": "../../../src/main/io/vtx_tramp.c",
+ "VTX_RESPONSE_TYPE_NONE": "0",
+ "VTX_RESPONSE_TYPE_CAPABILITIES": "1",
+ "VTX_RESPONSE_TYPE_STATUS": "2"
+ },
+ "vtxProtoState_e": {
+ "_source": "../../../src/main/io/vtx_tramp.c",
+ "VTX_STATE_RESET": "0",
+ "VTX_STATE_OFFILE": "1",
+ "VTX_STATE_DETECTING": "2",
+ "VTX_STATE_IDLE": "3",
+ "VTX_STATE_QUERY_DELAY": "4",
+ "VTX_STATE_QUERY_STATUS": "5",
+ "VTX_STATE_WAIT_STATUS": "6"
+ },
+ "vtxScheduleParams_e": {
+ "_source": "../../../src/main/io/vtx.c",
+ "VTX_PARAM_POWER": "0",
+ "VTX_PARAM_BANDCHAN": "1",
+ "VTX_PARAM_PITMODE": "2",
+ "VTX_PARAM_COUNT": "3"
+ },
+ "warningFlags_e": {
+ "_source": "../../../src/main/io/ledstrip.c",
+ "WARNING_ARMING_DISABLED": "0",
+ "WARNING_LOW_BATTERY": "1",
+ "WARNING_FAILSAFE": "2",
+ "WARNING_HW_ERROR": "3"
+ },
+ "warningLedState_e": {
+ "_source": "../../../src/main/io/statusindicator.c",
+ "WARNING_LED_OFF": "0",
+ "WARNING_LED_ON": "1",
+ "WARNING_LED_FLASH": "2"
+ },
+ "widgetAHIOptions_t": {
+ "_source": "../../../src/main/drivers/display_widgets.h",
+ "DISPLAY_WIDGET_AHI_OPTION_SHOW_CORNERS": "1 << 0"
+ },
+ "widgetAHIStyle_e": {
+ "_source": "../../../src/main/drivers/display_widgets.h",
+ "DISPLAY_WIDGET_AHI_STYLE_STAIRCASE": "0",
+ "DISPLAY_WIDGET_AHI_STYLE_LINE": "1"
+ },
+ "wpFwTurnSmoothing_e": {
+ "_source": "../../../src/main/navigation/navigation.h",
+ "WP_TURN_SMOOTHING_OFF": "0",
+ "WP_TURN_SMOOTHING_ON": "1",
+ "WP_TURN_SMOOTHING_CUT": "2"
+ },
+ "wpMissionPlannerStatus_e": {
+ "_source": "../../../src/main/navigation/navigation.h",
+ "WP_PLAN_WAIT": "0",
+ "WP_PLAN_SAVE": "1",
+ "WP_PLAN_OK": "2",
+ "WP_PLAN_FULL": "3"
+ },
+ "zeroCalibrationState_e": {
+ "_source": "../../../src/main/common/calibration.h",
+ "ZERO_CALIBRATION_NONE": "0",
+ "ZERO_CALIBRATION_IN_PROGRESS": "1",
+ "ZERO_CALIBRATION_DONE": "2",
+ "ZERO_CALIBRATION_FAIL": "3"
+ }
+}
\ No newline at end of file
diff --git a/docs/development/msp/inav_enums_ref.md b/docs/development/msp/inav_enums_ref.md
index 2d60f270183..e4476e833e4 100644
--- a/docs/development/msp/inav_enums_ref.md
+++ b/docs/development/msp/inav_enums_ref.md
@@ -162,6 +162,7 @@
- [ltm_modes_e](#enum-ltm_modes_e)
- [ltmUpdateRate_e](#enum-ltmupdaterate_e)
- [magSensor_e](#enum-magsensor_e)
+- [mavFrameSupportMask_e](#enum-mavframesupportmask_e)
- [mavlinkAutopilotType_e](#enum-mavlinkautopilottype_e)
- [mavlinkRadio_e](#enum-mavlinkradio_e)
- [measurementSteps_e](#enum-measurementsteps_e)
@@ -3128,6 +3129,19 @@
| `MAG_FAKE` | 16 | |
| `MAG_MAX` | MAG_FAKE | |
+---
+## `mavFrameSupportMask_e`
+
+> Source: ../../../src/main/telemetry/mavlink.c
+
+| Enumerator | Value | Condition |
+|---|---:|---|
+| `MAV_FRAME_SUPPORTED_NONE` | 0 | |
+| `MAV_FRAME_SUPPORTED_GLOBAL` | (1 << 0) | |
+| `MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT` | (1 << 1) | |
+| `MAV_FRAME_SUPPORTED_GLOBAL_INT` | (1 << 2) | |
+| `MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT_INT` | (1 << 3) | |
+
---
## `mavlinkAutopilotType_e`
diff --git a/src/main/telemetry/mavlink.c b/src/main/telemetry/mavlink.c
index fe0aebe26b7..b9e654bdbd8 100644
--- a/src/main/telemetry/mavlink.c
+++ b/src/main/telemetry/mavlink.c
@@ -263,11 +263,10 @@ static APM_COPTER_MODE inavToArduCopterMap(flightModeForTelemetry_e flightMode)
} else if (failsafePhase() == FAILSAFE_LANDING) {
return COPTER_MODE_LAND;
} else {
- // There is no valid mapping to ArduCopter
- return COPTER_MODE_ENUM_END;
+ return COPTER_MODE_RTL;
}
}
- default: return COPTER_MODE_ENUM_END;
+ default: return COPTER_MODE_STABILIZE;
}
}
@@ -294,23 +293,41 @@ static APM_PLANE_MODE inavToArduPlaneMap(flightModeForTelemetry_e flightMode)
case FLM_MISSION: return PLANE_MODE_AUTO;
case FLM_CRUISE: return PLANE_MODE_CRUISE;
case FLM_LAUNCH: return PLANE_MODE_TAKEOFF;
- case FLM_FAILSAFE:
+ case FLM_FAILSAFE: //failsafePhase_e
{
if (failsafePhase() == FAILSAFE_RETURN_TO_HOME) {
return PLANE_MODE_RTL;
}
else if (failsafePhase() == FAILSAFE_LANDING) {
- return PLANE_MODE_AUTO;
+ return PLANE_MODE_AUTOLAND;
}
else {
- // There is no valid mapping to ArduPlane
- return PLANE_MODE_ENUM_END;
+ return PLANE_MODE_RTL;
}
}
- default: return PLANE_MODE_ENUM_END;
+ default: return PLANE_MODE_MANUAL;
}
}
+typedef struct mavlinkModeSelection_s {
+ flightModeForTelemetry_e flightMode;
+ uint8_t customMode;
+} mavlinkModeSelection_t;
+
+static mavlinkModeSelection_t selectMavlinkMode(bool isPlane)
+{
+ mavlinkModeSelection_t modeSelection;
+ modeSelection.flightMode = getFlightModeForTelemetry();
+
+ if (isPlane) {
+ modeSelection.customMode = (uint8_t)inavToArduPlaneMap(modeSelection.flightMode);
+ } else {
+ modeSelection.customMode = (uint8_t)inavToArduCopterMap(modeSelection.flightMode);
+ }
+
+ return modeSelection;
+}
+
static int mavlinkStreamTrigger(enum MAV_DATA_STREAM streamNum)
{
uint8_t rate = (uint8_t) mavRates[streamNum];
@@ -586,11 +603,11 @@ static bool mavlinkPlaneModeIsConfigured(uint8_t customMode)
return isModeActivationConditionPresent(BOXNAVWP);
case PLANE_MODE_RTL:
return isModeActivationConditionPresent(BOXNAVRTH);
- case PLANE_MODE_LOITER:
- return isModeActivationConditionPresent(BOXNAVPOSHOLD);
case PLANE_MODE_GUIDED:
return isModeActivationConditionPresent(BOXNAVPOSHOLD) &&
isModeActivationConditionPresent(BOXGCSNAV);
+ case PLANE_MODE_LOITER:
+ return isModeActivationConditionPresent(BOXNAVPOSHOLD);
case PLANE_MODE_TAKEOFF:
return isModeActivationConditionPresent(BOXNAVLAUNCH);
default:
@@ -609,11 +626,11 @@ static bool mavlinkCopterModeIsConfigured(uint8_t customMode)
isModeActivationConditionPresent(BOXANGLEHOLD);
case COPTER_MODE_ALT_HOLD:
return isModeActivationConditionPresent(BOXNAVALTHOLD);
- case COPTER_MODE_POSHOLD:
- return isModeActivationConditionPresent(BOXNAVPOSHOLD);
case COPTER_MODE_GUIDED:
return isModeActivationConditionPresent(BOXNAVPOSHOLD) &&
isModeActivationConditionPresent(BOXGCSNAV);
+ case COPTER_MODE_POSHOLD:
+ return isModeActivationConditionPresent(BOXNAVPOSHOLD);
case COPTER_MODE_RTL:
return isModeActivationConditionPresent(BOXNAVRTH);
case COPTER_MODE_AUTO:
@@ -1124,17 +1141,15 @@ void mavlinkSendHeartbeat(void)
{
uint8_t mavModes = MAV_MODE_FLAG_CUSTOM_MODE_ENABLED;
- flightModeForTelemetry_e flm = getFlightModeForTelemetry();
- uint8_t mavCustomMode;
- uint8_t mavSystemType;
-
const bool isPlane = (STATE(FIXED_WING_LEGACY) || mixerConfig()->platformType == PLATFORM_AIRPLANE);
+ const mavlinkModeSelection_t modeSelection = selectMavlinkMode(isPlane);
+ flightModeForTelemetry_e flm = modeSelection.flightMode;
+ uint8_t mavCustomMode = modeSelection.customMode;
+ uint8_t mavSystemType;
if (isPlane) {
- mavCustomMode = (uint8_t)inavToArduPlaneMap(flm);
mavSystemType = MAV_TYPE_FIXED_WING;
}
else {
- mavCustomMode = (uint8_t)inavToArduCopterMap(flm);
mavSystemType = mavlinkGetVehicleType();
}
@@ -1943,34 +1958,27 @@ static bool handleIncoming_COMMAND(uint8_t targetSystem, uint8_t ackTargetSystem
break;
case MAVLINK_MSG_ID_AVAILABLE_MODES:
{
- flightModeForTelemetry_e flm = getFlightModeForTelemetry();
- uint8_t currentCustom;
- if (mixerConfig()->platformType == PLATFORM_AIRPLANE || STATE(FIXED_WING_LEGACY)) {
- currentCustom = (uint8_t)inavToArduPlaneMap(flm);
- mavlinkSendAvailableModes(planeModes, ARRAYLEN(planeModes), currentCustom, mavlinkPlaneModeIsConfigured);
+ const bool isPlane = mixerConfig()->platformType == PLATFORM_AIRPLANE || STATE(FIXED_WING_LEGACY);
+ const mavlinkModeSelection_t modeSelection = selectMavlinkMode(isPlane);
+ if (isPlane) {
+ mavlinkSendAvailableModes(planeModes, ARRAYLEN(planeModes), modeSelection.customMode, mavlinkPlaneModeIsConfigured);
} else {
- currentCustom = (uint8_t)inavToArduCopterMap(flm);
- mavlinkSendAvailableModes(copterModes, ARRAYLEN(copterModes), currentCustom, mavlinkCopterModeIsConfigured);
+ mavlinkSendAvailableModes(copterModes, ARRAYLEN(copterModes), modeSelection.customMode, mavlinkCopterModeIsConfigured);
}
sent = true;
}
break;
case MAVLINK_MSG_ID_CURRENT_MODE:
{
- flightModeForTelemetry_e flm = getFlightModeForTelemetry();
- uint8_t currentCustom;
- if (mixerConfig()->platformType == PLATFORM_AIRPLANE || STATE(FIXED_WING_LEGACY)) {
- currentCustom = (uint8_t)inavToArduPlaneMap(flm);
- } else {
- currentCustom = (uint8_t)inavToArduCopterMap(flm);
- }
+ const bool isPlane = mixerConfig()->platformType == PLATFORM_AIRPLANE || STATE(FIXED_WING_LEGACY);
+ const mavlinkModeSelection_t modeSelection = selectMavlinkMode(isPlane);
mavlink_msg_current_mode_pack(
mavSystemId,
mavComponentId,
&mavSendMsg,
MAV_STANDARD_MODE_NON_STANDARD,
- currentCustom,
- currentCustom);
+ modeSelection.customMode,
+ modeSelection.customMode);
mavlinkSendMessage();
sent = true;
}
From 9143acc60c824adf37ea678aa57866c58f743c4f Mon Sep 17 00:00:00 2001
From: frogmane <7685285+xznhj8129@users.noreply.github.com>
Date: Mon, 23 Feb 2026 22:27:25 -0500
Subject: [PATCH 20/46] add mavlink doc
---
docs/Mavlink.md | 130 ++++++++++++++++++++++++++++++++++++++++++++++++
1 file changed, 130 insertions(+)
create mode 100644 docs/Mavlink.md
diff --git a/docs/Mavlink.md b/docs/Mavlink.md
new file mode 100644
index 00000000000..8fdd440d3c1
--- /dev/null
+++ b/docs/Mavlink.md
@@ -0,0 +1,130 @@
+# MAVLink INAV Implementation
+
+INAV has a partial implementation of MAVLink that is intended primarily for simple telemetry and operation. It supports RC, missions, telemetry and some features such as Guided mode; but it is very different from a compliant MAVLink spec vehicle such as Pixhawk or Ardupilot and important differences exist, as such it is not 100% compatible and cannot be expected to work the same way. The standard MAVLink header library is used in compilation.
+
+## Fundamental differences from ArduPilot/PX4
+
+- **No MAVLink parameter API**: INAV sends a single stub parameter and otherwise ignores parameter traffic. Configure the aircraft through the INAV Configurator or CLI instead.
+- **Limited command support**: only a subset of commands is implemented; unsupported commands are `COMMAND_ACK`ed as `UNSUPPORTED`.
+- **Mission handling**: uploads are rejected while armed (except legacy guided waypoint writes). Mission frames are validated per command and unsupported frames are rejected.
+- **Mode reporting**: `custom_mode` approximates ArduPilot modes and may not match all INAV states.
+- **Flow control expectations**: INAV honours `RADIO_STATUS.txbuf` to avoid overrunning radios; without it, packets are simply paced at 20 ms intervals.
+- **Half‑duplex etiquette**: when half‑duplex is enabled, INAV waits one telemetry tick after any received frame before transmitting to reduce collisions.
+
+### Relevant CLI options
+
+- `mavlink_sysid` – system ID used in every outbound packet (default 1); most inbound handlers only act on packets targeted to this system ID.
+- `mavlink_autopilot_type` – heartbeat autopilot ID (`GENERIC` or `ARDUPILOT`).
+- `mavlink_version` – force MAVLink v1 when set to 1.
+- Stream rates (Hz): `mavlink_ext_status_rate`, `mavlink_rc_chan_rate`, `mavlink_pos_rate`, `mavlink_extra1_rate`, `mavlink_extra2_rate`, `mavlink_extra3_rate`. Each group is polled up to 50 Hz; a rate of 0 disables the group.
+- `mavlink_min_txbuffer` – minimum remote TX buffer level before sending when `RADIO_STATUS` provides flow control.
+- `mavlink_radio_type` – scales `RADIO_STATUS` RSSI/SNR for **generic**, **ELRS**, or **SiK** links.
+
+## Supported Outgoing Messages
+
+Messages are organized into MAVLink datastream groups. Each group sends **one message per trigger** at the configured rate:
+
+- `SYS_STATUS`: Advertises detected sensors (gyro/accel/compass, baro, pitot, GPS, optical flow, rangefinder, RC, blackbox) and whether they are healthy. Includes main loop load, battery voltage/current/percentage, and logging capability.
+- `RC_CHANNELS_RAW`: for v1, `RC_CHANNELS`: for v2. Up to 18 input channels plus RSSI mapped to MAVLink units.
+- `GPS_RAW_INT`: for GNSS fix quality, HDOP/VDOP, velocity, and satellite count when a fix (or estimated fix) exists.
+- `GLOBAL_POSITION_INT`: couples GPS position with INAV's altitude and velocity estimates.
+- `GPS_GLOBAL_ORIGIN`: broadcasts the current home position.
+- `ATTITUDE`: Roll, pitch, yaw, and angular rates.
+- `VFR_HUD`: with airspeed (if a healthy pitot is available), ground speed, throttle, altitude, and climb rate.
+- `HEARTBEAT`: encodes arming state and maps INAV flight modes onto ArduPilot-style `custom_mode`: values (see mappings below).
+- `EXTENDED_SYS_STATE`: publishes landed state.
+- `BATTERY_STATUS`: with per-cell voltages (cells 11‑14 in `voltages_ext`), current draw, consumed mAh/Wh, and remaining percentage when available.
+- `SCALED_PRESSURE`: for IMU/baro temperature.
+- `STATUSTEXT`: when the OSD has a pending system message; severity follows OSD attributes (notice/warning/critical).
+- On-demand (command-triggered) messages: `AUTOPILOT_VERSION`, `PROTOCOL_VERSION`, `MESSAGE_INTERVAL`, `HOME_POSITION`, `AVAILABLE_MODES`, and `CURRENT_MODE`.
+
+## Supported Incoming Messages
+
+- `HEARTBEAT`: used to detect ADS‑B participants when `type` is `MAV_TYPE_ADSB`.
+- `MISSION_COUNT`: starts an upload transaction (capped at `NAV_MAX_WAYPOINTS`).
+- `MISSION_ITEM` / `MISSION_ITEM_INT`: stores mission waypoints; rejects unsupported frames/sequence errors. Upload while armed is rejected except legacy guided waypoint writes.
+- `MISSION_REQUEST_LIST`, `MISSION_REQUEST`, `MISSION_REQUEST_INT`: downloads active mission items; returns `MISSION_ACK` on bad sequence.
+- `MISSION_CLEAR_ALL`: clears stored mission.
+- `COMMAND_LONG` / `COMMAND_INT`: command transport for supported `MAV_CMD_*` handlers.
+- `REQUEST_DATA_STREAM`: legacy stream-rate control per stream group.
+- `SET_POSITION_TARGET_GLOBAL_INT`: writes the GCS-guided waypoint when the frame is supported.
+- `RC_CHANNELS_OVERRIDE` passes channel values to the MAVLink serial receiver backend.
+- `RADIO_STATUS` updates remote TX buffer level and scales RSSI/SNR according to `mavlink_radio_type` (also feeds link stats for MAVLink RX receivers).
+- `ADSB_VEHICLE` populates the internal traffic list when ADS‑B is enabled.
+- `PARAM_REQUEST_LIST` elicits a stub `PARAM_VALUE` response so ground stations stop requesting parameters (INAV does not expose parameters over MAVLink).
+
+
+## Supported Commands
+
+Limited implementation of the Command protocol.
+
+- `MAV_CMD_DO_REPOSITION`: sets the Follow Me/GCS Nav waypoint when GCS NAV is valid. Accepts `MAV_FRAME_GLOBAL`, `MAV_FRAME_GLOBAL_INT`, `MAV_FRAME_GLOBAL_RELATIVE_ALT`, `MAV_FRAME_GLOBAL_RELATIVE_ALT_INT`; otherwise `UNSUPPORTED`.
+- `MAV_CMD_SET_MESSAGE_INTERVAL` / `MAV_CMD_GET_MESSAGE_INTERVAL`: adjust or query telemetry stream output for supported message IDs (streamed messages only; intervals slower than 1 Hz are not accepted).
+- `MAV_CMD_GET_HOME_POSITION`: replies with `HOME_POSITION` when home fix exists.
+- `MAV_CMD_REQUEST_MESSAGE`: emits one selected message (`HEARTBEAT`, `SYS_STATUS`, `ATTITUDE`, `VFR_HUD`, `AVAILABLE_MODES`, `CURRENT_MODE`, `EXTENDED_SYS_STATE`, RC channels, GPS/global/origin, battery/pressure, and `HOME_POSITION` when available) or `UNSUPPORTED`.
+- `MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES`: returns stub `AUTOPILOT_VERSION` (v2 only; v1 returns `UNSUPPORTED`).
+- `MAV_CMD_REQUEST_PROTOCOL_VERSION`: returns stub `PROTOCOL_VERSION` (v2 only; v1 returns `UNSUPPORTED`).
+
+## Mode mappings (INAV → MAVLink/ArduPilot)
+
+`custom_mode` is derived from active INAV telemetry flight mode (`getFlightModeForTelemetry()`), then mapped per vehicle type.
+
+- **Multirotor profiles**
+ - ACRO / ACRO AIR → **ACRO**
+ - ANGLE / HORIZON / ANGLE HOLD → **STABILIZE**
+ - ALT HOLD → **ALT_HOLD**
+ - POS HOLD → **GUIDED** (if GCS valid), otherwise **POSHOLD**
+ - RTH → **RTL**
+ - MISSION → **AUTO**
+ - LAUNCH → **THROW**
+ - FAILSAFE → **RTL** (RTH/other phases) or **LAND** (landing phase)
+ - Any other unmapped mode falls back to **STABILIZE**
+- **Fixed-wing profiles**
+ - MANUAL → **MANUAL**
+ - ACRO / ACRO AIR → **ACRO**
+ - ANGLE → **FBWA**
+ - HORIZON / ANGLE HOLD → **STABILIZE**
+ - ALT HOLD → **FBWB**
+ - POS HOLD → **GUIDED** (if GCS valid), otherwise **LOITER**
+ - RTH → **RTL**
+ - MISSION → **AUTO**
+ - CRUISE → **CRUISE**
+ - LAUNCH → **TAKEOFF**
+ - FAILSAFE → **RTL** (RTH/other phases) or **AUTOLAND** (landing phase)
+ - Any other unmapped mode falls back to **MANUAL**
+
+## Datastream groups and defaults
+
+Default rates (Hz) are shown; adjust with the CLI keys above.
+
+| Datastream group | Messages | Default rate |
+| --- | --- | --- |
+| `EXTENDED_STATUS` | `SYS_STATUS` | 2 Hz |
+| `RC_CHANNELS` | `RC_CHANNELS_RAW` (v1) / `RC_CHANNELS` (v2) | 1 Hz |
+| `POSITION` | `GPS_RAW_INT`, `GLOBAL_POSITION_INT`, `GPS_GLOBAL_ORIGIN` | 2 Hz |
+| `EXTRA1` | `ATTITUDE` | 3 Hz |
+| `EXTRA2` | `VFR_HUD`, `HEARTBEAT` | 2 Hz |
+| `EXT_SYS_STATE` | `EXTENDED_SYS_STATE` | 1 Hz (defaults to `mavlink_extra3_rate`) |
+| `EXTRA3` | `BATTERY_STATUS`, `SCALED_PRESSURE`, `STATUSTEXT` (when present) | 1 Hz |
+
+## Operating tips
+
+- Set `mavlink_radio_type` to **ELRS** or **SiK** if you use those links to get accurate link quality scaling in `RADIO_STATUS`.
+- If you rely on RC override via MAVLink, ensure the serial receiver type is set to `SERIALRX_MAVLINK` and consider enabling `telemetry_halfduplex` when RX shares the port.
+- To reduce bandwidth, lower the stream rates for groups you do not need, or disable them entirely by setting the rate to 0.
+
+
+## MAVLink Missions
+
+Partial compatibility with MAVLink mission planners such as QGC is implemented, however the differences between the two protocols means INAV cannot be programmed to it's full potential using only the MAVLINK mission protocol; only simple missions are possible. It is recommended to use MultiWii Planner or the INAV Configurator to program missions.
+
+## MSP mission parity gaps (MAV ↔ MSP)
+
+- WAYPOINT: MSP→MAV sends lat/lon/alt but drops leg speed `p1` and all user-action bits in `p3` (only alt-mode bit drives frame). MAV→MSP stores lat/lon/alt but forces `p1=0`, `p2=0`, keeps only alt-mode bit in `p3`; leg speed and user bits are lost.
+- POSHOLD_TIME / LOITER_TIME: loiter time `p1` OK; leg speed `p2` and user-action bits in `p3` are discarded both directions.
+- LAND: lat/lon/alt OK; leg speed `p1`, ground elevation `p2`, and user-action bits in `p3` are cleared in both directions (only alt-mode bit is retained from frame on upload).
+- RTH: RTH land-if-nonzero flag in `p1` is ignored both ways (always zeroed); user-action bits dropped; alt is sent only if the MAVLink frame is coordinate and returns with alt-mode bit set on upload.
+- JUMP: target and repeat count OK
+- SET_POI: lat/lon/alt OK; `param1` is fixed to `MAV_ROI_LOCATION`; user-action bits in `p3` are dropped (alt-mode bit respected on upload).
+- SET_HEAD: heading `p1` OK; user-action bits in `p3` are not represented.
+- Net effect: actions and positions OK, but MSP-specific fields (leg speed, LAND elevation adjustment, RTH land flag, user-action bits in `p3`) are lost, so MAVLink missions cannot fully conform to `MSP_navigation_messages.md`.
From b9b11c065207722d1caea8b6f48c23f672895cd0 Mon Sep 17 00:00:00 2001
From: frogmane <7685285+xznhj8129@users.noreply.github.com>
Date: Tue, 3 Mar 2026 16:17:16 -0500
Subject: [PATCH 21/46] add altitude command
---
src/main/telemetry/mavlink.c | 26 ++++++++++++++++++++++++++
1 file changed, 26 insertions(+)
diff --git a/src/main/telemetry/mavlink.c b/src/main/telemetry/mavlink.c
index b9e654bdbd8..3c68aa01794 100644
--- a/src/main/telemetry/mavlink.c
+++ b/src/main/telemetry/mavlink.c
@@ -1857,6 +1857,32 @@ static bool handleIncoming_COMMAND(uint8_t targetSystem, uint8_t ackTargetSystem
mavlinkSendCommandAck(command, MAV_RESULT_DENIED, ackTargetSystem, ackTargetComponent);
}
return true;
+#ifdef USE_BARO
+ case MAV_CMD_DO_CHANGE_ALTITUDE:
+ {
+ const float altitudeMeters = param1;
+ geoAltitudeDatumFlag_e datum;
+
+ switch (frame) {
+ case MAV_FRAME_GLOBAL:
+ case MAV_FRAME_GLOBAL_INT:
+ datum = NAV_WP_MSL_DATUM;
+ break;
+ case MAV_FRAME_GLOBAL_RELATIVE_ALT:
+ case MAV_FRAME_GLOBAL_RELATIVE_ALT_INT:
+ datum = NAV_WP_TAKEOFF_DATUM;
+ break;
+ default:
+ mavlinkSendCommandAck(command, MAV_RESULT_UNSUPPORTED, ackTargetSystem, ackTargetComponent);
+ return true;
+ }
+
+ const int32_t targetAltitudeCm = (int32_t)lrintf(altitudeMeters * 100.0f);
+ const bool accepted = navigationSetAltitudeTargetWithDatum(datum, targetAltitudeCm);
+ mavlinkSendCommandAck(command, accepted ? MAV_RESULT_ACCEPTED : MAV_RESULT_DENIED, ackTargetSystem, ackTargetComponent);
+ return true;
+ }
+#endif
case MAV_CMD_SET_MESSAGE_INTERVAL:
{
uint8_t stream;
From 454dd48c7a18149ba83865ee5dce6f1ac0a0fac3 Mon Sep 17 00:00:00 2001
From: frogmane <7685285+xznhj8129@users.noreply.github.com>
Date: Tue, 3 Mar 2026 16:43:43 -0500
Subject: [PATCH 22/46] docgen
---
dm.txt | 0
docs/development/msp/README.md | 2 +-
docs/development/msp/inav_enums.json | 10 +++++++++-
docs/development/msp/inav_enums_ref.md | 4 ++--
docs/development/msp/msp_messages.checksum | 2 +-
docs/development/msp/rev | 2 +-
6 files changed, 14 insertions(+), 6 deletions(-)
delete mode 100644 dm.txt
diff --git a/dm.txt b/dm.txt
deleted file mode 100644
index e69de29bb2d..00000000000
diff --git a/docs/development/msp/README.md b/docs/development/msp/README.md
index 2ca0fff6675..c4b6d06b58d 100644
--- a/docs/development/msp/README.md
+++ b/docs/development/msp/README.md
@@ -9,7 +9,7 @@ For list of enums, see [Enum documentation page](https://github.com/iNavFlight/i
-**JSON file rev: 4**
+**JSON file rev: 0**
**Warning: Verification needed, exercise caution until completely verified for accuracy and cleared, especially for integer signs. Source-based generation/validation is forthcoming. Refer to source for absolute certainty**
diff --git a/docs/development/msp/inav_enums.json b/docs/development/msp/inav_enums.json
index ffe24b3f24c..3844e59cee9 100644
--- a/docs/development/msp/inav_enums.json
+++ b/docs/development/msp/inav_enums.json
@@ -2238,6 +2238,14 @@
"MAG_FAKE": "16",
"MAG_MAX": "MAG_FAKE"
},
+ "mavFrameSupportMask_e": {
+ "_source": "inav/src/main/telemetry/mavlink.c",
+ "MAV_FRAME_SUPPORTED_NONE": "0",
+ "MAV_FRAME_SUPPORTED_GLOBAL": "(1 << 0)",
+ "MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT": "(1 << 1)",
+ "MAV_FRAME_SUPPORTED_GLOBAL_INT": "(1 << 2)",
+ "MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT_INT": "(1 << 3)"
+ },
"mavlinkAutopilotType_e": {
"_source": "inav/src/main/telemetry/telemetry.h",
"MAVLINK_AUTOPILOT_GENERIC": "0",
@@ -3831,7 +3839,7 @@
"THR_HI": "(2 << (2 * THROTTLE))"
},
"systemState_e": {
- "_source": "inav/src/main/fc/fc_init.c",
+ "_source": "inav/src/main/fc/fc_init.h",
"SYSTEM_STATE_INITIALISING": "0",
"SYSTEM_STATE_CONFIG_LOADED": "(1 << 0)",
"SYSTEM_STATE_SENSORS_READY": "(1 << 1)",
diff --git a/docs/development/msp/inav_enums_ref.md b/docs/development/msp/inav_enums_ref.md
index 2ac04b18f18..164ebd9bc14 100644
--- a/docs/development/msp/inav_enums_ref.md
+++ b/docs/development/msp/inav_enums_ref.md
@@ -5643,7 +5643,7 @@
---
## `systemState_e`
-> Source: ../../../src/main/fc/fc_init.h
+> Source: ../../../src/main/fc/fc_init.c
| Enumerator | Value | Condition |
|---|---:|---|
@@ -5657,7 +5657,7 @@
---
## `systemState_e`
-> Source: ../../../src/main/fc/fc_init.c
+> Source: ../../../src/main/fc/fc_init.h
| Enumerator | Value | Condition |
|---|---:|---|
diff --git a/docs/development/msp/msp_messages.checksum b/docs/development/msp/msp_messages.checksum
index ae689c4b8eb..14e143e04b9 100644
--- a/docs/development/msp/msp_messages.checksum
+++ b/docs/development/msp/msp_messages.checksum
@@ -1 +1 @@
-6e8861395a4275489a12012e6985d733
+7146802c1d6c89bce6aeda0d5e95c137
diff --git a/docs/development/msp/rev b/docs/development/msp/rev
index bf0d87ab1b2..c227083464f 100644
--- a/docs/development/msp/rev
+++ b/docs/development/msp/rev
@@ -1 +1 @@
-4
\ No newline at end of file
+0
\ No newline at end of file
From 1250399aec927b57b6af9a6e3d8e8b3d0ed07cf6 Mon Sep 17 00:00:00 2001
From: frogmane <7685285+xznhj8129@users.noreply.github.com>
Date: Tue, 3 Mar 2026 19:53:49 -0500
Subject: [PATCH 23/46] qodo fixes + set_pos_tgt_global alt change + docs
---
docs/Mavlink.md | 7 +--
src/main/telemetry/mavlink.c | 99 +++++++++++++++++++++++++-----------
2 files changed, 73 insertions(+), 33 deletions(-)
diff --git a/docs/Mavlink.md b/docs/Mavlink.md
index 8fdd440d3c1..b29dcdf8f89 100644
--- a/docs/Mavlink.md
+++ b/docs/Mavlink.md
@@ -46,9 +46,9 @@ Messages are organized into MAVLink datastream groups. Each group sends **one me
- `MISSION_REQUEST_LIST`, `MISSION_REQUEST`, `MISSION_REQUEST_INT`: downloads active mission items; returns `MISSION_ACK` on bad sequence.
- `MISSION_CLEAR_ALL`: clears stored mission.
- `COMMAND_LONG` / `COMMAND_INT`: command transport for supported `MAV_CMD_*` handlers.
-- `REQUEST_DATA_STREAM`: legacy stream-rate control per stream group.
-- `SET_POSITION_TARGET_GLOBAL_INT`: writes the GCS-guided waypoint when the frame is supported.
-- `RC_CHANNELS_OVERRIDE` passes channel values to the MAVLink serial receiver backend.
+- `REQUEST_DATA_STREAM`: legacy stream-rate control per stream group. `MAV_DATA_STREAM_ALL` (0) applies to all INAV-scheduled groups (`EXTENDED_STATUS`, `RC_CHANNELS`, `POSITION`, `EXTRA1`, `EXTRA2`, `EXTRA3`, `EXTENDED_SYS_STATE`); `start_stop==0` stops the addressed stream(s).
+- `SET_POSITION_TARGET_GLOBAL_INT`: requires matching `target_system` and `target_component` (`0` or local component), validates frame/type-mask semantics, updates guided WP255 for XY targets, and supports altitude-only control (`X/Y ignore`, `Z set`) using the same datum logic as `MAV_CMD_DO_CHANGE_ALTITUDE`.
+- `RC_CHANNELS_OVERRIDE` passes channel values to the MAVLink serial receiver backend when targeted to the local system ID.
- `RADIO_STATUS` updates remote TX buffer level and scales RSSI/SNR according to `mavlink_radio_type` (also feeds link stats for MAVLink RX receivers).
- `ADSB_VEHICLE` populates the internal traffic list when ADS‑B is enabled.
- `PARAM_REQUEST_LIST` elicits a stub `PARAM_VALUE` response so ground stations stop requesting parameters (INAV does not expose parameters over MAVLink).
@@ -59,6 +59,7 @@ Messages are organized into MAVLink datastream groups. Each group sends **one me
Limited implementation of the Command protocol.
- `MAV_CMD_DO_REPOSITION`: sets the Follow Me/GCS Nav waypoint when GCS NAV is valid. Accepts `MAV_FRAME_GLOBAL`, `MAV_FRAME_GLOBAL_INT`, `MAV_FRAME_GLOBAL_RELATIVE_ALT`, `MAV_FRAME_GLOBAL_RELATIVE_ALT_INT`; otherwise `UNSUPPORTED`.
+- `MAV_CMD_DO_CHANGE_ALTITUDE`: supported when barometer support is compiled (`USE_BARO`); accepts global/global-int (MSL datum) and global-relative/global-relative-int (takeoff-relative datum), then calls navigation altitude-target update.
- `MAV_CMD_SET_MESSAGE_INTERVAL` / `MAV_CMD_GET_MESSAGE_INTERVAL`: adjust or query telemetry stream output for supported message IDs (streamed messages only; intervals slower than 1 Hz are not accepted).
- `MAV_CMD_GET_HOME_POSITION`: replies with `HOME_POSITION` when home fix exists.
- `MAV_CMD_REQUEST_MESSAGE`: emits one selected message (`HEARTBEAT`, `SYS_STATUS`, `ATTITUDE`, `VFR_HUD`, `AVAILABLE_MODES`, `CURRENT_MODE`, `EXTENDED_SYS_STATE`, RC channels, GPS/global/origin, battery/pressure, and `HOME_POSITION` when available) or `UNSUPPORTED`.
diff --git a/src/main/telemetry/mavlink.c b/src/main/telemetry/mavlink.c
index 3c68aa01794..d7713ac6833 100644
--- a/src/main/telemetry/mavlink.c
+++ b/src/main/telemetry/mavlink.c
@@ -526,6 +526,33 @@ static bool mavlinkFrameUsesAbsoluteAltitude(uint8_t frame)
return frame == MAV_FRAME_GLOBAL || frame == MAV_FRAME_GLOBAL_INT;
}
+static MAV_RESULT mavlinkSetAltitudeTargetFromFrame(uint8_t frame, float altitudeMeters)
+{
+#ifdef USE_BARO
+ geoAltitudeDatumFlag_e datum;
+
+ switch (frame) {
+ case MAV_FRAME_GLOBAL:
+ case MAV_FRAME_GLOBAL_INT:
+ datum = NAV_WP_MSL_DATUM;
+ break;
+ case MAV_FRAME_GLOBAL_RELATIVE_ALT:
+ case MAV_FRAME_GLOBAL_RELATIVE_ALT_INT:
+ datum = NAV_WP_TAKEOFF_DATUM;
+ break;
+ default:
+ return MAV_RESULT_UNSUPPORTED;
+ }
+
+ const int32_t targetAltitudeCm = (int32_t)lrintf(altitudeMeters * 100.0f);
+ return navigationSetAltitudeTargetWithDatum(datum, targetAltitudeCm) ? MAV_RESULT_ACCEPTED : MAV_RESULT_DENIED;
+#else
+ UNUSED(frame);
+ UNUSED(altitudeMeters);
+ return MAV_RESULT_UNSUPPORTED;
+#endif
+}
+
static uint8_t navWaypointFrame(const navWaypoint_t *wp, bool useIntMessages)
{
switch (wp->action) {
@@ -1857,32 +1884,12 @@ static bool handleIncoming_COMMAND(uint8_t targetSystem, uint8_t ackTargetSystem
mavlinkSendCommandAck(command, MAV_RESULT_DENIED, ackTargetSystem, ackTargetComponent);
}
return true;
-#ifdef USE_BARO
case MAV_CMD_DO_CHANGE_ALTITUDE:
{
- const float altitudeMeters = param1;
- geoAltitudeDatumFlag_e datum;
-
- switch (frame) {
- case MAV_FRAME_GLOBAL:
- case MAV_FRAME_GLOBAL_INT:
- datum = NAV_WP_MSL_DATUM;
- break;
- case MAV_FRAME_GLOBAL_RELATIVE_ALT:
- case MAV_FRAME_GLOBAL_RELATIVE_ALT_INT:
- datum = NAV_WP_TAKEOFF_DATUM;
- break;
- default:
- mavlinkSendCommandAck(command, MAV_RESULT_UNSUPPORTED, ackTargetSystem, ackTargetComponent);
- return true;
- }
-
- const int32_t targetAltitudeCm = (int32_t)lrintf(altitudeMeters * 100.0f);
- const bool accepted = navigationSetAltitudeTargetWithDatum(datum, targetAltitudeCm);
- mavlinkSendCommandAck(command, accepted ? MAV_RESULT_ACCEPTED : MAV_RESULT_DENIED, ackTargetSystem, ackTargetComponent);
+ const MAV_RESULT result = mavlinkSetAltitudeTargetFromFrame(frame, param1);
+ mavlinkSendCommandAck(command, result, ackTargetSystem, ackTargetComponent);
return true;
}
-#endif
case MAV_CMD_SET_MESSAGE_INTERVAL:
{
uint8_t stream;
@@ -2175,15 +2182,25 @@ static bool handleIncoming_REQUEST_DATA_STREAM(void)
return false;
}
- if (msg.start_stop == 0) {
- mavlinkSetStreamRate(msg.req_stream_id, 0);
- return true;
+ uint8_t rate = 0;
+ if (msg.start_stop != 0) {
+ rate = (uint8_t)msg.req_message_rate;
+ if (rate > TELEMETRY_MAVLINK_MAXRATE) {
+ rate = TELEMETRY_MAVLINK_MAXRATE;
+ }
}
- uint8_t rate = (uint8_t)msg.req_message_rate;
- if (rate > TELEMETRY_MAVLINK_MAXRATE) {
- rate = TELEMETRY_MAVLINK_MAXRATE;
+ if (msg.req_stream_id == MAV_DATA_STREAM_ALL) {
+ mavlinkSetStreamRate(MAV_DATA_STREAM_EXTENDED_STATUS, rate);
+ mavlinkSetStreamRate(MAV_DATA_STREAM_RC_CHANNELS, rate);
+ mavlinkSetStreamRate(MAV_DATA_STREAM_POSITION, rate);
+ mavlinkSetStreamRate(MAV_DATA_STREAM_EXTRA1, rate);
+ mavlinkSetStreamRate(MAV_DATA_STREAM_EXTRA2, rate);
+ mavlinkSetStreamRate(MAV_DATA_STREAM_EXTRA3, rate);
+ mavlinkSetStreamRate(MAV_DATA_STREAM_EXTENDED_SYS_STATE, rate);
+ return true;
}
+
mavlinkSetStreamRate(msg.req_stream_id, rate);
return true;
}
@@ -2196,20 +2213,40 @@ static bool handleIncoming_SET_POSITION_TARGET_GLOBAL_INT(void)
if (msg.target_system != mavSystemId) {
return false;
}
+ if (msg.target_component != 0 && msg.target_component != mavComponentId) {
+ return false;
+ }
uint8_t frame = msg.coordinate_frame;
if (!mavlinkFrameIsSupported(frame,
+ MAV_FRAME_SUPPORTED_GLOBAL |
+ MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT |
MAV_FRAME_SUPPORTED_GLOBAL_INT |
MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT_INT)) {
return true;
}
+ const uint16_t typeMask = msg.type_mask;
+ const bool xIgnored = (typeMask & POSITION_TARGET_TYPEMASK_X_IGNORE) != 0;
+ const bool yIgnored = (typeMask & POSITION_TARGET_TYPEMASK_Y_IGNORE) != 0;
+ const bool zIgnored = (typeMask & POSITION_TARGET_TYPEMASK_Z_IGNORE) != 0;
+
+ // Altitude-only SET_POSITION_TARGET_GLOBAL_INT mirrors MAV_CMD_DO_CHANGE_ALTITUDE semantics.
+ if (xIgnored && yIgnored && !zIgnored) {
+ mavlinkSetAltitudeTargetFromFrame(frame, msg.alt);
+ return true;
+ }
+
+ if (xIgnored || yIgnored) {
+ return true;
+ }
+
if (isGCSValid()) {
navWaypoint_t wp;
wp.action = NAV_WP_ACTION_WAYPOINT;
wp.lat = msg.lat_int;
wp.lon = msg.lon_int;
- wp.alt = (int32_t)(msg.alt * 100.0f);
+ wp.alt = zIgnored ? 0 : (int32_t)(msg.alt * 100.0f);
wp.p1 = 0;
wp.p2 = 0;
wp.p3 = mavlinkFrameUsesAbsoluteAltitude(frame) ? NAV_WP_ALTMODE : 0;
@@ -2225,7 +2262,9 @@ static bool handleIncoming_SET_POSITION_TARGET_GLOBAL_INT(void)
static bool handleIncoming_RC_CHANNELS_OVERRIDE(void) {
mavlink_rc_channels_override_t msg;
mavlink_msg_rc_channels_override_decode(&mavRecvMsg, &msg);
- // Don't check system ID because it's not configurable with systems like Crossfire
+ if (msg.target_system != mavSystemId) {
+ return false;
+ }
mavlinkRxHandleMessage(&msg);
return true;
}
From eda3b3f284f4e3c4514cee09d862b0c04ed25a89 Mon Sep 17 00:00:00 2001
From: frogmane <7685285+xznhj8129@users.noreply.github.com>
Date: Thu, 26 Feb 2026 19:02:29 -0500
Subject: [PATCH 24/46] multi mav port + router, iteration 1
---
docs/Settings.md | 280 +++++++++++++
src/main/fc/settings.yaml | 206 +++++++++-
src/main/rx/mavlink.h | 6 +-
src/main/telemetry/mavlink.c | 700 ++++++++++++++++++++++++++++-----
src/main/telemetry/mavlink.h | 1 -
src/main/telemetry/telemetry.c | 58 ++-
src/main/telemetry/telemetry.h | 34 +-
7 files changed, 1142 insertions(+), 143 deletions(-)
diff --git a/docs/Settings.md b/docs/Settings.md
index 4e577bbedd5..610834d0d7f 100644
--- a/docs/Settings.md
+++ b/docs/Settings.md
@@ -2702,6 +2702,286 @@ Minimum percent of TX buffer space free, before attempting to transmit telemetry
---
+### mavlink_port1_compid
+
+MAVLink Component ID for MAVLink port 1
+
+| Default | Min | Max |
+| --- | --- | --- |
+| 1 | 1 | 255 |
+
+---
+
+### mavlink_port1_high_latency
+
+Enable MAVLink high-latency mode on port 1
+
+| Default | Min | Max |
+| --- | --- | --- |
+| OFF | OFF | ON |
+
+---
+
+### mavlink_port2_autopilot_type
+
+Autopilot type to advertise for MAVLink telemetry on port 2
+
+| Default | Min | Max |
+| --- | --- | --- |
+| GENERIC | | |
+
+---
+
+### mavlink_port2_compid
+
+MAVLink Component ID for MAVLink port 2
+
+| Default | Min | Max |
+| --- | --- | --- |
+| 1 | 1 | 255 |
+
+---
+
+### mavlink_port2_ext_status_rate
+
+Rate of the extended status message for MAVLink telemetry on port 2
+
+| Default | Min | Max |
+| --- | --- | --- |
+| 2 | 0 | 255 |
+
+---
+
+### mavlink_port2_extra1_rate
+
+Rate of the extra1 message for MAVLink telemetry on port 2
+
+| Default | Min | Max |
+| --- | --- | --- |
+| 2 | 0 | 255 |
+
+---
+
+### mavlink_port2_extra2_rate
+
+Rate of the extra2 message for MAVLink telemetry on port 2
+
+| Default | Min | Max |
+| --- | --- | --- |
+| 2 | 0 | 255 |
+
+---
+
+### mavlink_port2_extra3_rate
+
+Rate of the extra3 message for MAVLink telemetry on port 2
+
+| Default | Min | Max |
+| --- | --- | --- |
+| 1 | 0 | 255 |
+
+---
+
+### mavlink_port2_high_latency
+
+Enable MAVLink high-latency mode on port 2
+
+| Default | Min | Max |
+| --- | --- | --- |
+| OFF | OFF | ON |
+
+---
+
+### mavlink_port2_min_txbuffer
+
+Minimum percent of TX buffer space free for MAVLink port 2. Requires RADIO_STATUS messages.
+
+| Default | Min | Max |
+| --- | --- | --- |
+| 33 | 0 | 100 |
+
+---
+
+### mavlink_port2_pos_rate
+
+Rate of the position message for MAVLink telemetry on port 2
+
+| Default | Min | Max |
+| --- | --- | --- |
+| 2 | 0 | 255 |
+
+---
+
+### mavlink_port2_radio_type
+
+MAVLink radio type for port 2. Affects RSSI and LQ reporting on OSD.
+
+| Default | Min | Max |
+| --- | --- | --- |
+| GENERIC | | |
+
+---
+
+### mavlink_port2_rc_chan_rate
+
+Rate of the RC channels message for MAVLink telemetry on port 2
+
+| Default | Min | Max |
+| --- | --- | --- |
+| 1 | 0 | 255 |
+
+---
+
+### mavlink_port2_sysid
+
+MAVLink System ID for MAVLink port 2
+
+| Default | Min | Max |
+| --- | --- | --- |
+| 1 | 1 | 255 |
+
+---
+
+### mavlink_port2_version
+
+Version of MAVLink to use on port 2
+
+| Default | Min | Max |
+| --- | --- | --- |
+| 2 | 1 | 2 |
+
+---
+
+### mavlink_port3_autopilot_type
+
+Autopilot type to advertise for MAVLink telemetry on port 3
+
+| Default | Min | Max |
+| --- | --- | --- |
+| GENERIC | | |
+
+---
+
+### mavlink_port3_compid
+
+MAVLink Component ID for MAVLink port 3
+
+| Default | Min | Max |
+| --- | --- | --- |
+| 1 | 1 | 255 |
+
+---
+
+### mavlink_port3_ext_status_rate
+
+Rate of the extended status message for MAVLink telemetry on port 3
+
+| Default | Min | Max |
+| --- | --- | --- |
+| 2 | 0 | 255 |
+
+---
+
+### mavlink_port3_extra1_rate
+
+Rate of the extra1 message for MAVLink telemetry on port 3
+
+| Default | Min | Max |
+| --- | --- | --- |
+| 2 | 0 | 255 |
+
+---
+
+### mavlink_port3_extra2_rate
+
+Rate of the extra2 message for MAVLink telemetry on port 3
+
+| Default | Min | Max |
+| --- | --- | --- |
+| 2 | 0 | 255 |
+
+---
+
+### mavlink_port3_extra3_rate
+
+Rate of the extra3 message for MAVLink telemetry on port 3
+
+| Default | Min | Max |
+| --- | --- | --- |
+| 1 | 0 | 255 |
+
+---
+
+### mavlink_port3_high_latency
+
+Enable MAVLink high-latency mode on port 3
+
+| Default | Min | Max |
+| --- | --- | --- |
+| OFF | OFF | ON |
+
+---
+
+### mavlink_port3_min_txbuffer
+
+Minimum percent of TX buffer space free for MAVLink port 3. Requires RADIO_STATUS messages.
+
+| Default | Min | Max |
+| --- | --- | --- |
+| 33 | 0 | 100 |
+
+---
+
+### mavlink_port3_pos_rate
+
+Rate of the position message for MAVLink telemetry on port 3
+
+| Default | Min | Max |
+| --- | --- | --- |
+| 2 | 0 | 255 |
+
+---
+
+### mavlink_port3_radio_type
+
+MAVLink radio type for port 3. Affects RSSI and LQ reporting on OSD.
+
+| Default | Min | Max |
+| --- | --- | --- |
+| GENERIC | | |
+
+---
+
+### mavlink_port3_rc_chan_rate
+
+Rate of the RC channels message for MAVLink telemetry on port 3
+
+| Default | Min | Max |
+| --- | --- | --- |
+| 1 | 0 | 255 |
+
+---
+
+### mavlink_port3_sysid
+
+MAVLink System ID for MAVLink port 3
+
+| Default | Min | Max |
+| --- | --- | --- |
+| 1 | 1 | 255 |
+
+---
+
+### mavlink_port3_version
+
+Version of MAVLink to use on port 3
+
+| Default | Min | Max |
+| --- | --- | --- |
+| 2 | 1 | 2 |
+
+---
+
### mavlink_pos_rate
Rate of the position message for MAVLink telemetry
diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml
index 1e1932531e5..c7342f50b17 100644
--- a/src/main/fc/settings.yaml
+++ b/src/main/fc/settings.yaml
@@ -3225,79 +3225,263 @@ groups:
min: INT16_MIN
max: INT16_MAX
- name: mavlink_ext_status_rate
- field: mavlink.extended_status_rate
+ field: mavlink[0].extended_status_rate
description: "Rate of the extended status message for MAVLink telemetry"
type: uint8_t
min: 0
max: 255
default_value: 2
- name: mavlink_autopilot_type
- field: mavlink.autopilot_type
+ field: mavlink[0].autopilot_type
description: "Autopilot type to advertise for MAVLink telemetry"
table: mavlink_autopilot_type
default_value: "GENERIC"
type: uint8_t
- name: mavlink_rc_chan_rate
description: "Rate of the RC channels message for MAVLink telemetry"
- field: mavlink.rc_channels_rate
+ field: mavlink[0].rc_channels_rate
type: uint8_t
min: 0
max: 255
default_value: 1
- name: mavlink_pos_rate
description: "Rate of the position message for MAVLink telemetry"
- field: mavlink.position_rate
+ field: mavlink[0].position_rate
type: uint8_t
min: 0
max: 255
default_value: 2
- name: mavlink_extra1_rate
description: "Rate of the extra1 message for MAVLink telemetry"
- field: mavlink.extra1_rate
+ field: mavlink[0].extra1_rate
type: uint8_t
min: 0
max: 255
default_value: 2
- name: mavlink_extra2_rate
description: "Rate of the extra2 message for MAVLink telemetry"
- field: mavlink.extra2_rate
+ field: mavlink[0].extra2_rate
type: uint8_t
min: 0
max: 255
default_value: 2
- name: mavlink_extra3_rate
description: "Rate of the extra3 message for MAVLink telemetry"
- field: mavlink.extra3_rate
+ field: mavlink[0].extra3_rate
type: uint8_t
min: 0
max: 255
default_value: 1
- name: mavlink_version
- field: mavlink.version
+ field: mavlink[0].version
description: "Version of MAVLink to use"
type: uint8_t
min: 1
max: 2
default_value: 2
- name: mavlink_min_txbuffer
- field: mavlink.min_txbuff
+ field: mavlink[0].min_txbuff
description: "Minimum percent of TX buffer space free, before attempting to transmit telemetry. Requuires RADIO_STATUS messages to be processed. 0 = always transmits."
default_value: 33
min: 0
max: 100
- name: mavlink_radio_type
description: "Mavlink radio type. Affects how RSSI and LQ are reported on OSD."
- field: mavlink.radio_type
+ field: mavlink[0].radio_type
table: mavlink_radio_type
default_value: "GENERIC"
type: uint8_t
- name: mavlink_sysid
- field: mavlink.sysid
+ field: mavlink[0].sysid
description: "MAVLink System ID"
type: uint8_t
min: 1
max: 255
default_value: 1
+ - name: mavlink_port1_compid
+ field: mavlink[0].compid
+ description: "MAVLink Component ID for MAVLink port 1"
+ type: uint8_t
+ min: 1
+ max: 255
+ default_value: 1
+ - name: mavlink_port1_high_latency
+ field: mavlink[0].high_latency
+ description: "Enable MAVLink high-latency mode on port 1"
+ type: bool
+ default_value: OFF
+ - name: mavlink_port2_ext_status_rate
+ field: mavlink[1].extended_status_rate
+ description: "Rate of the extended status message for MAVLink telemetry on port 2"
+ type: uint8_t
+ min: 0
+ max: 255
+ default_value: 2
+ - name: mavlink_port2_autopilot_type
+ field: mavlink[1].autopilot_type
+ description: "Autopilot type to advertise for MAVLink telemetry on port 2"
+ table: mavlink_autopilot_type
+ default_value: "GENERIC"
+ type: uint8_t
+ - name: mavlink_port2_rc_chan_rate
+ description: "Rate of the RC channels message for MAVLink telemetry on port 2"
+ field: mavlink[1].rc_channels_rate
+ type: uint8_t
+ min: 0
+ max: 255
+ default_value: 1
+ - name: mavlink_port2_pos_rate
+ description: "Rate of the position message for MAVLink telemetry on port 2"
+ field: mavlink[1].position_rate
+ type: uint8_t
+ min: 0
+ max: 255
+ default_value: 2
+ - name: mavlink_port2_extra1_rate
+ description: "Rate of the extra1 message for MAVLink telemetry on port 2"
+ field: mavlink[1].extra1_rate
+ type: uint8_t
+ min: 0
+ max: 255
+ default_value: 2
+ - name: mavlink_port2_extra2_rate
+ description: "Rate of the extra2 message for MAVLink telemetry on port 2"
+ field: mavlink[1].extra2_rate
+ type: uint8_t
+ min: 0
+ max: 255
+ default_value: 2
+ - name: mavlink_port2_extra3_rate
+ description: "Rate of the extra3 message for MAVLink telemetry on port 2"
+ field: mavlink[1].extra3_rate
+ type: uint8_t
+ min: 0
+ max: 255
+ default_value: 1
+ - name: mavlink_port2_version
+ field: mavlink[1].version
+ description: "Version of MAVLink to use on port 2"
+ type: uint8_t
+ min: 1
+ max: 2
+ default_value: 2
+ - name: mavlink_port2_min_txbuffer
+ field: mavlink[1].min_txbuff
+ description: "Minimum percent of TX buffer space free for MAVLink port 2. Requires RADIO_STATUS messages."
+ default_value: 33
+ min: 0
+ max: 100
+ - name: mavlink_port2_radio_type
+ description: "MAVLink radio type for port 2. Affects RSSI and LQ reporting on OSD."
+ field: mavlink[1].radio_type
+ table: mavlink_radio_type
+ default_value: "GENERIC"
+ type: uint8_t
+ - name: mavlink_port2_sysid
+ field: mavlink[1].sysid
+ description: "MAVLink System ID for MAVLink port 2"
+ type: uint8_t
+ min: 1
+ max: 255
+ default_value: 1
+ - name: mavlink_port2_compid
+ field: mavlink[1].compid
+ description: "MAVLink Component ID for MAVLink port 2"
+ type: uint8_t
+ min: 1
+ max: 255
+ default_value: 1
+ - name: mavlink_port2_high_latency
+ field: mavlink[1].high_latency
+ description: "Enable MAVLink high-latency mode on port 2"
+ type: bool
+ default_value: OFF
+ - name: mavlink_port3_ext_status_rate
+ field: mavlink[2].extended_status_rate
+ description: "Rate of the extended status message for MAVLink telemetry on port 3"
+ type: uint8_t
+ min: 0
+ max: 255
+ default_value: 2
+ - name: mavlink_port3_autopilot_type
+ field: mavlink[2].autopilot_type
+ description: "Autopilot type to advertise for MAVLink telemetry on port 3"
+ table: mavlink_autopilot_type
+ default_value: "GENERIC"
+ type: uint8_t
+ - name: mavlink_port3_rc_chan_rate
+ description: "Rate of the RC channels message for MAVLink telemetry on port 3"
+ field: mavlink[2].rc_channels_rate
+ type: uint8_t
+ min: 0
+ max: 255
+ default_value: 1
+ - name: mavlink_port3_pos_rate
+ description: "Rate of the position message for MAVLink telemetry on port 3"
+ field: mavlink[2].position_rate
+ type: uint8_t
+ min: 0
+ max: 255
+ default_value: 2
+ - name: mavlink_port3_extra1_rate
+ description: "Rate of the extra1 message for MAVLink telemetry on port 3"
+ field: mavlink[2].extra1_rate
+ type: uint8_t
+ min: 0
+ max: 255
+ default_value: 2
+ - name: mavlink_port3_extra2_rate
+ description: "Rate of the extra2 message for MAVLink telemetry on port 3"
+ field: mavlink[2].extra2_rate
+ type: uint8_t
+ min: 0
+ max: 255
+ default_value: 2
+ - name: mavlink_port3_extra3_rate
+ description: "Rate of the extra3 message for MAVLink telemetry on port 3"
+ field: mavlink[2].extra3_rate
+ type: uint8_t
+ min: 0
+ max: 255
+ default_value: 1
+ - name: mavlink_port3_version
+ field: mavlink[2].version
+ description: "Version of MAVLink to use on port 3"
+ type: uint8_t
+ min: 1
+ max: 2
+ default_value: 2
+ - name: mavlink_port3_min_txbuffer
+ field: mavlink[2].min_txbuff
+ description: "Minimum percent of TX buffer space free for MAVLink port 3. Requires RADIO_STATUS messages."
+ default_value: 33
+ min: 0
+ max: 100
+ - name: mavlink_port3_radio_type
+ description: "MAVLink radio type for port 3. Affects RSSI and LQ reporting on OSD."
+ field: mavlink[2].radio_type
+ table: mavlink_radio_type
+ default_value: "GENERIC"
+ type: uint8_t
+ - name: mavlink_port3_sysid
+ field: mavlink[2].sysid
+ description: "MAVLink System ID for MAVLink port 3"
+ type: uint8_t
+ min: 1
+ max: 255
+ default_value: 1
+ - name: mavlink_port3_compid
+ field: mavlink[2].compid
+ description: "MAVLink Component ID for MAVLink port 3"
+ type: uint8_t
+ min: 1
+ max: 255
+ default_value: 1
+ - name: mavlink_port3_high_latency
+ field: mavlink[2].high_latency
+ description: "Enable MAVLink high-latency mode on port 3"
+ type: bool
+ default_value: OFF
- name: PG_OSD_CONFIG
type: osdConfig_t
diff --git a/src/main/rx/mavlink.h b/src/main/rx/mavlink.h
index 951b0eba105..644e71d4f8d 100644
--- a/src/main/rx/mavlink.h
+++ b/src/main/rx/mavlink.h
@@ -17,9 +17,13 @@
#pragma once
+#ifndef MAX_MAVLINK_PORTS
+#define MAX_MAVLINK_PORTS 3
+#endif
+
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wunused-function"
-#define MAVLINK_COMM_NUM_BUFFERS 1
+#define MAVLINK_COMM_NUM_BUFFERS MAX_MAVLINK_PORTS
#include "common/mavlink.h"
#pragma GCC diagnostic pop
diff --git a/src/main/telemetry/mavlink.c b/src/main/telemetry/mavlink.c
index d7713ac6833..74665525ec0 100644
--- a/src/main/telemetry/mavlink.c
+++ b/src/main/telemetry/mavlink.c
@@ -58,6 +58,7 @@
#include "flight/mixer_profile.h"
#include "flight/pid.h"
#include "flight/servos.h"
+#include "flight/wind_estimator.h"
#include "io/adsb.h"
#include "io/gps.h"
@@ -91,17 +92,22 @@
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wunused-function"
-#define MAVLINK_COMM_NUM_BUFFERS 1
+#ifndef MAVLINK_COMM_NUM_BUFFERS
+#define MAVLINK_COMM_NUM_BUFFERS MAX_MAVLINK_PORTS
+#endif
#include "common/mavlink.h"
#pragma GCC diagnostic pop
#define TELEMETRY_MAVLINK_PORT_MODE MODE_RXTX
#define TELEMETRY_MAVLINK_MAXRATE 50
#define TELEMETRY_MAVLINK_DELAY ((1000 * 1000) / TELEMETRY_MAVLINK_MAXRATE)
+#define TELEMETRY_MAVLINK_HIGH_LATENCY_INTERVAL_US (5 * 1000 * 1000)
#define MAV_DATA_STREAM_EXTENDED_SYS_STATE (MAV_DATA_STREAM_EXTRA3 + 1)
#define ARDUPILOT_VERSION_MAJOR 4
#define ARDUPILOT_VERSION_MINOR 6
#define ARDUPILOT_VERSION_PATCH 3
+#define MAVLINK_MAX_ROUTES 32
+#define MAVLINK_PORT_MASK(portIndex) (1U << (portIndex))
typedef enum {
MAV_FRAME_SUPPORTED_NONE = 0,
@@ -181,16 +187,14 @@ typedef enum APM_COPTER_MODE
COPTER_MODE_ENUM_END=29,
} APM_COPTER_MODE;
-static serialPort_t *mavlinkPort = NULL;
-static serialPortConfig_t *portConfig;
-
-static bool mavlinkTelemetryEnabled = false;
-static portSharing_e mavlinkPortSharing;
-static uint8_t txbuff_free = 100;
-static bool txbuff_valid = false;
+typedef struct mavlinkRouteEntry_s {
+ uint8_t sysid;
+ uint8_t compid;
+ uint8_t ingressPortIndex;
+} mavlinkRouteEntry_t;
/* MAVLink datastream rates in Hz */
-static uint8_t mavRates[] = {
+static const uint8_t mavDefaultRates[] = {
[MAV_DATA_STREAM_EXTENDED_STATUS] = 2, // 2Hz
[MAV_DATA_STREAM_RC_CHANNELS] = 1, // 1Hz
[MAV_DATA_STREAM_POSITION] = 2, // 2Hz
@@ -200,16 +204,36 @@ static uint8_t mavRates[] = {
[MAV_DATA_STREAM_EXTENDED_SYS_STATE] = 1 // 1Hz
};
-#define MAXSTREAMS (sizeof(mavRates) / sizeof(mavRates[0]))
-
-static timeUs_t lastMavlinkMessage = 0;
-static uint8_t mavRatesConfigured[MAXSTREAMS];
-static uint8_t mavTicks[MAXSTREAMS];
+typedef struct mavlinkPortRuntime_s {
+ serialPort_t *port;
+ const serialPortConfig_t *portConfig;
+ portSharing_e portSharing;
+ bool telemetryEnabled;
+ bool txbuffValid;
+ uint8_t txbuffFree;
+ timeUs_t lastMavlinkMessageUs;
+ timeUs_t lastHighLatencyMessageUs;
+ bool highLatencyEnabled;
+ uint8_t mavRates[ARRAYLEN(mavDefaultRates)];
+ uint8_t mavRatesConfigured[ARRAYLEN(mavDefaultRates)];
+ uint8_t mavTicks[ARRAYLEN(mavDefaultRates)];
+ mavlink_message_t mavRecvMsg;
+ mavlink_status_t mavRecvStatus;
+} mavlinkPortRuntime_t;
+
+#define MAXSTREAMS (ARRAYLEN(mavDefaultRates))
+
+static mavlinkPortRuntime_t mavPortStates[MAX_MAVLINK_PORTS];
+static uint8_t mavPortCount = 0;
+static mavlinkRouteEntry_t mavRouteTable[MAVLINK_MAX_ROUTES];
+static uint8_t mavRouteCount = 0;
+static uint8_t mavSendMask = 0;
+static mavlinkPortRuntime_t *mavActivePort = NULL;
+static const mavlinkTelemetryPortConfig_t *mavActiveConfig = NULL;
static mavlink_message_t mavSendMsg;
static mavlink_message_t mavRecvMsg;
-static mavlink_status_t mavRecvStatus;
-// Set mavSystemId from telemetryConfig()->mavlink.sysid
+// Set active MAV identity from active port settings.
static uint8_t mavSystemId = 1;
static uint8_t mavAutopilotType;
static uint8_t mavComponentId = MAV_COMP_ID_AUTOPILOT1;
@@ -328,40 +352,73 @@ static mavlinkModeSelection_t selectMavlinkMode(bool isPlane)
return modeSelection;
}
+static const mavlinkTelemetryPortConfig_t *mavlinkGetPortConfig(uint8_t portIndex)
+{
+ return &telemetryConfig()->mavlink[portIndex];
+}
+
+static void mavlinkApplyActivePortOutputVersion(void)
+{
+ mavlink_status_t *chanState = mavlink_get_channel_status(MAVLINK_COMM_0);
+ if (mavActiveConfig->version == 1) {
+ chanState->flags |= MAVLINK_STATUS_FLAG_OUT_MAVLINK1;
+ } else {
+ chanState->flags &= ~MAVLINK_STATUS_FLAG_OUT_MAVLINK1;
+ }
+}
+
+static void mavlinkSetActivePortContext(uint8_t portIndex)
+{
+ mavActivePort = &mavPortStates[portIndex];
+ mavActiveConfig = mavlinkGetPortConfig(portIndex);
+ mavAutopilotType = mavActiveConfig->autopilot_type;
+ mavSystemId = mavActiveConfig->sysid;
+ mavComponentId = mavActiveConfig->compid;
+ mavlinkApplyActivePortOutputVersion();
+}
+
static int mavlinkStreamTrigger(enum MAV_DATA_STREAM streamNum)
{
- uint8_t rate = (uint8_t) mavRates[streamNum];
+ if (!mavActivePort || streamNum >= MAXSTREAMS) {
+ return 0;
+ }
+
+ uint8_t rate = mavActivePort->mavRates[streamNum];
if (rate == 0) {
return 0;
}
- if (mavTicks[streamNum] == 0) {
+ if (mavActivePort->mavTicks[streamNum] == 0) {
// we're triggering now, setup the next trigger point
if (rate > TELEMETRY_MAVLINK_MAXRATE) {
rate = TELEMETRY_MAVLINK_MAXRATE;
}
- mavTicks[streamNum] = (TELEMETRY_MAVLINK_MAXRATE / rate);
+ mavActivePort->mavTicks[streamNum] = (TELEMETRY_MAVLINK_MAXRATE / rate);
return 1;
}
// count down at TASK_RATE_HZ
- mavTicks[streamNum]--;
+ mavActivePort->mavTicks[streamNum]--;
return 0;
}
static void mavlinkSetStreamRate(uint8_t streamNum, uint8_t rate)
{
- if (streamNum >= MAXSTREAMS) {
+ if (!mavActivePort || streamNum >= MAXSTREAMS) {
return;
}
- mavRates[streamNum] = rate;
- mavTicks[streamNum] = 0;
+ mavActivePort->mavRates[streamNum] = rate;
+ mavActivePort->mavTicks[streamNum] = 0;
}
static int32_t mavlinkStreamIntervalUs(uint8_t streamNum)
{
- uint8_t rate = mavRates[streamNum];
+ if (!mavActivePort || streamNum >= MAXSTREAMS) {
+ return -1;
+ }
+
+ uint8_t rate = mavActivePort->mavRates[streamNum];
if (rate == 0) {
return -1;
}
@@ -369,91 +426,153 @@ static int32_t mavlinkStreamIntervalUs(uint8_t streamNum)
return 1000000 / rate;
}
+static void configureMAVLinkStreamRates(uint8_t portIndex)
+{
+ mavlinkSetActivePortContext(portIndex);
+ mavlinkSetStreamRate(MAV_DATA_STREAM_EXTENDED_STATUS, mavActiveConfig->extended_status_rate);
+ mavlinkSetStreamRate(MAV_DATA_STREAM_RC_CHANNELS, mavActiveConfig->rc_channels_rate);
+ mavlinkSetStreamRate(MAV_DATA_STREAM_POSITION, mavActiveConfig->position_rate);
+ mavlinkSetStreamRate(MAV_DATA_STREAM_EXTRA1, mavActiveConfig->extra1_rate);
+ mavlinkSetStreamRate(MAV_DATA_STREAM_EXTRA2, mavActiveConfig->extra2_rate);
+ mavlinkSetStreamRate(MAV_DATA_STREAM_EXTRA3, mavActiveConfig->extra3_rate);
+ mavlinkSetStreamRate(MAV_DATA_STREAM_EXTENDED_SYS_STATE, mavActiveConfig->extra3_rate);
+ memcpy(mavActivePort->mavRatesConfigured, mavActivePort->mavRates, sizeof(mavActivePort->mavRatesConfigured));
+}
+
+static void freeMAVLinkTelemetryPortByIndex(uint8_t portIndex)
+{
+ mavlinkPortRuntime_t *state = &mavPortStates[portIndex];
+
+ if (state->port) {
+ closeSerialPort(state->port);
+ }
+
+ state->port = NULL;
+ state->telemetryEnabled = false;
+ state->txbuffValid = false;
+ state->txbuffFree = 100;
+ state->lastMavlinkMessageUs = 0;
+ state->lastHighLatencyMessageUs = 0;
+ state->highLatencyEnabled = mavlinkGetPortConfig(portIndex)->high_latency;
+ memset(&state->mavRecvStatus, 0, sizeof(state->mavRecvStatus));
+ memset(&state->mavRecvMsg, 0, sizeof(state->mavRecvMsg));
+}
+
void freeMAVLinkTelemetryPort(void)
{
- closeSerialPort(mavlinkPort);
- mavlinkPort = NULL;
- mavlinkTelemetryEnabled = false;
+ for (uint8_t portIndex = 0; portIndex < mavPortCount; portIndex++) {
+ freeMAVLinkTelemetryPortByIndex(portIndex);
+ }
+
+ mavSendMask = 0;
+ mavRouteCount = 0;
}
void initMAVLinkTelemetry(void)
{
- portConfig = findSerialPortConfig(FUNCTION_TELEMETRY_MAVLINK);
- mavlinkPortSharing = determinePortSharing(portConfig, FUNCTION_TELEMETRY_MAVLINK);
- memcpy(mavRatesConfigured, mavRates, sizeof(mavRatesConfigured));
+ memset(mavPortStates, 0, sizeof(mavPortStates));
+ memset(mavRouteTable, 0, sizeof(mavRouteTable));
+ mavPortCount = 0;
+ mavRouteCount = 0;
+ mavSendMask = 0;
+
+ const serialPortConfig_t *serialPortConfig = findSerialPortConfig(FUNCTION_TELEMETRY_MAVLINK);
+ while (serialPortConfig && mavPortCount < MAX_MAVLINK_PORTS) {
+ mavlinkPortRuntime_t *state = &mavPortStates[mavPortCount];
+ state->portConfig = serialPortConfig;
+ state->portSharing = determinePortSharing(serialPortConfig, FUNCTION_TELEMETRY_MAVLINK);
+ state->txbuffFree = 100;
+ state->highLatencyEnabled = mavlinkGetPortConfig(mavPortCount)->high_latency;
+ configureMAVLinkStreamRates(mavPortCount);
+
+ mavPortCount++;
+ serialPortConfig = findNextSerialPortConfig(FUNCTION_TELEMETRY_MAVLINK);
+ }
+
+ mavActivePort = NULL;
+ mavActiveConfig = NULL;
}
-void configureMAVLinkTelemetryPort(void)
+static void configureMAVLinkTelemetryPort(uint8_t portIndex)
{
- if (!portConfig) {
+ mavlinkPortRuntime_t *state = &mavPortStates[portIndex];
+
+ if (!state->portConfig) {
return;
}
- baudRate_e baudRateIndex = portConfig->telemetry_baudrateIndex;
+ baudRate_e baudRateIndex = state->portConfig->telemetry_baudrateIndex;
if (baudRateIndex == BAUD_AUTO) {
// default rate for minimOSD
baudRateIndex = BAUD_57600;
}
- mavlinkPort = openSerialPort(portConfig->identifier, FUNCTION_TELEMETRY_MAVLINK, NULL, NULL, baudRates[baudRateIndex], TELEMETRY_MAVLINK_PORT_MODE, SERIAL_NOT_INVERTED);
- mavAutopilotType = telemetryConfig()->mavlink.autopilot_type;
- mavSystemId = telemetryConfig()->mavlink.sysid;
-
- if (!mavlinkPort) {
+ state->port = openSerialPort(state->portConfig->identifier, FUNCTION_TELEMETRY_MAVLINK, NULL, NULL, baudRates[baudRateIndex], TELEMETRY_MAVLINK_PORT_MODE, SERIAL_NOT_INVERTED);
+ if (!state->port) {
return;
}
- mavlinkTelemetryEnabled = true;
-}
-
-static void configureMAVLinkStreamRates(void)
-{
- mavlinkSetStreamRate(MAV_DATA_STREAM_EXTENDED_STATUS, telemetryConfig()->mavlink.extended_status_rate);
- mavlinkSetStreamRate(MAV_DATA_STREAM_RC_CHANNELS, telemetryConfig()->mavlink.rc_channels_rate);
- mavlinkSetStreamRate(MAV_DATA_STREAM_POSITION, telemetryConfig()->mavlink.position_rate);
- mavlinkSetStreamRate(MAV_DATA_STREAM_EXTRA1, telemetryConfig()->mavlink.extra1_rate);
- mavlinkSetStreamRate(MAV_DATA_STREAM_EXTRA2, telemetryConfig()->mavlink.extra2_rate);
- mavlinkSetStreamRate(MAV_DATA_STREAM_EXTRA3, telemetryConfig()->mavlink.extra3_rate);
- mavlinkSetStreamRate(MAV_DATA_STREAM_EXTENDED_SYS_STATE, telemetryConfig()->mavlink.extra3_rate);
- memcpy(mavRatesConfigured, mavRates, sizeof(mavRates));
+ state->telemetryEnabled = true;
+ state->txbuffValid = false;
+ state->txbuffFree = 100;
+ state->lastMavlinkMessageUs = 0;
+ state->lastHighLatencyMessageUs = 0;
+ state->highLatencyEnabled = mavlinkGetPortConfig(portIndex)->high_latency;
+ memset(&state->mavRecvStatus, 0, sizeof(state->mavRecvStatus));
+ memset(&state->mavRecvMsg, 0, sizeof(state->mavRecvMsg));
}
void checkMAVLinkTelemetryState(void)
{
- bool newTelemetryEnabledValue = telemetryDetermineEnabledState(mavlinkPortSharing);
+ for (uint8_t portIndex = 0; portIndex < mavPortCount; portIndex++) {
+ mavlinkPortRuntime_t *state = &mavPortStates[portIndex];
+
+ bool newTelemetryEnabledValue = telemetryDetermineEnabledState(state->portSharing);
+ if ((state->portConfig->functionMask & FUNCTION_RX_SERIAL) &&
+ rxConfig()->receiverType == RX_TYPE_SERIAL &&
+ rxConfig()->serialrx_provider == SERIALRX_MAVLINK) {
+ newTelemetryEnabledValue = true;
+ }
- if (newTelemetryEnabledValue == mavlinkTelemetryEnabled) {
- return;
- }
+ if (newTelemetryEnabledValue == state->telemetryEnabled) {
+ continue;
+ }
- if (newTelemetryEnabledValue) {
- configureMAVLinkTelemetryPort();
- configureMAVLinkStreamRates();
- } else
- freeMAVLinkTelemetryPort();
+ if (newTelemetryEnabledValue) {
+ configureMAVLinkTelemetryPort(portIndex);
+ if (state->telemetryEnabled) {
+ configureMAVLinkStreamRates(portIndex);
+ }
+ } else {
+ freeMAVLinkTelemetryPortByIndex(portIndex);
+ }
+ }
}
static void mavlinkSendMessage(void)
{
uint8_t mavBuffer[MAVLINK_MAX_PACKET_LEN];
+ int msgLength = mavlink_msg_to_send_buffer(mavBuffer, &mavSendMsg);
- mavlink_status_t* chan_state = mavlink_get_channel_status(MAVLINK_COMM_0);
- if (telemetryConfig()->mavlink.version == 1) {
- chan_state->flags |= MAVLINK_STATUS_FLAG_OUT_MAVLINK1;
- } else {
- chan_state->flags &= ~MAVLINK_STATUS_FLAG_OUT_MAVLINK1;
- }
+ for (uint8_t portIndex = 0; portIndex < mavPortCount; portIndex++) {
+ if ((mavSendMask & MAVLINK_PORT_MASK(portIndex)) == 0) {
+ continue;
+ }
- int msgLength = mavlink_msg_to_send_buffer(mavBuffer, &mavSendMsg);
+ mavlinkPortRuntime_t *state = &mavPortStates[portIndex];
+ if (!state->telemetryEnabled || !state->port) {
+ continue;
+ }
- for (int i = 0; i < msgLength; i++) {
- serialWrite(mavlinkPort, mavBuffer[i]);
+ for (int i = 0; i < msgLength; i++) {
+ serialWrite(state->port, mavBuffer[i]);
+ }
}
}
static void mavlinkSendAutopilotVersion(void)
{
- if (telemetryConfig()->mavlink.version == 1) return;
+ if (mavActiveConfig->version == 1) return;
// Capabilities aligned with what we actually support.
uint64_t capabilities = 0;
@@ -486,11 +605,11 @@ static void mavlinkSendAutopilotVersion(void)
static void mavlinkSendProtocolVersion(void)
{
- if (telemetryConfig()->mavlink.version == 1) return;
+ if (mavActiveConfig->version == 1) return;
uint8_t specHash[8] = {0};
uint8_t libHash[8] = {0};
- const uint16_t protocolVersion = (uint16_t)telemetryConfig()->mavlink.version * 100;
+ const uint16_t protocolVersion = (uint16_t)mavActiveConfig->version * 100;
mavlink_msg_protocol_version_pack(
mavSystemId,
@@ -903,7 +1022,7 @@ void mavlinkSendSystemStatus(void)
void mavlinkSendRCChannelsAndRSSI(void)
{
#define GET_CHANNEL_VALUE(x) ((rxRuntimeConfig.channelCount >= (x + 1)) ? rxGetChannelValue(x) : 0)
- if (telemetryConfig()->mavlink.version == 1) {
+ if (mavActiveConfig->version == 1) {
mavlink_msg_rc_channels_raw_pack(mavSystemId, mavComponentId, &mavSendMsg,
// time_boot_ms Timestamp (milliseconds since system boot)
millis(),
@@ -1329,8 +1448,200 @@ void mavlinkSendBatteryTemperatureStatusText(void)
}
+static uint8_t mavlinkGetAutopilotEnum(void)
+{
+ if (mavAutopilotType == MAVLINK_AUTOPILOT_ARDUPILOT) {
+ return MAV_AUTOPILOT_ARDUPILOTMEGA;
+ }
+
+ return MAV_AUTOPILOT_GENERIC;
+}
+
+static uint8_t mavlinkHeadingDeg2FromCd(int32_t headingCd)
+{
+ return (uint8_t)(wrap_36000(headingCd) / 200);
+}
+
+static uint16_t mavlinkComputeHighLatencyFailures(void)
+{
+ uint16_t flags = 0;
+
+#if defined(USE_GPS)
+ if (!(sensors(SENSOR_GPS)
+#ifdef USE_GPS_FIX_ESTIMATION
+ || STATE(GPS_ESTIMATED_FIX)
+#endif
+ ) || gpsSol.fixType == GPS_NO_FIX) {
+ flags |= HL_FAILURE_FLAG_GPS;
+ }
+#endif
+
+#ifdef USE_PITOT
+ if (getHwPitotmeterStatus() != HW_SENSOR_OK) {
+ flags |= HL_FAILURE_FLAG_DIFFERENTIAL_PRESSURE;
+ }
+#endif
+
+ if (getHwBarometerStatus() != HW_SENSOR_OK) {
+ flags |= HL_FAILURE_FLAG_ABSOLUTE_PRESSURE;
+ }
+
+ if (getHwAccelerometerStatus() != HW_SENSOR_OK) {
+ flags |= HL_FAILURE_FLAG_3D_ACCEL;
+ }
+
+ if (getHwGyroStatus() != HW_SENSOR_OK) {
+ flags |= HL_FAILURE_FLAG_3D_GYRO;
+ }
+
+ if (getHwCompassStatus() != HW_SENSOR_OK) {
+ flags |= HL_FAILURE_FLAG_3D_MAG;
+ }
+
+ if (getHwRangefinderStatus() != HW_SENSOR_OK) {
+ flags |= HL_FAILURE_FLAG_TERRAIN;
+ }
+
+ const batteryState_e batteryState = getBatteryState();
+ if (batteryState == BATTERY_WARNING || batteryState == BATTERY_CRITICAL) {
+ flags |= HL_FAILURE_FLAG_BATTERY;
+ }
+
+ if (!rxIsReceivingSignal() || !rxAreFlightChannelsValid()) {
+ flags |= HL_FAILURE_FLAG_RC_RECEIVER;
+ }
+
+ return flags;
+}
+
+static void mavlinkSendHighLatency2(timeUs_t currentTimeUs)
+{
+ const bool isPlane = (STATE(FIXED_WING_LEGACY) || mixerConfig()->platformType == PLATFORM_AIRPLANE);
+ const mavlinkModeSelection_t modeSelection = selectMavlinkMode(isPlane);
+
+ int32_t latitude = 0;
+ int32_t longitude = 0;
+ int16_t altitude = (int16_t)constrain((int32_t)(getEstimatedActualPosition(Z) / 100), INT16_MIN, INT16_MAX);
+ int16_t targetAltitude = (int16_t)constrain((int32_t)(posControl.desiredState.pos.z / 100), INT16_MIN, INT16_MAX);
+ uint16_t targetDistance = 0;
+ uint16_t wpNum = 0;
+ uint8_t heading = mavlinkHeadingDeg2FromCd(DECIDEGREES_TO_CENTIDEGREES(attitude.values.yaw));
+ uint8_t targetHeading = mavlinkHeadingDeg2FromCd(posControl.desiredState.yaw);
+ uint8_t groundspeed = 0;
+ uint8_t airspeed = 0;
+ uint8_t airspeedSp = 0;
+ uint8_t windspeed = 0;
+ uint8_t windHeading = 0;
+ uint8_t eph = UINT8_MAX;
+ uint8_t epv = UINT8_MAX;
+ int8_t temperatureAir = 0;
+ int8_t climbRate = (int8_t)constrain(lrintf(getEstimatedActualVelocity(Z) / 10.0f), INT8_MIN, INT8_MAX);
+ int8_t battery = feature(FEATURE_VBAT) ? (int8_t)calculateBatteryPercentage() : -1;
+
+#if defined(USE_GPS)
+ if (sensors(SENSOR_GPS)
+#ifdef USE_GPS_FIX_ESTIMATION
+ || STATE(GPS_ESTIMATED_FIX)
+#endif
+ ) {
+ latitude = gpsSol.llh.lat;
+ longitude = gpsSol.llh.lon;
+ altitude = (int16_t)constrain((int32_t)(gpsSol.llh.alt / 100), INT16_MIN, INT16_MAX);
+
+ const int32_t desiredAltCm = lrintf(posControl.desiredState.pos.z);
+ const int32_t targetAltCm = GPS_home.alt + desiredAltCm;
+ targetAltitude = (int16_t)constrain(targetAltCm / 100, INT16_MIN, INT16_MAX);
+
+ groundspeed = (uint8_t)constrain(lrintf(gpsSol.groundSpeed / 20.0f), 0, UINT8_MAX);
+
+ if (gpsSol.flags.validEPE) {
+ eph = (uint8_t)constrain((gpsSol.eph + 5) / 10, 0, UINT8_MAX);
+ epv = (uint8_t)constrain((gpsSol.epv + 5) / 10, 0, UINT8_MAX);
+ }
+
+ if (posControl.activeWaypointIndex >= 0) {
+ wpNum = (uint16_t)posControl.activeWaypointIndex;
+ targetDistance = (uint16_t)constrain(lrintf(posControl.wpDistance / 1000.0f), 0, UINT16_MAX);
+ }
+ }
+#endif
+
+#if defined(USE_PITOT)
+ if (sensors(SENSOR_PITOT) && pitotIsHealthy()) {
+ airspeed = (uint8_t)constrain(lrintf(getAirspeedEstimate() / 20.0f), 0, UINT8_MAX);
+ airspeedSp = airspeed;
+ }
+#endif
+
+ if (airspeedSp == 0) {
+ const float desiredVelXY = calc_length_pythagorean_2D(posControl.desiredState.vel.x, posControl.desiredState.vel.y);
+ airspeedSp = (uint8_t)constrain(lrintf(desiredVelXY / 20.0f), 0, UINT8_MAX);
+ }
+
+ if (airspeed == 0) {
+ airspeed = groundspeed;
+ }
+
+#ifdef USE_WIND_ESTIMATOR
+ if (isEstimatedWindSpeedValid()) {
+ uint16_t windAngleCd = 0;
+ const float windHoriz = getEstimatedHorizontalWindSpeed(&windAngleCd);
+ windspeed = (uint8_t)constrain(lrintf(windHoriz / 20.0f), 0, UINT8_MAX);
+ windHeading = mavlinkHeadingDeg2FromCd(windAngleCd);
+ }
+#endif
+
+ int16_t temperature;
+ sensors(SENSOR_BARO) ? getBaroTemperature(&temperature) : getIMUTemperature(&temperature);
+ temperatureAir = (int8_t)constrain(temperature, INT8_MIN, INT8_MAX);
+
+ const uint16_t failureFlags = mavlinkComputeHighLatencyFailures();
+
+ mavlink_msg_high_latency2_pack(
+ mavSystemId,
+ mavComponentId,
+ &mavSendMsg,
+ (uint32_t)(currentTimeUs / 1000),
+ mavlinkGetVehicleType(),
+ mavlinkGetAutopilotEnum(),
+ modeSelection.customMode,
+ latitude,
+ longitude,
+ altitude,
+ targetAltitude,
+ heading,
+ targetHeading,
+ targetDistance,
+ (uint8_t)constrain(getThrottlePercent(osdUsingScaledThrottle()), 0, 100),
+ airspeed,
+ airspeedSp,
+ groundspeed,
+ windspeed,
+ windHeading,
+ eph,
+ epv,
+ temperatureAir,
+ climbRate,
+ battery,
+ wpNum,
+ failureFlags,
+ 0,
+ 0,
+ 0);
+
+ mavlinkSendMessage();
+}
+
void processMAVLinkTelemetry(timeUs_t currentTimeUs)
{
+ if (mavActivePort->highLatencyEnabled && mavActiveConfig->version != 1) {
+ if ((currentTimeUs - mavActivePort->lastHighLatencyMessageUs) >= TELEMETRY_MAVLINK_HIGH_LATENCY_INTERVAL_US) {
+ mavlinkSendHighLatency2(currentTimeUs);
+ mavActivePort->lastHighLatencyMessageUs = currentTimeUs;
+ }
+ return;
+ }
+
// is executed @ TELEMETRY_MAVLINK_MAXRATE rate
if (mavlinkStreamTrigger(MAV_DATA_STREAM_EXTENDED_STATUS)) {
mavlinkSendSystemStatus();
@@ -1897,7 +2208,7 @@ static bool handleIncoming_COMMAND(uint8_t targetSystem, uint8_t ackTargetSystem
if (mavlinkMessageToStream((uint16_t)param1, &stream)) {
if (param2 == 0.0f) {
- mavlinkSetStreamRate(stream, mavRatesConfigured[stream]);
+ mavlinkSetStreamRate(stream, mavActivePort->mavRatesConfigured[stream]);
result = MAV_RESULT_ACCEPTED;
} else if (param2 < 0.0f) {
mavlinkSetStreamRate(stream, 0);
@@ -1939,8 +2250,24 @@ static bool handleIncoming_COMMAND(uint8_t targetSystem, uint8_t ackTargetSystem
mavlinkSendCommandAck(command, MAV_RESULT_ACCEPTED, ackTargetSystem, ackTargetComponent);
return true;
}
+ case MAV_CMD_CONTROL_HIGH_LATENCY:
+ if (param1 == 0.0f || param1 == 1.0f) {
+ if (mavActiveConfig->version == 1 && param1 > 0.5f) {
+ mavlinkSendCommandAck(command, MAV_RESULT_UNSUPPORTED, ackTargetSystem, ackTargetComponent);
+ return true;
+ }
+
+ mavActivePort->highLatencyEnabled = param1 > 0.5f;
+ if (mavActivePort->highLatencyEnabled) {
+ mavActivePort->lastHighLatencyMessageUs = 0;
+ }
+ mavlinkSendCommandAck(command, MAV_RESULT_ACCEPTED, ackTargetSystem, ackTargetComponent);
+ } else {
+ mavlinkSendCommandAck(command, MAV_RESULT_FAILED, ackTargetSystem, ackTargetComponent);
+ }
+ return true;
case MAV_CMD_REQUEST_PROTOCOL_VERSION:
- if (telemetryConfig()->mavlink.version == 1) {
+ if (mavActiveConfig->version == 1) {
mavlinkSendCommandAck(command, MAV_RESULT_UNSUPPORTED, ackTargetSystem, ackTargetComponent);
} else {
mavlinkSendProtocolVersion();
@@ -1948,7 +2275,7 @@ static bool handleIncoming_COMMAND(uint8_t targetSystem, uint8_t ackTargetSystem
}
return true;
case MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES:
- if (telemetryConfig()->mavlink.version == 1) {
+ if (mavActiveConfig->version == 1) {
mavlinkSendCommandAck(command, MAV_RESULT_UNSUPPORTED, ackTargetSystem, ackTargetComponent);
} else {
mavlinkSendAutopilotVersion();
@@ -1966,13 +2293,13 @@ static bool handleIncoming_COMMAND(uint8_t targetSystem, uint8_t ackTargetSystem
sent = true;
break;
case MAVLINK_MSG_ID_AUTOPILOT_VERSION:
- if (telemetryConfig()->mavlink.version != 1) {
+ if (mavActiveConfig->version != 1) {
mavlinkSendAutopilotVersion();
sent = true;
}
break;
case MAVLINK_MSG_ID_PROTOCOL_VERSION:
- if (telemetryConfig()->mavlink.version != 1) {
+ if (mavActiveConfig->version != 1) {
mavlinkSendProtocolVersion();
sent = true;
}
@@ -2283,7 +2610,7 @@ static bool handleIncoming_PARAM_REQUEST_LIST(void) {
}
static void mavlinkParseRxStats(const mavlink_radio_status_t *msg) {
- switch(telemetryConfig()->mavlink.radio_type) {
+ switch(mavActiveConfig->radio_type) {
case MAVLINK_RADIO_SIK:
// rssi scaling info from: https://ardupilot.org/rover/docs/common-3dr-radio-advanced-configuration-and-technical-information.html
rxLinkStatistics.uplinkRSSI = (msg->rssi / 1.9) - 127;
@@ -2307,8 +2634,13 @@ static void mavlinkParseRxStats(const mavlink_radio_status_t *msg) {
static bool handleIncoming_RADIO_STATUS(void) {
mavlink_radio_status_t msg;
mavlink_msg_radio_status_decode(&mavRecvMsg, &msg);
- txbuff_valid = true;
- txbuff_free = msg.txbuf;
+ if (msg.txbuf > 0) {
+ mavActivePort->txbuffValid = true;
+ mavActivePort->txbuffFree = msg.txbuf;
+ } else {
+ mavActivePort->txbuffValid = false;
+ mavActivePort->txbuffFree = 100;
+ }
if (rxConfig()->receiverType == RX_TYPE_SERIAL &&
rxConfig()->serialrx_provider == SERIALRX_MAVLINK) {
@@ -2360,14 +2692,164 @@ static bool handleIncoming_ADSB_VEHICLE(void) {
}
#endif
+static bool mavlinkIsFromLocalIdentity(uint8_t sysid, uint8_t compid)
+{
+ for (uint8_t portIndex = 0; portIndex < mavPortCount; portIndex++) {
+ const mavlinkTelemetryPortConfig_t *cfg = mavlinkGetPortConfig(portIndex);
+ if (cfg->sysid == sysid && cfg->compid == compid) {
+ return true;
+ }
+ }
+
+ return false;
+}
+
+static void mavlinkLearnRoute(uint8_t ingressPortIndex)
+{
+ if (mavRecvMsg.sysid == 0 || mavlinkIsFromLocalIdentity(mavRecvMsg.sysid, mavRecvMsg.compid)) {
+ return;
+ }
+
+ for (uint8_t routeIndex = 0; routeIndex < mavRouteCount; routeIndex++) {
+ mavlinkRouteEntry_t *route = &mavRouteTable[routeIndex];
+ if (route->sysid == mavRecvMsg.sysid && route->compid == mavRecvMsg.compid) {
+ route->ingressPortIndex = ingressPortIndex;
+ return;
+ }
+ }
+
+ if (mavRouteCount >= MAVLINK_MAX_ROUTES) {
+ return;
+ }
+
+ mavRouteTable[mavRouteCount].sysid = mavRecvMsg.sysid;
+ mavRouteTable[mavRouteCount].compid = mavRecvMsg.compid;
+ mavRouteTable[mavRouteCount].ingressPortIndex = ingressPortIndex;
+ mavRouteCount++;
+}
+
+static void mavlinkExtractTargets(const mavlink_message_t *msg, int16_t *targetSystem, int16_t *targetComponent)
+{
+ *targetSystem = -1;
+ *targetComponent = -1;
+
+ const mavlink_msg_entry_t *msgEntry = mavlink_get_msg_entry(msg->msgid);
+ if (!msgEntry) {
+ return;
+ }
+
+ if (msgEntry->flags & MAV_MSG_ENTRY_FLAG_HAVE_TARGET_SYSTEM) {
+ *targetSystem = _MAV_RETURN_uint8_t(msg, msgEntry->target_system_ofs);
+ }
+
+ if (msgEntry->flags & MAV_MSG_ENTRY_FLAG_HAVE_TARGET_COMPONENT) {
+ *targetComponent = _MAV_RETURN_uint8_t(msg, msgEntry->target_component_ofs);
+ }
+}
+
+static bool mavlinkRouteMatchesTargetOnPort(uint8_t portIndex, int16_t targetSystem, int16_t targetComponent)
+{
+ for (uint8_t routeIndex = 0; routeIndex < mavRouteCount; routeIndex++) {
+ const mavlinkRouteEntry_t *route = &mavRouteTable[routeIndex];
+ if (route->ingressPortIndex != portIndex || route->sysid != targetSystem) {
+ continue;
+ }
+
+ if (targetComponent <= 0 || route->compid == targetComponent) {
+ return true;
+ }
+ }
+
+ return false;
+}
+
+static void mavlinkForwardMessage(uint8_t ingressPortIndex, int16_t targetSystem, int16_t targetComponent)
+{
+ if (mavRecvMsg.msgid == MAVLINK_MSG_ID_RADIO_STATUS) {
+ return;
+ }
+
+ uint8_t mavBuffer[MAVLINK_MAX_PACKET_LEN];
+ const int msgLength = mavlink_msg_to_send_buffer(mavBuffer, &mavRecvMsg);
+
+ for (uint8_t portIndex = 0; portIndex < mavPortCount; portIndex++) {
+ if (portIndex == ingressPortIndex) {
+ continue;
+ }
+
+ const mavlinkPortRuntime_t *state = &mavPortStates[portIndex];
+ if (!state->telemetryEnabled || !state->port) {
+ continue;
+ }
+
+ bool shouldForward = false;
+ if (targetSystem <= 0) {
+ shouldForward = true;
+ } else if (mavlinkRouteMatchesTargetOnPort(portIndex, targetSystem, targetComponent)) {
+ shouldForward = true;
+ }
+
+ if (!shouldForward) {
+ continue;
+ }
+
+ for (int i = 0; i < msgLength; i++) {
+ serialWrite(state->port, mavBuffer[i]);
+ }
+ }
+}
+
+static int8_t mavlinkResolveLocalPortForTarget(int16_t targetSystem, int16_t targetComponent, uint8_t ingressPortIndex)
+{
+ if (targetSystem <= 0) {
+ return ingressPortIndex;
+ }
+
+ for (uint8_t portIndex = 0; portIndex < mavPortCount; portIndex++) {
+ const mavlinkTelemetryPortConfig_t *cfg = mavlinkGetPortConfig(portIndex);
+ if (cfg->sysid != targetSystem) {
+ continue;
+ }
+
+ if (targetComponent <= 0 || cfg->compid == targetComponent) {
+ return portIndex;
+ }
+ }
+
+ return -1;
+}
+
// Returns whether a message was processed
-static bool processMAVLinkIncomingTelemetry(void)
+static bool processMAVLinkIncomingTelemetry(uint8_t ingressPortIndex)
{
- while (serialRxBytesWaiting(mavlinkPort) > 0) {
+ mavlinkPortRuntime_t *state = &mavPortStates[ingressPortIndex];
+
+ while (serialRxBytesWaiting(state->port) > 0) {
// Limit handling to one message per cycle
- char c = serialRead(mavlinkPort);
- uint8_t result = mavlink_parse_char(0, c, &mavRecvMsg, &mavRecvStatus);
+ const char c = serialRead(state->port);
+ const uint8_t result = mavlink_parse_char(ingressPortIndex, c, &state->mavRecvMsg, &state->mavRecvStatus);
if (result == MAVLINK_FRAMING_OK) {
+ mavRecvMsg = state->mavRecvMsg;
+
+ if (mavlinkIsFromLocalIdentity(mavRecvMsg.sysid, mavRecvMsg.compid)) {
+ return false;
+ }
+
+ mavlinkLearnRoute(ingressPortIndex);
+
+ int16_t targetSystem;
+ int16_t targetComponent;
+ mavlinkExtractTargets(&mavRecvMsg, &targetSystem, &targetComponent);
+ mavlinkForwardMessage(ingressPortIndex, targetSystem, targetComponent);
+
+ const int8_t localPortIndex = mavlinkResolveLocalPortForTarget(targetSystem, targetComponent, ingressPortIndex);
+ if (localPortIndex < 0) {
+ return false;
+ }
+
+ mavlinkSetActivePortContext((uint8_t)localPortIndex);
+ mavSendMask = MAVLINK_PORT_MASK(ingressPortIndex);
+
switch (mavRecvMsg.msgid) {
case MAVLINK_MSG_ID_HEARTBEAT:
return handleIncoming_HEARTBEAT();
@@ -2424,32 +2906,40 @@ static bool isMAVLinkTelemetryHalfDuplex(void) {
void handleMAVLinkTelemetry(timeUs_t currentTimeUs)
{
- if (!mavlinkTelemetryEnabled) {
- return;
- }
+ for (uint8_t portIndex = 0; portIndex < mavPortCount; portIndex++) {
+ mavlinkPortRuntime_t *state = &mavPortStates[portIndex];
+ if (!state->telemetryEnabled || !state->port) {
+ continue;
+ }
- if (!mavlinkPort) {
- return;
- }
+ mavlinkSetActivePortContext(portIndex);
- // Process incoming MAVLink
- bool receivedMessage = processMAVLinkIncomingTelemetry();
- bool shouldSendTelemetry = false;
+ // Process incoming MAVLink on this port and forward when needed.
+ const bool receivedMessage = processMAVLinkIncomingTelemetry(portIndex);
- // Determine whether to send telemetry back based on flow control / pacing
- if (txbuff_valid) {
- // Use flow control if available
- shouldSendTelemetry = txbuff_free >= telemetryConfig()->mavlink.min_txbuff;
- } else {
- // If not, use blind frame pacing - and back off for collision avoidance if half-duplex
- bool halfDuplexBackoff = (isMAVLinkTelemetryHalfDuplex() && receivedMessage);
- shouldSendTelemetry = ((currentTimeUs - lastMavlinkMessage) >= TELEMETRY_MAVLINK_DELAY) && !halfDuplexBackoff;
- }
+ // Restore context back to this port before periodic send decisions.
+ mavlinkSetActivePortContext(portIndex);
+ bool shouldSendTelemetry = false;
- if (shouldSendTelemetry) {
+ if (state->txbuffValid) {
+ // Use flow control if available.
+ shouldSendTelemetry = state->txbuffFree >= mavActiveConfig->min_txbuff;
+ } else {
+ // If not, use blind frame pacing and half-duplex backoff after RX activity.
+ const bool halfDuplexBackoff = isMAVLinkTelemetryHalfDuplex() && receivedMessage;
+ shouldSendTelemetry = ((currentTimeUs - state->lastMavlinkMessageUs) >= TELEMETRY_MAVLINK_DELAY) && !halfDuplexBackoff;
+ }
+
+ if (!shouldSendTelemetry) {
+ continue;
+ }
+
+ mavSendMask = MAVLINK_PORT_MASK(portIndex);
processMAVLinkTelemetry(currentTimeUs);
- lastMavlinkMessage = currentTimeUs;
+ state->lastMavlinkMessageUs = currentTimeUs;
}
+
+ mavSendMask = 0;
}
#endif
diff --git a/src/main/telemetry/mavlink.h b/src/main/telemetry/mavlink.h
index f5b51e1e3ef..899674194de 100755
--- a/src/main/telemetry/mavlink.h
+++ b/src/main/telemetry/mavlink.h
@@ -22,4 +22,3 @@ void handleMAVLinkTelemetry(timeUs_t currentTimeUs);
void checkMAVLinkTelemetryState(void);
void freeMAVLinkTelemetryPort(void);
-void configureMAVLinkTelemetryPort(void);
diff --git a/src/main/telemetry/telemetry.c b/src/main/telemetry/telemetry.c
index 2c896945843..b771fc5c86c 100644
--- a/src/main/telemetry/telemetry.c
+++ b/src/main/telemetry/telemetry.c
@@ -56,7 +56,7 @@
#include "telemetry/ghst.h"
-PG_REGISTER_WITH_RESET_TEMPLATE(telemetryConfig_t, telemetryConfig, PG_TELEMETRY_CONFIG, 8);
+PG_REGISTER_WITH_RESET_TEMPLATE(telemetryConfig_t, telemetryConfig, PG_TELEMETRY_CONFIG, 9);
PG_RESET_TEMPLATE(telemetryConfig_t, telemetryConfig,
.telemetry_switch = SETTING_TELEMETRY_SWITCH_DEFAULT,
@@ -87,17 +87,51 @@ PG_RESET_TEMPLATE(telemetryConfig_t, telemetryConfig,
#endif
.mavlink = {
- .autopilot_type = SETTING_MAVLINK_AUTOPILOT_TYPE_DEFAULT,
- .extended_status_rate = SETTING_MAVLINK_EXT_STATUS_RATE_DEFAULT,
- .rc_channels_rate = SETTING_MAVLINK_RC_CHAN_RATE_DEFAULT,
- .position_rate = SETTING_MAVLINK_POS_RATE_DEFAULT,
- .extra1_rate = SETTING_MAVLINK_EXTRA1_RATE_DEFAULT,
- .extra2_rate = SETTING_MAVLINK_EXTRA2_RATE_DEFAULT,
- .extra3_rate = SETTING_MAVLINK_EXTRA3_RATE_DEFAULT,
- .version = SETTING_MAVLINK_VERSION_DEFAULT,
- .min_txbuff = SETTING_MAVLINK_MIN_TXBUFFER_DEFAULT,
- .radio_type = SETTING_MAVLINK_RADIO_TYPE_DEFAULT,
- .sysid = SETTING_MAVLINK_SYSID_DEFAULT
+ {
+ .autopilot_type = SETTING_MAVLINK_AUTOPILOT_TYPE_DEFAULT,
+ .extended_status_rate = SETTING_MAVLINK_EXT_STATUS_RATE_DEFAULT,
+ .rc_channels_rate = SETTING_MAVLINK_RC_CHAN_RATE_DEFAULT,
+ .position_rate = SETTING_MAVLINK_POS_RATE_DEFAULT,
+ .extra1_rate = SETTING_MAVLINK_EXTRA1_RATE_DEFAULT,
+ .extra2_rate = SETTING_MAVLINK_EXTRA2_RATE_DEFAULT,
+ .extra3_rate = SETTING_MAVLINK_EXTRA3_RATE_DEFAULT,
+ .version = SETTING_MAVLINK_VERSION_DEFAULT,
+ .min_txbuff = SETTING_MAVLINK_MIN_TXBUFFER_DEFAULT,
+ .radio_type = SETTING_MAVLINK_RADIO_TYPE_DEFAULT,
+ .sysid = SETTING_MAVLINK_SYSID_DEFAULT,
+ .compid = SETTING_MAVLINK_PORT1_COMPID_DEFAULT,
+ .high_latency = SETTING_MAVLINK_PORT1_HIGH_LATENCY_DEFAULT
+ },
+ {
+ .autopilot_type = SETTING_MAVLINK_PORT2_AUTOPILOT_TYPE_DEFAULT,
+ .extended_status_rate = SETTING_MAVLINK_PORT2_EXT_STATUS_RATE_DEFAULT,
+ .rc_channels_rate = SETTING_MAVLINK_PORT2_RC_CHAN_RATE_DEFAULT,
+ .position_rate = SETTING_MAVLINK_PORT2_POS_RATE_DEFAULT,
+ .extra1_rate = SETTING_MAVLINK_PORT2_EXTRA1_RATE_DEFAULT,
+ .extra2_rate = SETTING_MAVLINK_PORT2_EXTRA2_RATE_DEFAULT,
+ .extra3_rate = SETTING_MAVLINK_PORT2_EXTRA3_RATE_DEFAULT,
+ .version = SETTING_MAVLINK_PORT2_VERSION_DEFAULT,
+ .min_txbuff = SETTING_MAVLINK_PORT2_MIN_TXBUFFER_DEFAULT,
+ .radio_type = SETTING_MAVLINK_PORT2_RADIO_TYPE_DEFAULT,
+ .sysid = SETTING_MAVLINK_PORT2_SYSID_DEFAULT,
+ .compid = SETTING_MAVLINK_PORT2_COMPID_DEFAULT,
+ .high_latency = SETTING_MAVLINK_PORT2_HIGH_LATENCY_DEFAULT
+ },
+ {
+ .autopilot_type = SETTING_MAVLINK_PORT3_AUTOPILOT_TYPE_DEFAULT,
+ .extended_status_rate = SETTING_MAVLINK_PORT3_EXT_STATUS_RATE_DEFAULT,
+ .rc_channels_rate = SETTING_MAVLINK_PORT3_RC_CHAN_RATE_DEFAULT,
+ .position_rate = SETTING_MAVLINK_PORT3_POS_RATE_DEFAULT,
+ .extra1_rate = SETTING_MAVLINK_PORT3_EXTRA1_RATE_DEFAULT,
+ .extra2_rate = SETTING_MAVLINK_PORT3_EXTRA2_RATE_DEFAULT,
+ .extra3_rate = SETTING_MAVLINK_PORT3_EXTRA3_RATE_DEFAULT,
+ .version = SETTING_MAVLINK_PORT3_VERSION_DEFAULT,
+ .min_txbuff = SETTING_MAVLINK_PORT3_MIN_TXBUFFER_DEFAULT,
+ .radio_type = SETTING_MAVLINK_PORT3_RADIO_TYPE_DEFAULT,
+ .sysid = SETTING_MAVLINK_PORT3_SYSID_DEFAULT,
+ .compid = SETTING_MAVLINK_PORT3_COMPID_DEFAULT,
+ .high_latency = SETTING_MAVLINK_PORT3_HIGH_LATENCY_DEFAULT
+ }
}
);
diff --git a/src/main/telemetry/telemetry.h b/src/main/telemetry/telemetry.h
index 7fb26781c11..bc363c930a8 100644
--- a/src/main/telemetry/telemetry.h
+++ b/src/main/telemetry/telemetry.h
@@ -30,6 +30,10 @@
#include "io/serial.h"
+#ifndef MAX_MAVLINK_PORTS
+#define MAX_MAVLINK_PORTS 3
+#endif
+
typedef enum {
LTM_RATE_NORMAL,
LTM_RATE_MEDIUM,
@@ -53,6 +57,22 @@ typedef enum {
SMARTPORT_FUEL_UNIT_MWH
} smartportFuelUnit_e;
+typedef struct mavlinkTelemetryPortConfig_s {
+ uint8_t autopilot_type;
+ uint8_t extended_status_rate;
+ uint8_t rc_channels_rate;
+ uint8_t position_rate;
+ uint8_t extra1_rate;
+ uint8_t extra2_rate;
+ uint8_t extra3_rate;
+ uint8_t version;
+ uint8_t min_txbuff;
+ uint8_t radio_type;
+ uint8_t sysid;
+ uint8_t compid;
+ bool high_latency;
+} mavlinkTelemetryPortConfig_t;
+
typedef struct telemetryConfig_s {
uint8_t telemetry_switch; // Use aux channel to change serial output & baudrate( MSP / Telemetry ). It disables automatic switching to Telemetry when armed.
uint8_t telemetry_inverted; // Flip the default inversion of the protocol - Same as serialrx_inverted in rx.c, but for telemetry.
@@ -76,19 +96,7 @@ typedef struct telemetryConfig_s {
uint16_t accEventThresholdLow;
uint16_t accEventThresholdNegX;
#endif
- struct {
- uint8_t autopilot_type;
- uint8_t extended_status_rate;
- uint8_t rc_channels_rate;
- uint8_t position_rate;
- uint8_t extra1_rate;
- uint8_t extra2_rate;
- uint8_t extra3_rate;
- uint8_t version;
- uint8_t min_txbuff;
- uint8_t radio_type;
- uint8_t sysid;
- } mavlink;
+ mavlinkTelemetryPortConfig_t mavlink[MAX_MAVLINK_PORTS];
} telemetryConfig_t;
PG_DECLARE(telemetryConfig_t, telemetryConfig);
From 4436964f110549822b6abed3b966a3236d5ce150 Mon Sep 17 00:00:00 2001
From: frogmane <7685285+xznhj8129@users.noreply.github.com>
Date: Thu, 26 Feb 2026 23:15:43 -0500
Subject: [PATCH 25/46] small refactor + settings + common.h max mav ports
define
---
docs/Mavlink.md | 19 ++-
docs/Settings.md | 160 ++++++++++++++++----------
src/main/fc/settings.yaml | 144 +++++++++++++----------
src/main/io/serial.c | 2 -
src/main/rx/mavlink.h | 4 +-
src/main/target/common.h | 5 +-
src/main/telemetry/mavlink.c | 203 +++++++--------------------------
src/main/telemetry/mavlink.h | 152 ++++++++++++++++++++++++
src/main/telemetry/telemetry.c | 44 ++++---
src/main/telemetry/telemetry.h | 17 +--
10 files changed, 427 insertions(+), 323 deletions(-)
diff --git a/docs/Mavlink.md b/docs/Mavlink.md
index b29dcdf8f89..d39c1165c25 100644
--- a/docs/Mavlink.md
+++ b/docs/Mavlink.md
@@ -16,9 +16,9 @@ INAV has a partial implementation of MAVLink that is intended primarily for simp
- `mavlink_sysid` – system ID used in every outbound packet (default 1); most inbound handlers only act on packets targeted to this system ID.
- `mavlink_autopilot_type` – heartbeat autopilot ID (`GENERIC` or `ARDUPILOT`).
- `mavlink_version` – force MAVLink v1 when set to 1.
-- Stream rates (Hz): `mavlink_ext_status_rate`, `mavlink_rc_chan_rate`, `mavlink_pos_rate`, `mavlink_extra1_rate`, `mavlink_extra2_rate`, `mavlink_extra3_rate`. Each group is polled up to 50 Hz; a rate of 0 disables the group.
-- `mavlink_min_txbuffer` – minimum remote TX buffer level before sending when `RADIO_STATUS` provides flow control.
-- `mavlink_radio_type` – scales `RADIO_STATUS` RSSI/SNR for **generic**, **ELRS**, or **SiK** links.
+- Stream rates (Hz): `mavlink_port1_ext_status_rate`, `mavlink_port1_rc_chan_rate`, `mavlink_port1_pos_rate`, `mavlink_port1_extra1_rate`, `mavlink_port1_extra2_rate`, `mavlink_port1_extra3_rate`. Each group is polled up to 50 Hz; a rate of 0 disables the group.
+- `mavlink_port1_min_txbuffer` – minimum remote TX buffer level before sending when `RADIO_STATUS` provides flow control.
+- `mavlink_port1_radio_type` – scales `RADIO_STATUS` RSSI/SNR for **generic**, **ELRS**, or **SiK** links.
## Supported Outgoing Messages
@@ -46,10 +46,10 @@ Messages are organized into MAVLink datastream groups. Each group sends **one me
- `MISSION_REQUEST_LIST`, `MISSION_REQUEST`, `MISSION_REQUEST_INT`: downloads active mission items; returns `MISSION_ACK` on bad sequence.
- `MISSION_CLEAR_ALL`: clears stored mission.
- `COMMAND_LONG` / `COMMAND_INT`: command transport for supported `MAV_CMD_*` handlers.
-- `REQUEST_DATA_STREAM`: legacy stream-rate control per stream group. `MAV_DATA_STREAM_ALL` (0) applies to all INAV-scheduled groups (`EXTENDED_STATUS`, `RC_CHANNELS`, `POSITION`, `EXTRA1`, `EXTRA2`, `EXTRA3`, `EXTENDED_SYS_STATE`); `start_stop==0` stops the addressed stream(s).
-- `SET_POSITION_TARGET_GLOBAL_INT`: requires matching `target_system` and `target_component` (`0` or local component), validates frame/type-mask semantics, updates guided WP255 for XY targets, and supports altitude-only control (`X/Y ignore`, `Z set`) using the same datum logic as `MAV_CMD_DO_CHANGE_ALTITUDE`.
-- `RC_CHANNELS_OVERRIDE` passes channel values to the MAVLink serial receiver backend when targeted to the local system ID.
-- `RADIO_STATUS` updates remote TX buffer level and scales RSSI/SNR according to `mavlink_radio_type` (also feeds link stats for MAVLink RX receivers).
+- `REQUEST_DATA_STREAM`: legacy stream-rate control per stream group.
+- `SET_POSITION_TARGET_GLOBAL_INT`: writes the GCS-guided waypoint when the frame is supported.
+- `RC_CHANNELS_OVERRIDE` passes channel values to the MAVLink serial receiver backend.
+- `RADIO_STATUS` updates remote TX buffer level and scales RSSI/SNR according to `mavlink_port1_radio_type` (also feeds link stats for MAVLink RX receivers).
- `ADSB_VEHICLE` populates the internal traffic list when ADS‑B is enabled.
- `PARAM_REQUEST_LIST` elicits a stub `PARAM_VALUE` response so ground stations stop requesting parameters (INAV does not expose parameters over MAVLink).
@@ -59,7 +59,6 @@ Messages are organized into MAVLink datastream groups. Each group sends **one me
Limited implementation of the Command protocol.
- `MAV_CMD_DO_REPOSITION`: sets the Follow Me/GCS Nav waypoint when GCS NAV is valid. Accepts `MAV_FRAME_GLOBAL`, `MAV_FRAME_GLOBAL_INT`, `MAV_FRAME_GLOBAL_RELATIVE_ALT`, `MAV_FRAME_GLOBAL_RELATIVE_ALT_INT`; otherwise `UNSUPPORTED`.
-- `MAV_CMD_DO_CHANGE_ALTITUDE`: supported when barometer support is compiled (`USE_BARO`); accepts global/global-int (MSL datum) and global-relative/global-relative-int (takeoff-relative datum), then calls navigation altitude-target update.
- `MAV_CMD_SET_MESSAGE_INTERVAL` / `MAV_CMD_GET_MESSAGE_INTERVAL`: adjust or query telemetry stream output for supported message IDs (streamed messages only; intervals slower than 1 Hz are not accepted).
- `MAV_CMD_GET_HOME_POSITION`: replies with `HOME_POSITION` when home fix exists.
- `MAV_CMD_REQUEST_MESSAGE`: emits one selected message (`HEARTBEAT`, `SYS_STATUS`, `ATTITUDE`, `VFR_HUD`, `AVAILABLE_MODES`, `CURRENT_MODE`, `EXTENDED_SYS_STATE`, RC channels, GPS/global/origin, battery/pressure, and `HOME_POSITION` when available) or `UNSUPPORTED`.
@@ -105,12 +104,12 @@ Default rates (Hz) are shown; adjust with the CLI keys above.
| `POSITION` | `GPS_RAW_INT`, `GLOBAL_POSITION_INT`, `GPS_GLOBAL_ORIGIN` | 2 Hz |
| `EXTRA1` | `ATTITUDE` | 3 Hz |
| `EXTRA2` | `VFR_HUD`, `HEARTBEAT` | 2 Hz |
-| `EXT_SYS_STATE` | `EXTENDED_SYS_STATE` | 1 Hz (defaults to `mavlink_extra3_rate`) |
+| `EXT_SYS_STATE` | `EXTENDED_SYS_STATE` | 1 Hz (defaults to `mavlink_port1_extra3_rate`) |
| `EXTRA3` | `BATTERY_STATUS`, `SCALED_PRESSURE`, `STATUSTEXT` (when present) | 1 Hz |
## Operating tips
-- Set `mavlink_radio_type` to **ELRS** or **SiK** if you use those links to get accurate link quality scaling in `RADIO_STATUS`.
+- Set `mavlink_port1_radio_type` to **ELRS** or **SiK** if you use those links to get accurate link quality scaling in `RADIO_STATUS`.
- If you rely on RC override via MAVLink, ensure the serial receiver type is set to `SERIALRX_MAVLINK` and consider enabling `telemetry_halfduplex` when RX shares the port.
- To reduce bandwidth, lower the stream rates for groups you do not need, or disable them entirely by setting the rate to 0.
diff --git a/docs/Settings.md b/docs/Settings.md
index 610834d0d7f..939991a9792 100644
--- a/docs/Settings.md
+++ b/docs/Settings.md
@@ -2652,9 +2652,19 @@ Autopilot type to advertise for MAVLink telemetry
---
-### mavlink_ext_status_rate
+### mavlink_port1_compid
+
+MAVLink Component ID for MAVLink port 1
+
+| Default | Min | Max |
+| --- | --- | --- |
+| 1 | 1 | 255 |
+
+---
-Rate of the extended status message for MAVLink telemetry
+### mavlink_port1_ext_status_rate
+
+Rate of the extended status message for MAVLink telemetry on port 1
| Default | Min | Max |
| --- | --- | --- |
@@ -2662,9 +2672,9 @@ Rate of the extended status message for MAVLink telemetry
---
-### mavlink_extra1_rate
+### mavlink_port1_extra1_rate
-Rate of the extra1 message for MAVLink telemetry
+Rate of the extra1 message for MAVLink telemetry on port 1
| Default | Min | Max |
| --- | --- | --- |
@@ -2672,9 +2682,9 @@ Rate of the extra1 message for MAVLink telemetry
---
-### mavlink_extra2_rate
+### mavlink_port1_extra2_rate
-Rate of the extra2 message for MAVLink telemetry
+Rate of the extra2 message for MAVLink telemetry on port 1
| Default | Min | Max |
| --- | --- | --- |
@@ -2682,9 +2692,9 @@ Rate of the extra2 message for MAVLink telemetry
---
-### mavlink_extra3_rate
+### mavlink_port1_extra3_rate
-Rate of the extra3 message for MAVLink telemetry
+Rate of the extra3 message for MAVLink telemetry on port 1
| Default | Min | Max |
| --- | --- | --- |
@@ -2692,39 +2702,39 @@ Rate of the extra3 message for MAVLink telemetry
---
-### mavlink_min_txbuffer
+### mavlink_port1_high_latency
-Minimum percent of TX buffer space free, before attempting to transmit telemetry. Requuires RADIO_STATUS messages to be processed. 0 = always transmits.
+Enable MAVLink high-latency mode on port 1
| Default | Min | Max |
| --- | --- | --- |
-| 33 | 0 | 100 |
+| OFF | OFF | ON |
---
-### mavlink_port1_compid
+### mavlink_port1_min_txbuffer
-MAVLink Component ID for MAVLink port 1
+Minimum percent of TX buffer space free for MAVLink port 1. Requires RADIO_STATUS messages.
| Default | Min | Max |
| --- | --- | --- |
-| 1 | 1 | 255 |
+| 33 | 0 | 100 |
---
-### mavlink_port1_high_latency
+### mavlink_port1_pos_rate
-Enable MAVLink high-latency mode on port 1
+Rate of the position message for MAVLink telemetry on port 1
| Default | Min | Max |
| --- | --- | --- |
-| OFF | OFF | ON |
+| 2 | 0 | 255 |
---
-### mavlink_port2_autopilot_type
+### mavlink_port1_radio_type
-Autopilot type to advertise for MAVLink telemetry on port 2
+MAVLink radio type for port 1. Affects RSSI and LQ reporting on OSD.
| Default | Min | Max |
| --- | --- | --- |
@@ -2732,6 +2742,16 @@ Autopilot type to advertise for MAVLink telemetry on port 2
---
+### mavlink_port1_rc_chan_rate
+
+Rate of the RC channels message for MAVLink telemetry on port 1
+
+| Default | Min | Max |
+| --- | --- | --- |
+| 1 | 0 | 255 |
+
+---
+
### mavlink_port2_compid
MAVLink Component ID for MAVLink port 2
@@ -2832,36 +2852,6 @@ Rate of the RC channels message for MAVLink telemetry on port 2
---
-### mavlink_port2_sysid
-
-MAVLink System ID for MAVLink port 2
-
-| Default | Min | Max |
-| --- | --- | --- |
-| 1 | 1 | 255 |
-
----
-
-### mavlink_port2_version
-
-Version of MAVLink to use on port 2
-
-| Default | Min | Max |
-| --- | --- | --- |
-| 2 | 1 | 2 |
-
----
-
-### mavlink_port3_autopilot_type
-
-Autopilot type to advertise for MAVLink telemetry on port 3
-
-| Default | Min | Max |
-| --- | --- | --- |
-| GENERIC | | |
-
----
-
### mavlink_port3_compid
MAVLink Component ID for MAVLink port 3
@@ -2962,9 +2952,9 @@ Rate of the RC channels message for MAVLink telemetry on port 3
---
-### mavlink_port3_sysid
+### mavlink_port4_compid
-MAVLink System ID for MAVLink port 3
+MAVLink Component ID for MAVLink port 4
| Default | Min | Max |
| --- | --- | --- |
@@ -2972,19 +2962,69 @@ MAVLink System ID for MAVLink port 3
---
-### mavlink_port3_version
+### mavlink_port4_ext_status_rate
-Version of MAVLink to use on port 3
+Rate of the extended status message for MAVLink telemetry on port 4
| Default | Min | Max |
| --- | --- | --- |
-| 2 | 1 | 2 |
+| 2 | 0 | 255 |
+
+---
+
+### mavlink_port4_extra1_rate
+
+Rate of the extra1 message for MAVLink telemetry on port 4
+
+| Default | Min | Max |
+| --- | --- | --- |
+| 2 | 0 | 255 |
+
+---
+
+### mavlink_port4_extra2_rate
+
+Rate of the extra2 message for MAVLink telemetry on port 4
+
+| Default | Min | Max |
+| --- | --- | --- |
+| 2 | 0 | 255 |
+
+---
+
+### mavlink_port4_extra3_rate
+
+Rate of the extra3 message for MAVLink telemetry on port 4
+
+| Default | Min | Max |
+| --- | --- | --- |
+| 1 | 0 | 255 |
+
+---
+
+### mavlink_port4_high_latency
+
+Enable MAVLink high-latency mode on port 4
+
+| Default | Min | Max |
+| --- | --- | --- |
+| OFF | OFF | ON |
+
+---
+
+### mavlink_port4_min_txbuffer
+
+Minimum percent of TX buffer space free for MAVLink port 4. Requires RADIO_STATUS messages.
+
+| Default | Min | Max |
+| --- | --- | --- |
+| 33 | 0 | 100 |
---
-### mavlink_pos_rate
+### mavlink_port4_pos_rate
-Rate of the position message for MAVLink telemetry
+Rate of the position message for MAVLink telemetry on port 4
| Default | Min | Max |
| --- | --- | --- |
@@ -2992,9 +3032,9 @@ Rate of the position message for MAVLink telemetry
---
-### mavlink_radio_type
+### mavlink_port4_radio_type
-Mavlink radio type. Affects how RSSI and LQ are reported on OSD.
+MAVLink radio type for port 4. Affects RSSI and LQ reporting on OSD.
| Default | Min | Max |
| --- | --- | --- |
@@ -3002,9 +3042,9 @@ Mavlink radio type. Affects how RSSI and LQ are reported on OSD.
---
-### mavlink_rc_chan_rate
+### mavlink_port4_rc_chan_rate
-Rate of the RC channels message for MAVLink telemetry
+Rate of the RC channels message for MAVLink telemetry on port 4
| Default | Min | Max |
| --- | --- | --- |
diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml
index c7342f50b17..4d262c9b63e 100644
--- a/src/main/fc/settings.yaml
+++ b/src/main/fc/settings.yaml
@@ -3224,75 +3224,75 @@ groups:
type: int16_t
min: INT16_MIN
max: INT16_MAX
- - name: mavlink_ext_status_rate
+ - name: mavlink_port1_ext_status_rate
field: mavlink[0].extended_status_rate
- description: "Rate of the extended status message for MAVLink telemetry"
+ description: "Rate of the extended status message for MAVLink telemetry on port 1"
type: uint8_t
min: 0
max: 255
default_value: 2
- name: mavlink_autopilot_type
- field: mavlink[0].autopilot_type
+ field: mavlink_common.autopilot_type
description: "Autopilot type to advertise for MAVLink telemetry"
table: mavlink_autopilot_type
default_value: "GENERIC"
type: uint8_t
- - name: mavlink_rc_chan_rate
- description: "Rate of the RC channels message for MAVLink telemetry"
+ - name: mavlink_port1_rc_chan_rate
+ description: "Rate of the RC channels message for MAVLink telemetry on port 1"
field: mavlink[0].rc_channels_rate
type: uint8_t
min: 0
max: 255
default_value: 1
- - name: mavlink_pos_rate
- description: "Rate of the position message for MAVLink telemetry"
+ - name: mavlink_port1_pos_rate
+ description: "Rate of the position message for MAVLink telemetry on port 1"
field: mavlink[0].position_rate
type: uint8_t
min: 0
max: 255
default_value: 2
- - name: mavlink_extra1_rate
- description: "Rate of the extra1 message for MAVLink telemetry"
+ - name: mavlink_port1_extra1_rate
+ description: "Rate of the extra1 message for MAVLink telemetry on port 1"
field: mavlink[0].extra1_rate
type: uint8_t
min: 0
max: 255
default_value: 2
- - name: mavlink_extra2_rate
- description: "Rate of the extra2 message for MAVLink telemetry"
+ - name: mavlink_port1_extra2_rate
+ description: "Rate of the extra2 message for MAVLink telemetry on port 1"
field: mavlink[0].extra2_rate
type: uint8_t
min: 0
max: 255
default_value: 2
- - name: mavlink_extra3_rate
- description: "Rate of the extra3 message for MAVLink telemetry"
+ - name: mavlink_port1_extra3_rate
+ description: "Rate of the extra3 message for MAVLink telemetry on port 1"
field: mavlink[0].extra3_rate
type: uint8_t
min: 0
max: 255
default_value: 1
- name: mavlink_version
- field: mavlink[0].version
+ field: mavlink_common.version
description: "Version of MAVLink to use"
type: uint8_t
min: 1
max: 2
default_value: 2
- - name: mavlink_min_txbuffer
+ - name: mavlink_port1_min_txbuffer
field: mavlink[0].min_txbuff
- description: "Minimum percent of TX buffer space free, before attempting to transmit telemetry. Requuires RADIO_STATUS messages to be processed. 0 = always transmits."
+ description: "Minimum percent of TX buffer space free for MAVLink port 1. Requires RADIO_STATUS messages."
default_value: 33
min: 0
max: 100
- - name: mavlink_radio_type
- description: "Mavlink radio type. Affects how RSSI and LQ are reported on OSD."
+ - name: mavlink_port1_radio_type
+ description: "MAVLink radio type for port 1. Affects RSSI and LQ reporting on OSD."
field: mavlink[0].radio_type
table: mavlink_radio_type
default_value: "GENERIC"
type: uint8_t
- name: mavlink_sysid
- field: mavlink[0].sysid
+ field: mavlink_common.sysid
description: "MAVLink System ID"
type: uint8_t
min: 1
@@ -3317,12 +3317,6 @@ groups:
min: 0
max: 255
default_value: 2
- - name: mavlink_port2_autopilot_type
- field: mavlink[1].autopilot_type
- description: "Autopilot type to advertise for MAVLink telemetry on port 2"
- table: mavlink_autopilot_type
- default_value: "GENERIC"
- type: uint8_t
- name: mavlink_port2_rc_chan_rate
description: "Rate of the RC channels message for MAVLink telemetry on port 2"
field: mavlink[1].rc_channels_rate
@@ -3358,13 +3352,6 @@ groups:
min: 0
max: 255
default_value: 1
- - name: mavlink_port2_version
- field: mavlink[1].version
- description: "Version of MAVLink to use on port 2"
- type: uint8_t
- min: 1
- max: 2
- default_value: 2
- name: mavlink_port2_min_txbuffer
field: mavlink[1].min_txbuff
description: "Minimum percent of TX buffer space free for MAVLink port 2. Requires RADIO_STATUS messages."
@@ -3377,13 +3364,6 @@ groups:
table: mavlink_radio_type
default_value: "GENERIC"
type: uint8_t
- - name: mavlink_port2_sysid
- field: mavlink[1].sysid
- description: "MAVLink System ID for MAVLink port 2"
- type: uint8_t
- min: 1
- max: 255
- default_value: 1
- name: mavlink_port2_compid
field: mavlink[1].compid
description: "MAVLink Component ID for MAVLink port 2"
@@ -3403,12 +3383,6 @@ groups:
min: 0
max: 255
default_value: 2
- - name: mavlink_port3_autopilot_type
- field: mavlink[2].autopilot_type
- description: "Autopilot type to advertise for MAVLink telemetry on port 3"
- table: mavlink_autopilot_type
- default_value: "GENERIC"
- type: uint8_t
- name: mavlink_port3_rc_chan_rate
description: "Rate of the RC channels message for MAVLink telemetry on port 3"
field: mavlink[2].rc_channels_rate
@@ -3444,13 +3418,6 @@ groups:
min: 0
max: 255
default_value: 1
- - name: mavlink_port3_version
- field: mavlink[2].version
- description: "Version of MAVLink to use on port 3"
- type: uint8_t
- min: 1
- max: 2
- default_value: 2
- name: mavlink_port3_min_txbuffer
field: mavlink[2].min_txbuff
description: "Minimum percent of TX buffer space free for MAVLink port 3. Requires RADIO_STATUS messages."
@@ -3463,13 +3430,6 @@ groups:
table: mavlink_radio_type
default_value: "GENERIC"
type: uint8_t
- - name: mavlink_port3_sysid
- field: mavlink[2].sysid
- description: "MAVLink System ID for MAVLink port 3"
- type: uint8_t
- min: 1
- max: 255
- default_value: 1
- name: mavlink_port3_compid
field: mavlink[2].compid
description: "MAVLink Component ID for MAVLink port 3"
@@ -3482,6 +3442,72 @@ groups:
description: "Enable MAVLink high-latency mode on port 3"
type: bool
default_value: OFF
+ - name: mavlink_port4_ext_status_rate
+ field: mavlink[3].extended_status_rate
+ description: "Rate of the extended status message for MAVLink telemetry on port 4"
+ type: uint8_t
+ min: 0
+ max: 255
+ default_value: 2
+ - name: mavlink_port4_rc_chan_rate
+ description: "Rate of the RC channels message for MAVLink telemetry on port 4"
+ field: mavlink[3].rc_channels_rate
+ type: uint8_t
+ min: 0
+ max: 255
+ default_value: 1
+ - name: mavlink_port4_pos_rate
+ description: "Rate of the position message for MAVLink telemetry on port 4"
+ field: mavlink[3].position_rate
+ type: uint8_t
+ min: 0
+ max: 255
+ default_value: 2
+ - name: mavlink_port4_extra1_rate
+ description: "Rate of the extra1 message for MAVLink telemetry on port 4"
+ field: mavlink[3].extra1_rate
+ type: uint8_t
+ min: 0
+ max: 255
+ default_value: 2
+ - name: mavlink_port4_extra2_rate
+ description: "Rate of the extra2 message for MAVLink telemetry on port 4"
+ field: mavlink[3].extra2_rate
+ type: uint8_t
+ min: 0
+ max: 255
+ default_value: 2
+ - name: mavlink_port4_extra3_rate
+ description: "Rate of the extra3 message for MAVLink telemetry on port 4"
+ field: mavlink[3].extra3_rate
+ type: uint8_t
+ min: 0
+ max: 255
+ default_value: 1
+ - name: mavlink_port4_min_txbuffer
+ field: mavlink[3].min_txbuff
+ description: "Minimum percent of TX buffer space free for MAVLink port 4. Requires RADIO_STATUS messages."
+ default_value: 33
+ min: 0
+ max: 100
+ - name: mavlink_port4_radio_type
+ description: "MAVLink radio type for port 4. Affects RSSI and LQ reporting on OSD."
+ field: mavlink[3].radio_type
+ table: mavlink_radio_type
+ default_value: "GENERIC"
+ type: uint8_t
+ - name: mavlink_port4_compid
+ field: mavlink[3].compid
+ description: "MAVLink Component ID for MAVLink port 4"
+ type: uint8_t
+ min: 1
+ max: 255
+ default_value: 1
+ - name: mavlink_port4_high_latency
+ field: mavlink[3].high_latency
+ description: "Enable MAVLink high-latency mode on port 4"
+ type: bool
+ default_value: OFF
- name: PG_OSD_CONFIG
type: osdConfig_t
diff --git a/src/main/io/serial.c b/src/main/io/serial.c
index d6b82da02b8..e7865f3fac2 100644
--- a/src/main/io/serial.c
+++ b/src/main/io/serial.c
@@ -296,10 +296,8 @@ bool isSerialConfigValid(const serialConfig_t *serialConfigToCheck)
if ((portConfig->functionMask & FUNCTION_MSP) && (portConfig->functionMask & ALL_FUNCTIONS_SHARABLE_WITH_MSP)) {
// MSP & telemetry
-#ifdef USE_TELEMETRY
} else if (telemetryCheckRxPortShared(portConfig)) {
// serial RX & telemetry
-#endif
} else {
// some other combination
return false;
diff --git a/src/main/rx/mavlink.h b/src/main/rx/mavlink.h
index 644e71d4f8d..c891039ddb8 100644
--- a/src/main/rx/mavlink.h
+++ b/src/main/rx/mavlink.h
@@ -17,9 +17,7 @@
#pragma once
-#ifndef MAX_MAVLINK_PORTS
-#define MAX_MAVLINK_PORTS 3
-#endif
+#include "target/common.h"
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wunused-function"
diff --git a/src/main/target/common.h b/src/main/target/common.h
index 45eb12ac4bc..e63eff4785d 100644
--- a/src/main/target/common.h
+++ b/src/main/target/common.h
@@ -31,6 +31,10 @@
#define DYNAMIC_HEAP_SIZE 2048
+#ifndef MAX_MAVLINK_PORTS
+#define MAX_MAVLINK_PORTS 4
+#endif
+
#define I2C1_OVERCLOCK false
#define I2C2_OVERCLOCK false
#define USE_I2C_PULLUP // Enable built-in pullups on all boards in case external ones are too week
@@ -226,4 +230,3 @@
#define USE_EZ_TUNE
#define USE_ADAPTIVE_FILTER
-
diff --git a/src/main/telemetry/mavlink.c b/src/main/telemetry/mavlink.c
index 74665525ec0..3ccf552c77b 100644
--- a/src/main/telemetry/mavlink.c
+++ b/src/main/telemetry/mavlink.c
@@ -90,111 +90,8 @@
#include "scheduler/scheduler.h"
-#pragma GCC diagnostic push
-#pragma GCC diagnostic ignored "-Wunused-function"
-#ifndef MAVLINK_COMM_NUM_BUFFERS
-#define MAVLINK_COMM_NUM_BUFFERS MAX_MAVLINK_PORTS
-#endif
-#include "common/mavlink.h"
-#pragma GCC diagnostic pop
-
-#define TELEMETRY_MAVLINK_PORT_MODE MODE_RXTX
-#define TELEMETRY_MAVLINK_MAXRATE 50
-#define TELEMETRY_MAVLINK_DELAY ((1000 * 1000) / TELEMETRY_MAVLINK_MAXRATE)
-#define TELEMETRY_MAVLINK_HIGH_LATENCY_INTERVAL_US (5 * 1000 * 1000)
-#define MAV_DATA_STREAM_EXTENDED_SYS_STATE (MAV_DATA_STREAM_EXTRA3 + 1)
-#define ARDUPILOT_VERSION_MAJOR 4
-#define ARDUPILOT_VERSION_MINOR 6
-#define ARDUPILOT_VERSION_PATCH 3
-#define MAVLINK_MAX_ROUTES 32
-#define MAVLINK_PORT_MASK(portIndex) (1U << (portIndex))
-
-typedef enum {
- MAV_FRAME_SUPPORTED_NONE = 0,
- MAV_FRAME_SUPPORTED_GLOBAL = (1 << 0),
- MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT = (1 << 1),
- MAV_FRAME_SUPPORTED_GLOBAL_INT = (1 << 2),
- MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT_INT = (1 << 3),
-} mavFrameSupportMask_e;
-
-/**
- * MAVLink requires angles to be in the range -Pi..Pi.
- * This converts angles from a range of 0..Pi to -Pi..Pi
- */
-#define RADIANS_TO_MAVLINK_RANGE(angle) (angle > M_PIf) ? angle - (2 * M_PIf) : angle
-
-/** @brief A mapping of plane flight modes for custom_mode field of heartbeat. */
-typedef enum APM_PLANE_MODE
-{
- PLANE_MODE_MANUAL=0,
- PLANE_MODE_CIRCLE=1,
- PLANE_MODE_STABILIZE=2,
- PLANE_MODE_TRAINING=3,
- PLANE_MODE_ACRO=4,
- PLANE_MODE_FLY_BY_WIRE_A=5,
- PLANE_MODE_FLY_BY_WIRE_B=6,
- PLANE_MODE_CRUISE=7,
- PLANE_MODE_AUTOTUNE=8,
- PLANE_MODE_AUTO=10,
- PLANE_MODE_RTL=11,
- PLANE_MODE_LOITER=12,
- PLANE_MODE_TAKEOFF=13,
- PLANE_MODE_AVOID_ADSB=14,
- PLANE_MODE_GUIDED=15,
- PLANE_MODE_INITIALIZING=16,
- PLANE_MODE_QSTABILIZE=17,
- PLANE_MODE_QHOVER=18,
- PLANE_MODE_QLOITER=19,
- PLANE_MODE_QLAND=20,
- PLANE_MODE_QRTL=21,
- PLANE_MODE_QAUTOTUNE=22,
- PLANE_MODE_QACRO=23,
- PLANE_MODE_THERMAL=24,
- PLANE_MODE_LOITER_ALT_QLAND=25,
- PLANE_MODE_AUTOLAND=26,
- PLANE_MODE_ENUM_END=27,
-} APM_PLANE_MODE;
-
-/** @brief A mapping of copter flight modes for custom_mode field of heartbeat. */
-typedef enum APM_COPTER_MODE
-{
- COPTER_MODE_STABILIZE=0,
- COPTER_MODE_ACRO=1,
- COPTER_MODE_ALT_HOLD=2,
- COPTER_MODE_AUTO=3,
- COPTER_MODE_GUIDED=4,
- COPTER_MODE_LOITER=5,
- COPTER_MODE_RTL=6,
- COPTER_MODE_CIRCLE=7,
- COPTER_MODE_LAND=9,
- COPTER_MODE_DRIFT=11,
- COPTER_MODE_SPORT=13,
- COPTER_MODE_FLIP=14,
- COPTER_MODE_AUTOTUNE=15,
- COPTER_MODE_POSHOLD=16,
- COPTER_MODE_BRAKE=17,
- COPTER_MODE_THROW=18,
- COPTER_MODE_AVOID_ADSB=19,
- COPTER_MODE_GUIDED_NOGPS=20,
- COPTER_MODE_SMART_RTL=21,
- COPTER_MODE_FLOWHOLD=22,
- COPTER_MODE_FOLLOW=23,
- COPTER_MODE_ZIGZAG=24,
- COPTER_MODE_SYSTEMID=25,
- COPTER_MODE_AUTOROTATE=26,
- COPTER_MODE_AUTO_RTL=27,
- COPTER_MODE_TURTLE=28,
- COPTER_MODE_ENUM_END=29,
-} APM_COPTER_MODE;
-
-typedef struct mavlinkRouteEntry_s {
- uint8_t sysid;
- uint8_t compid;
- uint8_t ingressPortIndex;
-} mavlinkRouteEntry_t;
-
/* MAVLink datastream rates in Hz */
-static const uint8_t mavDefaultRates[] = {
+const uint8_t mavDefaultRates[MAVLINK_STREAM_COUNT] = {
[MAV_DATA_STREAM_EXTENDED_STATUS] = 2, // 2Hz
[MAV_DATA_STREAM_RC_CHANNELS] = 1, // 1Hz
[MAV_DATA_STREAM_POSITION] = 2, // 2Hz
@@ -204,25 +101,6 @@ static const uint8_t mavDefaultRates[] = {
[MAV_DATA_STREAM_EXTENDED_SYS_STATE] = 1 // 1Hz
};
-typedef struct mavlinkPortRuntime_s {
- serialPort_t *port;
- const serialPortConfig_t *portConfig;
- portSharing_e portSharing;
- bool telemetryEnabled;
- bool txbuffValid;
- uint8_t txbuffFree;
- timeUs_t lastMavlinkMessageUs;
- timeUs_t lastHighLatencyMessageUs;
- bool highLatencyEnabled;
- uint8_t mavRates[ARRAYLEN(mavDefaultRates)];
- uint8_t mavRatesConfigured[ARRAYLEN(mavDefaultRates)];
- uint8_t mavTicks[ARRAYLEN(mavDefaultRates)];
- mavlink_message_t mavRecvMsg;
- mavlink_status_t mavRecvStatus;
-} mavlinkPortRuntime_t;
-
-#define MAXSTREAMS (ARRAYLEN(mavDefaultRates))
-
static mavlinkPortRuntime_t mavPortStates[MAX_MAVLINK_PORTS];
static uint8_t mavPortCount = 0;
static mavlinkRouteEntry_t mavRouteTable[MAVLINK_MAX_ROUTES];
@@ -357,10 +235,20 @@ static const mavlinkTelemetryPortConfig_t *mavlinkGetPortConfig(uint8_t portInde
return &telemetryConfig()->mavlink[portIndex];
}
+static const mavlinkTelemetryCommonConfig_t *mavlinkGetCommonConfig(void)
+{
+ return &telemetryConfig()->mavlink_common;
+}
+
+static uint8_t mavlinkGetProtocolVersion(void)
+{
+ return mavlinkGetCommonConfig()->version;
+}
+
static void mavlinkApplyActivePortOutputVersion(void)
{
mavlink_status_t *chanState = mavlink_get_channel_status(MAVLINK_COMM_0);
- if (mavActiveConfig->version == 1) {
+ if (mavlinkGetProtocolVersion() == 1) {
chanState->flags |= MAVLINK_STATUS_FLAG_OUT_MAVLINK1;
} else {
chanState->flags &= ~MAVLINK_STATUS_FLAG_OUT_MAVLINK1;
@@ -371,8 +259,9 @@ static void mavlinkSetActivePortContext(uint8_t portIndex)
{
mavActivePort = &mavPortStates[portIndex];
mavActiveConfig = mavlinkGetPortConfig(portIndex);
- mavAutopilotType = mavActiveConfig->autopilot_type;
- mavSystemId = mavActiveConfig->sysid;
+ const mavlinkTelemetryCommonConfig_t *commonConfig = mavlinkGetCommonConfig();
+ mavAutopilotType = commonConfig->autopilot_type;
+ mavSystemId = commonConfig->sysid;
mavComponentId = mavActiveConfig->compid;
mavlinkApplyActivePortOutputVersion();
}
@@ -572,7 +461,7 @@ static void mavlinkSendMessage(void)
static void mavlinkSendAutopilotVersion(void)
{
- if (mavActiveConfig->version == 1) return;
+ if (mavlinkGetProtocolVersion() == 1) return;
// Capabilities aligned with what we actually support.
uint64_t capabilities = 0;
@@ -605,11 +494,11 @@ static void mavlinkSendAutopilotVersion(void)
static void mavlinkSendProtocolVersion(void)
{
- if (mavActiveConfig->version == 1) return;
+ if (mavlinkGetProtocolVersion() == 1) return;
uint8_t specHash[8] = {0};
uint8_t libHash[8] = {0};
- const uint16_t protocolVersion = (uint16_t)mavActiveConfig->version * 100;
+ const uint16_t protocolVersion = (uint16_t)mavlinkGetProtocolVersion() * 100;
mavlink_msg_protocol_version_pack(
mavSystemId,
@@ -692,12 +581,7 @@ static uint8_t navWaypointFrame(const navWaypoint_t *wp, bool useIntMessages)
return useIntMessages ? MAV_FRAME_GLOBAL_RELATIVE_ALT_INT : MAV_FRAME_GLOBAL_RELATIVE_ALT;
}
-typedef struct {
- uint8_t customMode;
- const char *name;
-} mavlinkModeDescriptor_t;
-
-static const mavlinkModeDescriptor_t planeModes[] = {
+const mavlinkModeDescriptor_t planeModes[] = {
{ PLANE_MODE_MANUAL, "MANUAL" },
{ PLANE_MODE_ACRO, "ACRO" },
{ PLANE_MODE_STABILIZE, "STABILIZE" },
@@ -710,8 +594,9 @@ static const mavlinkModeDescriptor_t planeModes[] = {
{ PLANE_MODE_TAKEOFF, "TAKEOFF" },
{ PLANE_MODE_GUIDED, "GUIDED" },
};
+const uint8_t planeModesCount = (uint8_t)ARRAYLEN(planeModes);
-static const mavlinkModeDescriptor_t copterModes[] = {
+const mavlinkModeDescriptor_t copterModes[] = {
{ COPTER_MODE_ACRO, "ACRO" },
{ COPTER_MODE_STABILIZE, "STABILIZE" },
{ COPTER_MODE_ALT_HOLD, "ALT_HOLD" },
@@ -726,6 +611,7 @@ static const mavlinkModeDescriptor_t copterModes[] = {
{ COPTER_MODE_SMART_RTL, "SMART_RTL" },
{ COPTER_MODE_DRIFT, "DRIFT" },
};
+const uint8_t copterModesCount = (uint8_t)ARRAYLEN(copterModes);
static bool mavlinkPlaneModeIsConfigured(uint8_t customMode)
{
@@ -1022,7 +908,7 @@ void mavlinkSendSystemStatus(void)
void mavlinkSendRCChannelsAndRSSI(void)
{
#define GET_CHANNEL_VALUE(x) ((rxRuntimeConfig.channelCount >= (x + 1)) ? rxGetChannelValue(x) : 0)
- if (mavActiveConfig->version == 1) {
+ if (mavlinkGetProtocolVersion() == 1) {
mavlink_msg_rc_channels_raw_pack(mavSystemId, mavComponentId, &mavSendMsg,
// time_boot_ms Timestamp (milliseconds since system boot)
millis(),
@@ -1634,7 +1520,7 @@ static void mavlinkSendHighLatency2(timeUs_t currentTimeUs)
void processMAVLinkTelemetry(timeUs_t currentTimeUs)
{
- if (mavActivePort->highLatencyEnabled && mavActiveConfig->version != 1) {
+ if (mavActivePort->highLatencyEnabled && mavlinkGetProtocolVersion() != 1) {
if ((currentTimeUs - mavActivePort->lastHighLatencyMessageUs) >= TELEMETRY_MAVLINK_HIGH_LATENCY_INTERVAL_US) {
mavlinkSendHighLatency2(currentTimeUs);
mavActivePort->lastHighLatencyMessageUs = currentTimeUs;
@@ -1988,18 +1874,6 @@ static bool handleIncoming_MISSION_REQUEST_LIST(void)
return false;
}
-typedef struct {
- uint8_t frame;
- uint16_t command;
- float param1;
- float param2;
- float param3;
- float param4;
- int32_t lat;
- int32_t lon;
- float alt;
-} mavlinkMissionItemData_t;
-
static bool fillMavlinkMissionItemFromWaypoint(const navWaypoint_t *wp, bool useIntMessages, mavlinkMissionItemData_t *item)
{
mavlinkMissionItemData_t data = {0};
@@ -2252,7 +2126,7 @@ static bool handleIncoming_COMMAND(uint8_t targetSystem, uint8_t ackTargetSystem
}
case MAV_CMD_CONTROL_HIGH_LATENCY:
if (param1 == 0.0f || param1 == 1.0f) {
- if (mavActiveConfig->version == 1 && param1 > 0.5f) {
+ if (mavlinkGetProtocolVersion() == 1 && param1 > 0.5f) {
mavlinkSendCommandAck(command, MAV_RESULT_UNSUPPORTED, ackTargetSystem, ackTargetComponent);
return true;
}
@@ -2267,7 +2141,7 @@ static bool handleIncoming_COMMAND(uint8_t targetSystem, uint8_t ackTargetSystem
}
return true;
case MAV_CMD_REQUEST_PROTOCOL_VERSION:
- if (mavActiveConfig->version == 1) {
+ if (mavlinkGetProtocolVersion() == 1) {
mavlinkSendCommandAck(command, MAV_RESULT_UNSUPPORTED, ackTargetSystem, ackTargetComponent);
} else {
mavlinkSendProtocolVersion();
@@ -2275,7 +2149,7 @@ static bool handleIncoming_COMMAND(uint8_t targetSystem, uint8_t ackTargetSystem
}
return true;
case MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES:
- if (mavActiveConfig->version == 1) {
+ if (mavlinkGetProtocolVersion() == 1) {
mavlinkSendCommandAck(command, MAV_RESULT_UNSUPPORTED, ackTargetSystem, ackTargetComponent);
} else {
mavlinkSendAutopilotVersion();
@@ -2293,13 +2167,13 @@ static bool handleIncoming_COMMAND(uint8_t targetSystem, uint8_t ackTargetSystem
sent = true;
break;
case MAVLINK_MSG_ID_AUTOPILOT_VERSION:
- if (mavActiveConfig->version != 1) {
+ if (mavlinkGetProtocolVersion() != 1) {
mavlinkSendAutopilotVersion();
sent = true;
}
break;
case MAVLINK_MSG_ID_PROTOCOL_VERSION:
- if (mavActiveConfig->version != 1) {
+ if (mavlinkGetProtocolVersion() != 1) {
mavlinkSendProtocolVersion();
sent = true;
}
@@ -2321,9 +2195,9 @@ static bool handleIncoming_COMMAND(uint8_t targetSystem, uint8_t ackTargetSystem
const bool isPlane = mixerConfig()->platformType == PLATFORM_AIRPLANE || STATE(FIXED_WING_LEGACY);
const mavlinkModeSelection_t modeSelection = selectMavlinkMode(isPlane);
if (isPlane) {
- mavlinkSendAvailableModes(planeModes, ARRAYLEN(planeModes), modeSelection.customMode, mavlinkPlaneModeIsConfigured);
+ mavlinkSendAvailableModes(planeModes, planeModesCount, modeSelection.customMode, mavlinkPlaneModeIsConfigured);
} else {
- mavlinkSendAvailableModes(copterModes, ARRAYLEN(copterModes), modeSelection.customMode, mavlinkCopterModeIsConfigured);
+ mavlinkSendAvailableModes(copterModes, copterModesCount, modeSelection.customMode, mavlinkCopterModeIsConfigured);
}
sent = true;
}
@@ -2694,9 +2568,14 @@ static bool handleIncoming_ADSB_VEHICLE(void) {
static bool mavlinkIsFromLocalIdentity(uint8_t sysid, uint8_t compid)
{
+ const uint8_t localSystemId = mavlinkGetCommonConfig()->sysid;
+ if (sysid != localSystemId) {
+ return false;
+ }
+
for (uint8_t portIndex = 0; portIndex < mavPortCount; portIndex++) {
const mavlinkTelemetryPortConfig_t *cfg = mavlinkGetPortConfig(portIndex);
- if (cfg->sysid == sysid && cfg->compid == compid) {
+ if (cfg->compid == compid) {
return true;
}
}
@@ -2805,12 +2684,12 @@ static int8_t mavlinkResolveLocalPortForTarget(int16_t targetSystem, int16_t tar
return ingressPortIndex;
}
+ if ((uint8_t)targetSystem != mavlinkGetCommonConfig()->sysid) {
+ return -1;
+ }
+
for (uint8_t portIndex = 0; portIndex < mavPortCount; portIndex++) {
const mavlinkTelemetryPortConfig_t *cfg = mavlinkGetPortConfig(portIndex);
- if (cfg->sysid != targetSystem) {
- continue;
- }
-
if (targetComponent <= 0 || cfg->compid == targetComponent) {
return portIndex;
}
diff --git a/src/main/telemetry/mavlink.h b/src/main/telemetry/mavlink.h
index 899674194de..57d03e1d64e 100755
--- a/src/main/telemetry/mavlink.h
+++ b/src/main/telemetry/mavlink.h
@@ -17,6 +17,158 @@
#pragma once
+#include "common/time.h"
+
+#include "io/serial.h"
+
+#include "target/common.h"
+
+#pragma GCC diagnostic push
+#pragma GCC diagnostic ignored "-Wunused-function"
+#ifndef MAVLINK_COMM_NUM_BUFFERS
+#define MAVLINK_COMM_NUM_BUFFERS MAX_MAVLINK_PORTS
+#endif
+#include "common/mavlink.h"
+#pragma GCC diagnostic pop
+
+#define TELEMETRY_MAVLINK_PORT_MODE MODE_RXTX
+#define TELEMETRY_MAVLINK_MAXRATE 50
+#define TELEMETRY_MAVLINK_DELAY ((1000 * 1000) / TELEMETRY_MAVLINK_MAXRATE)
+#define TELEMETRY_MAVLINK_HIGH_LATENCY_INTERVAL_US (5 * 1000 * 1000)
+#define MAV_DATA_STREAM_EXTENDED_SYS_STATE (MAV_DATA_STREAM_EXTRA3 + 1)
+#define MAVLINK_STREAM_COUNT (MAV_DATA_STREAM_EXTENDED_SYS_STATE + 1)
+#define ARDUPILOT_VERSION_MAJOR 4
+#define ARDUPILOT_VERSION_MINOR 6
+#define ARDUPILOT_VERSION_PATCH 3
+#define MAVLINK_MAX_ROUTES 32
+#define MAVLINK_PORT_MASK(portIndex) (1U << (portIndex))
+#define MAXSTREAMS MAVLINK_STREAM_COUNT
+
+typedef enum {
+ MAV_FRAME_SUPPORTED_NONE = 0,
+ MAV_FRAME_SUPPORTED_GLOBAL = (1 << 0),
+ MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT = (1 << 1),
+ MAV_FRAME_SUPPORTED_GLOBAL_INT = (1 << 2),
+ MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT_INT = (1 << 3),
+} mavFrameSupportMask_e;
+
+/**
+ * MAVLink requires angles to be in the range -Pi..Pi.
+ * This converts angles from a range of 0..Pi to -Pi..Pi
+ */
+#define RADIANS_TO_MAVLINK_RANGE(angle) (angle > M_PIf) ? angle - (2 * M_PIf) : angle
+
+/** @brief A mapping of plane flight modes for custom_mode field of heartbeat. */
+typedef enum APM_PLANE_MODE
+{
+ PLANE_MODE_MANUAL=0,
+ PLANE_MODE_CIRCLE=1,
+ PLANE_MODE_STABILIZE=2,
+ PLANE_MODE_TRAINING=3,
+ PLANE_MODE_ACRO=4,
+ PLANE_MODE_FLY_BY_WIRE_A=5,
+ PLANE_MODE_FLY_BY_WIRE_B=6,
+ PLANE_MODE_CRUISE=7,
+ PLANE_MODE_AUTOTUNE=8,
+ PLANE_MODE_AUTO=10,
+ PLANE_MODE_RTL=11,
+ PLANE_MODE_LOITER=12,
+ PLANE_MODE_TAKEOFF=13,
+ PLANE_MODE_AVOID_ADSB=14,
+ PLANE_MODE_GUIDED=15,
+ PLANE_MODE_INITIALIZING=16,
+ PLANE_MODE_QSTABILIZE=17,
+ PLANE_MODE_QHOVER=18,
+ PLANE_MODE_QLOITER=19,
+ PLANE_MODE_QLAND=20,
+ PLANE_MODE_QRTL=21,
+ PLANE_MODE_QAUTOTUNE=22,
+ PLANE_MODE_QACRO=23,
+ PLANE_MODE_THERMAL=24,
+ PLANE_MODE_LOITER_ALT_QLAND=25,
+ PLANE_MODE_AUTOLAND=26,
+ PLANE_MODE_ENUM_END=27,
+} APM_PLANE_MODE;
+
+/** @brief A mapping of copter flight modes for custom_mode field of heartbeat. */
+typedef enum APM_COPTER_MODE
+{
+ COPTER_MODE_STABILIZE=0,
+ COPTER_MODE_ACRO=1,
+ COPTER_MODE_ALT_HOLD=2,
+ COPTER_MODE_AUTO=3,
+ COPTER_MODE_GUIDED=4,
+ COPTER_MODE_LOITER=5,
+ COPTER_MODE_RTL=6,
+ COPTER_MODE_CIRCLE=7,
+ COPTER_MODE_LAND=9,
+ COPTER_MODE_DRIFT=11,
+ COPTER_MODE_SPORT=13,
+ COPTER_MODE_FLIP=14,
+ COPTER_MODE_AUTOTUNE=15,
+ COPTER_MODE_POSHOLD=16,
+ COPTER_MODE_BRAKE=17,
+ COPTER_MODE_THROW=18,
+ COPTER_MODE_AVOID_ADSB=19,
+ COPTER_MODE_GUIDED_NOGPS=20,
+ COPTER_MODE_SMART_RTL=21,
+ COPTER_MODE_FLOWHOLD=22,
+ COPTER_MODE_FOLLOW=23,
+ COPTER_MODE_ZIGZAG=24,
+ COPTER_MODE_SYSTEMID=25,
+ COPTER_MODE_AUTOROTATE=26,
+ COPTER_MODE_AUTO_RTL=27,
+ COPTER_MODE_TURTLE=28,
+ COPTER_MODE_ENUM_END=29,
+} APM_COPTER_MODE;
+
+typedef struct mavlinkRouteEntry_s {
+ uint8_t sysid;
+ uint8_t compid;
+ uint8_t ingressPortIndex;
+} mavlinkRouteEntry_t;
+
+extern const uint8_t mavDefaultRates[MAVLINK_STREAM_COUNT];
+
+typedef struct mavlinkPortRuntime_s {
+ serialPort_t *port;
+ const serialPortConfig_t *portConfig;
+ portSharing_e portSharing;
+ bool telemetryEnabled;
+ bool txbuffValid;
+ uint8_t txbuffFree;
+ timeUs_t lastMavlinkMessageUs;
+ timeUs_t lastHighLatencyMessageUs;
+ bool highLatencyEnabled;
+ uint8_t mavRates[MAVLINK_STREAM_COUNT];
+ uint8_t mavRatesConfigured[MAVLINK_STREAM_COUNT];
+ uint8_t mavTicks[MAVLINK_STREAM_COUNT];
+ mavlink_message_t mavRecvMsg;
+ mavlink_status_t mavRecvStatus;
+} mavlinkPortRuntime_t;
+
+typedef struct mavlinkModeDescriptor_s {
+ uint8_t customMode;
+ const char *name;
+} mavlinkModeDescriptor_t;
+
+extern const mavlinkModeDescriptor_t planeModes[];
+extern const uint8_t planeModesCount;
+extern const mavlinkModeDescriptor_t copterModes[];
+extern const uint8_t copterModesCount;
+
+typedef struct mavlinkMissionItemData_s {
+ uint8_t frame;
+ uint16_t command;
+ float param1;
+ float param2;
+ float param3;
+ float param4;
+ int32_t lat;
+ int32_t lon;
+ float alt;
+} mavlinkMissionItemData_t;
+
void initMAVLinkTelemetry(void);
void handleMAVLinkTelemetry(timeUs_t currentTimeUs);
void checkMAVLinkTelemetryState(void);
diff --git a/src/main/telemetry/telemetry.c b/src/main/telemetry/telemetry.c
index b771fc5c86c..c77f80a2c57 100644
--- a/src/main/telemetry/telemetry.c
+++ b/src/main/telemetry/telemetry.c
@@ -56,7 +56,7 @@
#include "telemetry/ghst.h"
-PG_REGISTER_WITH_RESET_TEMPLATE(telemetryConfig_t, telemetryConfig, PG_TELEMETRY_CONFIG, 9);
+PG_REGISTER_WITH_RESET_TEMPLATE(telemetryConfig_t, telemetryConfig, PG_TELEMETRY_CONFIG, 10);
PG_RESET_TEMPLATE(telemetryConfig_t, telemetryConfig,
.telemetry_switch = SETTING_TELEMETRY_SWITCH_DEFAULT,
@@ -86,51 +86,59 @@ PG_RESET_TEMPLATE(telemetryConfig_t, telemetryConfig,
.accEventThresholdNegX = SETTING_ACC_EVENT_THRESHOLD_NEG_X_DEFAULT,
#endif
+ .mavlink_common = {
+ .autopilot_type = SETTING_MAVLINK_AUTOPILOT_TYPE_DEFAULT,
+ .version = SETTING_MAVLINK_VERSION_DEFAULT,
+ .sysid = SETTING_MAVLINK_SYSID_DEFAULT,
+ },
.mavlink = {
{
- .autopilot_type = SETTING_MAVLINK_AUTOPILOT_TYPE_DEFAULT,
- .extended_status_rate = SETTING_MAVLINK_EXT_STATUS_RATE_DEFAULT,
- .rc_channels_rate = SETTING_MAVLINK_RC_CHAN_RATE_DEFAULT,
- .position_rate = SETTING_MAVLINK_POS_RATE_DEFAULT,
- .extra1_rate = SETTING_MAVLINK_EXTRA1_RATE_DEFAULT,
- .extra2_rate = SETTING_MAVLINK_EXTRA2_RATE_DEFAULT,
- .extra3_rate = SETTING_MAVLINK_EXTRA3_RATE_DEFAULT,
- .version = SETTING_MAVLINK_VERSION_DEFAULT,
- .min_txbuff = SETTING_MAVLINK_MIN_TXBUFFER_DEFAULT,
- .radio_type = SETTING_MAVLINK_RADIO_TYPE_DEFAULT,
- .sysid = SETTING_MAVLINK_SYSID_DEFAULT,
+ .extended_status_rate = SETTING_MAVLINK_PORT1_EXT_STATUS_RATE_DEFAULT,
+ .rc_channels_rate = SETTING_MAVLINK_PORT1_RC_CHAN_RATE_DEFAULT,
+ .position_rate = SETTING_MAVLINK_PORT1_POS_RATE_DEFAULT,
+ .extra1_rate = SETTING_MAVLINK_PORT1_EXTRA1_RATE_DEFAULT,
+ .extra2_rate = SETTING_MAVLINK_PORT1_EXTRA2_RATE_DEFAULT,
+ .extra3_rate = SETTING_MAVLINK_PORT1_EXTRA3_RATE_DEFAULT,
+ .min_txbuff = SETTING_MAVLINK_PORT1_MIN_TXBUFFER_DEFAULT,
+ .radio_type = SETTING_MAVLINK_PORT1_RADIO_TYPE_DEFAULT,
.compid = SETTING_MAVLINK_PORT1_COMPID_DEFAULT,
.high_latency = SETTING_MAVLINK_PORT1_HIGH_LATENCY_DEFAULT
},
{
- .autopilot_type = SETTING_MAVLINK_PORT2_AUTOPILOT_TYPE_DEFAULT,
.extended_status_rate = SETTING_MAVLINK_PORT2_EXT_STATUS_RATE_DEFAULT,
.rc_channels_rate = SETTING_MAVLINK_PORT2_RC_CHAN_RATE_DEFAULT,
.position_rate = SETTING_MAVLINK_PORT2_POS_RATE_DEFAULT,
.extra1_rate = SETTING_MAVLINK_PORT2_EXTRA1_RATE_DEFAULT,
.extra2_rate = SETTING_MAVLINK_PORT2_EXTRA2_RATE_DEFAULT,
.extra3_rate = SETTING_MAVLINK_PORT2_EXTRA3_RATE_DEFAULT,
- .version = SETTING_MAVLINK_PORT2_VERSION_DEFAULT,
.min_txbuff = SETTING_MAVLINK_PORT2_MIN_TXBUFFER_DEFAULT,
.radio_type = SETTING_MAVLINK_PORT2_RADIO_TYPE_DEFAULT,
- .sysid = SETTING_MAVLINK_PORT2_SYSID_DEFAULT,
.compid = SETTING_MAVLINK_PORT2_COMPID_DEFAULT,
.high_latency = SETTING_MAVLINK_PORT2_HIGH_LATENCY_DEFAULT
},
{
- .autopilot_type = SETTING_MAVLINK_PORT3_AUTOPILOT_TYPE_DEFAULT,
.extended_status_rate = SETTING_MAVLINK_PORT3_EXT_STATUS_RATE_DEFAULT,
.rc_channels_rate = SETTING_MAVLINK_PORT3_RC_CHAN_RATE_DEFAULT,
.position_rate = SETTING_MAVLINK_PORT3_POS_RATE_DEFAULT,
.extra1_rate = SETTING_MAVLINK_PORT3_EXTRA1_RATE_DEFAULT,
.extra2_rate = SETTING_MAVLINK_PORT3_EXTRA2_RATE_DEFAULT,
.extra3_rate = SETTING_MAVLINK_PORT3_EXTRA3_RATE_DEFAULT,
- .version = SETTING_MAVLINK_PORT3_VERSION_DEFAULT,
.min_txbuff = SETTING_MAVLINK_PORT3_MIN_TXBUFFER_DEFAULT,
.radio_type = SETTING_MAVLINK_PORT3_RADIO_TYPE_DEFAULT,
- .sysid = SETTING_MAVLINK_PORT3_SYSID_DEFAULT,
.compid = SETTING_MAVLINK_PORT3_COMPID_DEFAULT,
.high_latency = SETTING_MAVLINK_PORT3_HIGH_LATENCY_DEFAULT
+ },
+ {
+ .extended_status_rate = SETTING_MAVLINK_PORT4_EXT_STATUS_RATE_DEFAULT,
+ .rc_channels_rate = SETTING_MAVLINK_PORT4_RC_CHAN_RATE_DEFAULT,
+ .position_rate = SETTING_MAVLINK_PORT4_POS_RATE_DEFAULT,
+ .extra1_rate = SETTING_MAVLINK_PORT4_EXTRA1_RATE_DEFAULT,
+ .extra2_rate = SETTING_MAVLINK_PORT4_EXTRA2_RATE_DEFAULT,
+ .extra3_rate = SETTING_MAVLINK_PORT4_EXTRA3_RATE_DEFAULT,
+ .min_txbuff = SETTING_MAVLINK_PORT4_MIN_TXBUFFER_DEFAULT,
+ .radio_type = SETTING_MAVLINK_PORT4_RADIO_TYPE_DEFAULT,
+ .compid = SETTING_MAVLINK_PORT4_COMPID_DEFAULT,
+ .high_latency = SETTING_MAVLINK_PORT4_HIGH_LATENCY_DEFAULT
}
}
);
diff --git a/src/main/telemetry/telemetry.h b/src/main/telemetry/telemetry.h
index bc363c930a8..46937dd7386 100644
--- a/src/main/telemetry/telemetry.h
+++ b/src/main/telemetry/telemetry.h
@@ -29,10 +29,7 @@
#include "config/parameter_group.h"
#include "io/serial.h"
-
-#ifndef MAX_MAVLINK_PORTS
-#define MAX_MAVLINK_PORTS 3
-#endif
+#include "target/common.h"
typedef enum {
LTM_RATE_NORMAL,
@@ -51,6 +48,12 @@ typedef enum {
MAVLINK_RADIO_SIK,
} mavlinkRadio_e;
+typedef struct mavlinkTelemetryCommonConfig_s {
+ uint8_t autopilot_type;
+ uint8_t version;
+ uint8_t sysid;
+} mavlinkTelemetryCommonConfig_t;
+
typedef enum {
SMARTPORT_FUEL_UNIT_PERCENT,
SMARTPORT_FUEL_UNIT_MAH,
@@ -58,17 +61,14 @@ typedef enum {
} smartportFuelUnit_e;
typedef struct mavlinkTelemetryPortConfig_s {
- uint8_t autopilot_type;
uint8_t extended_status_rate;
uint8_t rc_channels_rate;
uint8_t position_rate;
uint8_t extra1_rate;
uint8_t extra2_rate;
uint8_t extra3_rate;
- uint8_t version;
uint8_t min_txbuff;
uint8_t radio_type;
- uint8_t sysid;
uint8_t compid;
bool high_latency;
} mavlinkTelemetryPortConfig_t;
@@ -96,12 +96,13 @@ typedef struct telemetryConfig_s {
uint16_t accEventThresholdLow;
uint16_t accEventThresholdNegX;
#endif
+ mavlinkTelemetryCommonConfig_t mavlink_common;
mavlinkTelemetryPortConfig_t mavlink[MAX_MAVLINK_PORTS];
} telemetryConfig_t;
PG_DECLARE(telemetryConfig_t, telemetryConfig);
-#define TELEMETRY_SHAREABLE_PORT_FUNCTIONS_MASK (FUNCTION_TELEMETRY_LTM | FUNCTION_TELEMETRY_IBUS)
+#define TELEMETRY_SHAREABLE_PORT_FUNCTIONS_MASK (FUNCTION_TELEMETRY_LTM | FUNCTION_TELEMETRY_IBUS | FUNCTION_TELEMETRY_MAVLINK)
extern serialPort_t *telemetrySharedPort;
void telemetryInit(void);
From e45c0903ec97df8eceda9875990f0ddd365db6d1 Mon Sep 17 00:00:00 2001
From: frogmane <7685285+xznhj8129@users.noreply.github.com>
Date: Tue, 3 Mar 2026 14:19:39 -0500
Subject: [PATCH 26/46] broadcast fixing
---
src/main/telemetry/mavlink.c | 112 ++-
src/utils/mavlink_tests/ROUTING_TEST.md | 32 +
.../mav_fix2_singleport_benchmark.py | 465 ++++++++++
.../mavlink_tests/mav_multi_benchmark.py | 804 ++++++++++++++++++
src/utils/mavlink_tests/mav_multi_sweep.py | 152 ++++
.../mavlink_routing_compliance_test.py | 499 +++++++++++
src/utils/mavlink_tests/mavlink_test_rc.py | 141 +++
src/utils/mavlink_tests/msp_test_rc.py | 145 ++++
.../mavlink_tests/routing_test_config.yaml | 58 ++
..._multiport4_sweep_rc460800_tele115200.yaml | 51 ++
10 files changed, 2435 insertions(+), 24 deletions(-)
create mode 100644 src/utils/mavlink_tests/ROUTING_TEST.md
create mode 100644 src/utils/mavlink_tests/mav_fix2_singleport_benchmark.py
create mode 100644 src/utils/mavlink_tests/mav_multi_benchmark.py
create mode 100644 src/utils/mavlink_tests/mav_multi_sweep.py
create mode 100644 src/utils/mavlink_tests/mavlink_routing_compliance_test.py
create mode 100644 src/utils/mavlink_tests/mavlink_test_rc.py
create mode 100644 src/utils/mavlink_tests/msp_test_rc.py
create mode 100644 src/utils/mavlink_tests/routing_test_config.yaml
create mode 100644 src/utils/mavlink_tests/test_config_multiport4_sweep_rc460800_tele115200.yaml
diff --git a/src/main/telemetry/mavlink.c b/src/main/telemetry/mavlink.c
index 3ccf552c77b..9198e982ac8 100644
--- a/src/main/telemetry/mavlink.c
+++ b/src/main/telemetry/mavlink.c
@@ -2024,11 +2024,14 @@ static void mavlinkSendCommandAck(uint16_t command, MAV_RESULT result, uint8_t a
mavlinkSendMessage();
}
-static bool handleIncoming_COMMAND(uint8_t targetSystem, uint8_t ackTargetSystem, uint8_t ackTargetComponent, uint16_t command, uint8_t frame, float param1, float param2, float param3, float param4, float latitudeDeg, float longitudeDeg, float altitudeMeters)
+static bool handleIncoming_COMMAND(uint8_t targetSystem, uint8_t targetComponent, uint8_t ackTargetSystem, uint8_t ackTargetComponent, uint16_t command, uint8_t frame, float param1, float param2, float param3, float param4, float latitudeDeg, float longitudeDeg, float altitudeMeters)
{
if (targetSystem != mavSystemId) {
return false;
}
+ if (targetComponent != 0 && targetComponent != mavComponentId) {
+ return false;
+ }
UNUSED(param3);
switch (command) {
@@ -2276,7 +2279,7 @@ static bool handleIncoming_COMMAND_INT(void)
mavlink_command_int_t msg;
mavlink_msg_command_int_decode(&mavRecvMsg, &msg);
- return handleIncoming_COMMAND(msg.target_system, mavRecvMsg.sysid, mavRecvMsg.compid, msg.command, msg.frame, msg.param1, msg.param2, msg.param3, msg.param4, (float)msg.x / 1e7f, (float)msg.y / 1e7f, msg.z);
+ return handleIncoming_COMMAND(msg.target_system, msg.target_component, mavRecvMsg.sysid, mavRecvMsg.compid, msg.command, msg.frame, msg.param1, msg.param2, msg.param3, msg.param4, (float)msg.x / 1e7f, (float)msg.y / 1e7f, msg.z);
}
static bool handleIncoming_COMMAND_LONG(void)
@@ -2285,7 +2288,7 @@ static bool handleIncoming_COMMAND_LONG(void)
mavlink_msg_command_long_decode(&mavRecvMsg, &msg);
// COMMAND_LONG has no frame field; location commands are WGS84 global by definition.
- return handleIncoming_COMMAND(msg.target_system, mavRecvMsg.sysid, mavRecvMsg.compid, msg.command, MAV_FRAME_GLOBAL, msg.param1, msg.param2, msg.param3, msg.param4, msg.param5, msg.param6, msg.param7);
+ return handleIncoming_COMMAND(msg.target_system, msg.target_component, mavRecvMsg.sysid, mavRecvMsg.compid, msg.command, MAV_FRAME_GLOBAL, msg.param1, msg.param2, msg.param3, msg.param4, msg.param5, msg.param6, msg.param7);
}
static bool handleIncoming_MISSION_ITEM_INT(void)
@@ -2382,6 +2385,9 @@ static bool handleIncoming_REQUEST_DATA_STREAM(void)
if (msg.target_system != mavSystemId) {
return false;
}
+ if (msg.target_component != 0 && msg.target_component != mavComponentId) {
+ return false;
+ }
uint8_t rate = 0;
if (msg.start_stop != 0) {
@@ -2698,6 +2704,27 @@ static int8_t mavlinkResolveLocalPortForTarget(int16_t targetSystem, int16_t tar
return -1;
}
+static bool mavlinkShouldFanOutLocalBroadcast(const mavlink_message_t *msg)
+{
+ if (msg->msgid == MAVLINK_MSG_ID_REQUEST_DATA_STREAM) {
+ return true;
+ }
+
+ if (msg->msgid == MAVLINK_MSG_ID_COMMAND_LONG) {
+ mavlink_command_long_t cmd;
+ mavlink_msg_command_long_decode(msg, &cmd);
+ return cmd.command == MAV_CMD_SET_MESSAGE_INTERVAL || cmd.command == MAV_CMD_CONTROL_HIGH_LATENCY;
+ }
+
+ if (msg->msgid == MAVLINK_MSG_ID_COMMAND_INT) {
+ mavlink_command_int_t cmd;
+ mavlink_msg_command_int_decode(msg, &cmd);
+ return cmd.command == MAV_CMD_SET_MESSAGE_INTERVAL || cmd.command == MAV_CMD_CONTROL_HIGH_LATENCY;
+ }
+
+ return false;
+}
+
// Returns whether a message was processed
static bool processMAVLinkIncomingTelemetry(uint8_t ingressPortIndex)
{
@@ -2726,52 +2753,89 @@ static bool processMAVLinkIncomingTelemetry(uint8_t ingressPortIndex)
return false;
}
- mavlinkSetActivePortContext((uint8_t)localPortIndex);
- mavSendMask = MAVLINK_PORT_MASK(ingressPortIndex);
+ uint8_t localPortMask = MAVLINK_PORT_MASK((uint8_t)localPortIndex);
+ const bool isLocalOrSystemBroadcast = targetSystem == 0 || ((targetSystem > 0) && ((uint8_t)targetSystem == mavlinkGetCommonConfig()->sysid));
+ if (targetComponent == 0 && isLocalOrSystemBroadcast && mavlinkShouldFanOutLocalBroadcast(&mavRecvMsg)) {
+ localPortMask = 0;
+ for (uint8_t portIndex = 0; portIndex < mavPortCount; portIndex++) {
+ localPortMask |= MAVLINK_PORT_MASK(portIndex);
+ }
+ }
+
+ bool handled = false;
+ for (uint8_t localIndex = 0; localIndex < mavPortCount; localIndex++) {
+ if (!(localPortMask & MAVLINK_PORT_MASK(localIndex))) {
+ continue;
+ }
+
+ mavlinkSetActivePortContext(localIndex);
+ mavSendMask = MAVLINK_PORT_MASK(ingressPortIndex);
+ bool localHandled = false;
- switch (mavRecvMsg.msgid) {
+ switch (mavRecvMsg.msgid) {
case MAVLINK_MSG_ID_HEARTBEAT:
- return handleIncoming_HEARTBEAT();
+ localHandled = handleIncoming_HEARTBEAT();
+ break;
case MAVLINK_MSG_ID_PARAM_REQUEST_LIST:
- return handleIncoming_PARAM_REQUEST_LIST();
+ localHandled = handleIncoming_PARAM_REQUEST_LIST();
+ break;
case MAVLINK_MSG_ID_MISSION_CLEAR_ALL:
- return handleIncoming_MISSION_CLEAR_ALL();
+ localHandled = handleIncoming_MISSION_CLEAR_ALL();
+ break;
case MAVLINK_MSG_ID_MISSION_COUNT:
- return handleIncoming_MISSION_COUNT();
+ localHandled = handleIncoming_MISSION_COUNT();
+ break;
case MAVLINK_MSG_ID_MISSION_ITEM:
- return handleIncoming_MISSION_ITEM();
+ localHandled = handleIncoming_MISSION_ITEM();
+ break;
case MAVLINK_MSG_ID_MISSION_ITEM_INT:
- return handleIncoming_MISSION_ITEM_INT();
+ localHandled = handleIncoming_MISSION_ITEM_INT();
+ break;
case MAVLINK_MSG_ID_MISSION_REQUEST_LIST:
- return handleIncoming_MISSION_REQUEST_LIST();
-
+ localHandled = handleIncoming_MISSION_REQUEST_LIST();
+ break;
case MAVLINK_MSG_ID_COMMAND_LONG:
- return handleIncoming_COMMAND_LONG();
+ localHandled = handleIncoming_COMMAND_LONG();
+ break;
case MAVLINK_MSG_ID_COMMAND_INT: //7 parameters: parameters 1-4, 7 are floats, and parameters 5,6 are scaled integers
- return handleIncoming_COMMAND_INT();
+ localHandled = handleIncoming_COMMAND_INT();
+ break;
case MAVLINK_MSG_ID_MISSION_REQUEST:
- return handleIncoming_MISSION_REQUEST();
+ localHandled = handleIncoming_MISSION_REQUEST();
+ break;
case MAVLINK_MSG_ID_MISSION_REQUEST_INT:
- return handleIncoming_MISSION_REQUEST_INT();
+ localHandled = handleIncoming_MISSION_REQUEST_INT();
+ break;
case MAVLINK_MSG_ID_REQUEST_DATA_STREAM:
- return handleIncoming_REQUEST_DATA_STREAM();
+ localHandled = handleIncoming_REQUEST_DATA_STREAM();
+ break;
case MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE:
handleIncoming_RC_CHANNELS_OVERRIDE();
// Don't set that we handled a message, otherwise RC channel packets will block telemetry messages
- return false;
+ localHandled = false;
+ break;
case MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT:
- return handleIncoming_SET_POSITION_TARGET_GLOBAL_INT();
+ localHandled = handleIncoming_SET_POSITION_TARGET_GLOBAL_INT();
+ break;
#ifdef USE_ADSB
case MAVLINK_MSG_ID_ADSB_VEHICLE:
- return handleIncoming_ADSB_VEHICLE();
+ localHandled = handleIncoming_ADSB_VEHICLE();
+ break;
#endif
case MAVLINK_MSG_ID_RADIO_STATUS:
handleIncoming_RADIO_STATUS();
// Don't set that we handled a message, otherwise radio status packets will block telemetry messages.
- return false;
+ localHandled = false;
+ break;
default:
- return false;
+ localHandled = false;
+ break;
+ }
+
+ handled = handled || localHandled;
}
+
+ return handled;
}
}
diff --git a/src/utils/mavlink_tests/ROUTING_TEST.md b/src/utils/mavlink_tests/ROUTING_TEST.md
new file mode 100644
index 00000000000..6a67b31822b
--- /dev/null
+++ b/src/utils/mavlink_tests/ROUTING_TEST.md
@@ -0,0 +1,32 @@
+# MAVLink Routing Compliance Test
+
+- fc_system_id: `1`
+- links: `['link_camera', 'link_components_a', 'link_gcs', 'link_gimbal']`
+- gcs_link: `link_gcs`
+- components: `[('mav1_elrs_receiver', 1, 68, 'link_components_a'), ('mav2_companion_computer', 1, 191, 'link_components_a'), ('mav3_camera', 1, 100, 'link_camera'), ('mav4_gimbal', 1, 154, 'link_gimbal')]`
+
+## Rule References
+
+- broadcast_forward: `routing.md:25-27,48-49`
+- known_target_forward: `routing.md:49-50; MAVLink_routing.cpp:66-80`
+- unknown_target_blocked: `routing.md:26-27,53`
+- no_ingress_loop: `MAVLink_routing.cpp:197-209`
+- no_repack: `routing.md:29-31`
+
+## Results
+
+| Case | Source(link) | Target(sys,comp) | Expected Links | Observed Links | Routing | No Ingress Loop | Payload Intact | Pass |
+| --- | --- | --- | --- | --- | --- | --- | --- | --- |
+| `gcs_broadcast` | `gcs (link_gcs)` | `(0,0)` | `['link_camera', 'link_components_a', 'link_gimbal']` | `['link_camera', 'link_components_a', 'link_gimbal']` | `True` | `True` | `True` | `True` |
+| `gcs_target_mav1_elrs_receiver` | `gcs (link_gcs)` | `(1,68)` | `['link_components_a']` | `['link_components_a']` | `True` | `True` | `True` | `True` |
+| `gcs_target_mav2_companion_computer` | `gcs (link_gcs)` | `(1,191)` | `['link_components_a']` | `['link_components_a']` | `True` | `True` | `True` | `True` |
+| `gcs_target_mav3_camera` | `gcs (link_gcs)` | `(1,100)` | `['link_camera']` | `['link_camera']` | `True` | `True` | `True` | `True` |
+| `gcs_target_mav4_gimbal` | `gcs (link_gcs)` | `(1,154)` | `['link_gimbal']` | `['link_gimbal']` | `True` | `True` | `True` | `True` |
+| `gcs_target_unknown_component` | `gcs (link_gcs)` | `(1,199)` | `[]` | `[]` | `True` | `True` | `True` | `True` |
+| `gcs_target_unknown_system` | `gcs (link_gcs)` | `(42,1)` | `[]` | `[]` | `True` | `True` | `True` | `True` |
+| `mav1_elrs_receiver_broadcast` | `mav1_elrs_receiver (link_components_a)` | `(0,0)` | `['link_camera', 'link_gcs', 'link_gimbal']` | `['link_camera', 'link_gcs', 'link_gimbal']` | `True` | `True` | `True` | `True` |
+| `mav1_elrs_receiver_to_mav3_camera` | `mav1_elrs_receiver (link_components_a)` | `(1,100)` | `['link_camera']` | `['link_camera']` | `True` | `True` | `True` | `True` |
+| `mav1_elrs_receiver_to_gcs` | `mav1_elrs_receiver (link_components_a)` | `(255,190)` | `['link_gcs']` | `['link_gcs']` | `True` | `True` | `True` | `True` |
+
+summary pass_count=10 fail_count=0 total=10
+
diff --git a/src/utils/mavlink_tests/mav_fix2_singleport_benchmark.py b/src/utils/mavlink_tests/mav_fix2_singleport_benchmark.py
new file mode 100644
index 00000000000..f510b28b270
--- /dev/null
+++ b/src/utils/mavlink_tests/mav_fix2_singleport_benchmark.py
@@ -0,0 +1,465 @@
+#!/usr/bin/env python3
+"""
+Usage:
+ /home/anon/miniconda3/envs/drone/bin/python mydev/branch/mav_multi/mav_fix2_singleport_benchmark.py --config mydev/branch/mav_multi/test_config_mav_fix2.yaml
+"""
+
+from __future__ import annotations
+
+import argparse
+import contextlib
+import math
+import socket
+import struct
+import subprocess
+import time
+from datetime import datetime, timezone
+from pathlib import Path
+from typing import Any, Dict, List, Tuple
+
+import yaml
+from pymavlink import mavutil
+from serial.serialutil import SerialException
+
+try:
+ from mspapi2.msp_api import MSPApi
+ from mspapi2.lib import InavMSP
+except ModuleNotFoundError:
+ repo_root_guess = Path(__file__).resolve().parents[3]
+ mspapi2_repo = repo_root_guess.parent / "mspapi2"
+ if mspapi2_repo.exists():
+ import sys
+
+ sys.path.insert(0, str(mspapi2_repo))
+ from mspapi2.msp_api import MSPApi
+ from mspapi2.lib import InavMSP
+
+
+CHANNELS = [1500, 1500, 900, 1500] + [900] * 14
+MAV_CMD_REQUEST_MESSAGE = int(mavutil.mavlink.MAV_CMD_REQUEST_MESSAGE)
+
+
+def load_config(config_path: Path) -> Dict[str, Any]:
+ return yaml.safe_load(config_path.read_text(encoding="utf-8"))
+
+
+def wait_for_tcp_port(host: str, port: int, timeout_s: float) -> None:
+ deadline = time.monotonic() + timeout_s
+ while time.monotonic() < deadline:
+ try:
+ with socket.create_connection((host, port), timeout=1.0):
+ return
+ except (ConnectionRefusedError, socket.timeout, OSError):
+ time.sleep(0.2)
+ raise TimeoutError(f"TCP port {host}:{port} did not become available within {timeout_s}s")
+
+
+def cli_read_until_prompt(cli_socket: socket.socket) -> str:
+ data = b""
+ while b"\n# " not in data:
+ chunk = cli_socket.recv(65536)
+ if not chunk:
+ raise ConnectionError("CLI socket closed before prompt")
+ data += chunk
+ return data.decode("utf-8", errors="replace")
+
+
+def run_cli_commands(host: str, port: int, commands: List[str]) -> None:
+ with socket.create_connection((host, port), timeout=5.0) as cli_socket:
+ cli_socket.settimeout(3.0)
+ cli_socket.sendall(b"#\n")
+ cli_read_until_prompt(cli_socket)
+ for command in commands:
+ cli_socket.sendall(command.encode("utf-8") + b"\n")
+ if command == "save":
+ break
+ cli_read_until_prompt(cli_socket)
+ time.sleep(1.0)
+
+
+def build_serial_command(index: int, function_mask: int, baud: int) -> str:
+ return f"serial {index} {function_mask} {baud} {baud} 0 {baud}"
+
+
+def build_cli_commands(config: Dict[str, Any]) -> List[str]:
+ cli_cfg = config["cli"]
+ rc_baud = int(cli_cfg["rc_baud"])
+ commands = [
+ "feature TELEMETRY",
+ "set receiver_type = SERIAL",
+ "set serialrx_provider = MAVLINK",
+ build_serial_command(0, 1, 115200), # UART1 MSP
+ build_serial_command(1, 256, rc_baud), # UART2 MAVLINK single port (RC-capable)
+ build_serial_command(2, 0, rc_baud),
+ build_serial_command(3, 0, rc_baud),
+ "set mavlink_version = 2",
+ f"set mavlink_port1_ext_status_rate = {int(cli_cfg['ext_status_rate_hz'])}",
+ f"set mavlink_port1_rc_chan_rate = {int(cli_cfg['rc_chan_rate_hz'])}",
+ f"set mavlink_port1_pos_rate = {int(cli_cfg['pos_rate_hz'])}",
+ f"set mavlink_port1_extra1_rate = {int(cli_cfg['extra1_rate_hz'])}",
+ f"set mavlink_port1_extra2_rate = {int(cli_cfg['extra2_rate_hz'])}",
+ f"set mavlink_port1_extra3_rate = {int(cli_cfg['extra3_rate_hz'])}",
+ "save",
+ ]
+ return commands
+
+
+def run_workload(
+ config: Dict[str, Any],
+ sitl_pid: int,
+ duration_s: float,
+ command_rate_hz: float,
+ rc_tx_hz_override: float | None = None,
+) -> Dict[str, Any]:
+ tests_cfg = config["tests"]
+ ports_cfg = config["ports"]
+ rc_port = int(ports_cfg["rc"])
+ msp_port = int(ports_cfg["msp"])
+
+ wait_for_tcp_port("127.0.0.1", rc_port, float(tests_cfg["port_ready_timeout_s"]))
+ wait_for_tcp_port("127.0.0.1", msp_port, float(tests_cfg["port_ready_timeout_s"]))
+ msp_enabled = msp_port != rc_port
+
+ heartbeat_expected_hz = float(tests_cfg["heartbeat_expected_hz"])
+ rc_expected_hz = float(tests_cfg["rc_expected_hz"])
+ rc_tx_hz = float(tests_cfg["rc_tx_hz"]) if rc_tx_hz_override is None else float(rc_tx_hz_override)
+ msp_poll_hz = float(tests_cfg["msp_poll_hz"])
+ msp_request_timeout_s = float(tests_cfg["msp_request_timeout_s"])
+ command_message_id = int(tests_cfg["stress_command_message_id"])
+ target_system = int(tests_cfg["rc_target_system"])
+ target_component = int(tests_cfg["rc_target_component"])
+
+ listener = mavutil.mavlink_connection(
+ f"tcp:127.0.0.1:{rc_port}",
+ source_system=170,
+ source_component=190,
+ autoreconnect=True,
+ )
+ sender = mavutil.mavlink_connection(
+ f"tcp:127.0.0.1:{rc_port}",
+ source_system=239,
+ source_component=191,
+ autoreconnect=True,
+ )
+
+ # Prime telemetry stream startup from GCS side.
+ handshake_deadline = time.monotonic() + 3.0
+ while time.monotonic() < handshake_deadline:
+ sender.mav.heartbeat_send(
+ mavutil.mavlink.MAV_TYPE_GCS,
+ mavutil.mavlink.MAV_AUTOPILOT_INVALID,
+ 0,
+ 0,
+ 0,
+ )
+ msg = listener.recv_match(type="HEARTBEAT", blocking=True, timeout=0.2)
+ if msg is not None:
+ target_system = int(msg.get_srcSystem())
+ target_component = int(msg.get_srcComponent())
+ break
+
+ hb_count = 0
+ hb_est_lost = 0
+ last_hb_t: float | None = None
+ rc_count = 0
+ rc_est_lost = 0
+ last_rc_t: float | None = None
+ rc_mismatch = 0
+ command_sent = 0
+ command_ack_total = 0
+ command_ack_ok = 0
+ msp_success = 0
+ msp_fail = 0
+ msp_mismatch = 0
+ rc_sent = 0
+ fc_cpu_load_samples: List[float] = []
+ fc_cycle_time_samples: List[float] = []
+ fc_status_fail = 0
+ fc_status_last_error = ""
+
+ rc_period_s = 1.0 / rc_tx_hz
+ next_rc_send_t = time.monotonic()
+ command_period_s = 0.0 if command_rate_hz <= 0 else (1.0 / command_rate_hz)
+ next_command_send_t = next_rc_send_t
+ next_heartbeat_send_t = next_rc_send_t
+
+ prev_sample_t = time.monotonic()
+ next_resource_sample_t = prev_sample_t + 1.0
+ next_msp_poll_t = prev_sample_t + (1.0 / msp_poll_hz)
+ workload_end_t = prev_sample_t + duration_s
+
+ with (MSPApi(tcp_endpoint=f"127.0.0.1:{msp_port}") if msp_enabled else contextlib.nullcontext()) as msp_api:
+ if msp_enabled:
+ msp_api._serial._max_retries = 1
+ msp_api._serial._reconnect_delay = 0.05
+ while time.monotonic() < workload_end_t:
+ now = time.monotonic()
+
+ if now >= next_heartbeat_send_t:
+ listener.mav.heartbeat_send(
+ mavutil.mavlink.MAV_TYPE_GCS,
+ mavutil.mavlink.MAV_AUTOPILOT_INVALID,
+ 0,
+ 0,
+ 0,
+ )
+ sender.mav.heartbeat_send(
+ mavutil.mavlink.MAV_TYPE_GCS,
+ mavutil.mavlink.MAV_AUTOPILOT_INVALID,
+ 0,
+ 0,
+ 0,
+ )
+ next_heartbeat_send_t += 1.0
+ if next_heartbeat_send_t < now:
+ next_heartbeat_send_t = now + 1.0
+
+ if now >= next_rc_send_t:
+ sender.mav.rc_channels_override_send(target_system, target_component, *CHANNELS[:8])
+ rc_sent += 1
+ next_rc_send_t += rc_period_s
+ if next_rc_send_t < now:
+ next_rc_send_t = now + rc_period_s
+
+ if command_period_s > 0 and now >= next_command_send_t:
+ sender.mav.command_long_send(
+ target_system,
+ target_component,
+ MAV_CMD_REQUEST_MESSAGE,
+ 0,
+ float(command_message_id),
+ 0,
+ 0,
+ 0,
+ 0,
+ 0,
+ 0,
+ )
+ command_sent += 1
+ next_command_send_t += command_period_s
+ if next_command_send_t < now:
+ next_command_send_t = now + command_period_s
+
+ while True:
+ try:
+ msg = listener.recv_match(blocking=False)
+ except (ConnectionRefusedError, OSError):
+ wait_for_tcp_port("127.0.0.1", rc_port, float(tests_cfg["port_ready_timeout_s"]))
+ break
+ if msg is None:
+ break
+ msg_type = msg.get_type()
+ if msg_type == "HEARTBEAT":
+ target_system = int(msg.get_srcSystem())
+ target_component = int(msg.get_srcComponent())
+ hb_count += 1
+ if last_hb_t is not None:
+ dt = now - last_hb_t
+ hb_est_lost += max(int(math.floor(dt * heartbeat_expected_hz) - 1), 0)
+ last_hb_t = now
+ elif msg_type == "RC_CHANNELS":
+ rc_count += 1
+ if last_rc_t is not None:
+ dt = now - last_rc_t
+ rc_est_lost += max(int(math.floor(dt * rc_expected_hz) - 1), 0)
+ last_rc_t = now
+ if (
+ abs(int(msg.chan1_raw) - CHANNELS[0]) > 20
+ or abs(int(msg.chan2_raw) - CHANNELS[1]) > 20
+ or abs(int(msg.chan3_raw) - CHANNELS[2]) > 20
+ or abs(int(msg.chan4_raw) - CHANNELS[3]) > 20
+ ):
+ rc_mismatch += 1
+ elif msg_type == "COMMAND_ACK":
+ if int(msg.command) == MAV_CMD_REQUEST_MESSAGE:
+ command_ack_total += 1
+ if int(msg.result) == int(mavutil.mavlink.MAV_RESULT_ACCEPTED):
+ command_ack_ok += 1
+
+ if msp_enabled and now >= next_msp_poll_t:
+ try:
+ _, payload = msp_api._request_raw(InavMSP.MSP_RC, timeout=msp_request_timeout_s)
+ if len(payload) % 2:
+ raise ValueError("MSP RC payload length must be even")
+ channel_count = len(payload) // 2
+ channels = list(struct.unpack(f"<{channel_count}H", payload))
+ msp_success += 1
+ if (
+ abs(channels[0] - CHANNELS[0]) > 40
+ or abs(channels[1] - CHANNELS[1]) > 40
+ or abs(channels[2] - CHANNELS[2]) > 40
+ or abs(channels[3] - CHANNELS[3]) > 40
+ ):
+ msp_mismatch += 1
+ except (SerialException, RuntimeError, TimeoutError, ConnectionRefusedError):
+ msp_fail += 1
+ next_msp_poll_t += 1.0 / msp_poll_hz
+
+ if now >= next_resource_sample_t:
+ if msp_enabled:
+ try:
+ status = msp_api.get_inav_status()
+ fc_cpu_load_samples.append(float(status["cpuLoad"]))
+ fc_cycle_time_samples.append(float(status["cycleTime"]))
+ except (SerialException, RuntimeError, TimeoutError, ConnectionRefusedError, KeyError, ValueError) as exc:
+ fc_status_fail += 1
+ fc_status_last_error = str(exc)
+ prev_sample_t = now
+ next_resource_sample_t += 1.0
+
+ time.sleep(0.001)
+
+ if msp_enabled and not fc_cpu_load_samples:
+ raise RuntimeError(f"No MSP2_INAV_STATUS samples collected; last_error={fc_status_last_error} fail_count={fc_status_fail}")
+
+ listener.close()
+ sender.close()
+
+ hb_total = hb_count + hb_est_lost
+ rc_total = rc_count + rc_est_lost
+ return {
+ "duration_s": duration_s,
+ "heartbeat_count": hb_count,
+ "heartbeat_est_lost": hb_est_lost,
+ "heartbeat_loss_rate": (hb_est_lost / hb_total) if hb_total > 0 else 0.0,
+ "rc_count": rc_count,
+ "rc_est_lost": rc_est_lost,
+ "rc_loss_rate": (rc_est_lost / rc_total) if rc_total > 0 else 0.0,
+ "rc_mismatch": rc_mismatch,
+ "rc_mismatch_rate": (rc_mismatch / max(rc_count, 1)),
+ "msp_success": msp_success,
+ "msp_fail": msp_fail,
+ "msp_failure_rate": (msp_fail / max(msp_success + msp_fail, 1)),
+ "msp_mismatch": msp_mismatch,
+ "msp_mismatch_rate": (msp_mismatch / max(msp_success, 1)),
+ "command_sent": command_sent,
+ "command_ack_total": command_ack_total,
+ "command_ack_ok": command_ack_ok,
+ "command_ack_failure_rate": ((command_sent - command_ack_total) / command_sent) if command_sent > 0 else 0.0,
+ "command_ack_non_ok_rate": ((command_ack_total - command_ack_ok) / command_ack_total) if command_ack_total > 0 else 0.0,
+ "rc_sent": rc_sent,
+ "rc_sent_hz": (rc_sent / max(duration_s, 1e-6)),
+ "fc_cpu_load_avg_pct": (sum(fc_cpu_load_samples) / len(fc_cpu_load_samples)) if fc_cpu_load_samples else 0.0,
+ "fc_cpu_load_max_pct": max(fc_cpu_load_samples) if fc_cpu_load_samples else 0.0,
+ "fc_cycle_time_avg_us": (sum(fc_cycle_time_samples) / len(fc_cycle_time_samples)) if fc_cycle_time_samples else 0.0,
+ "fc_cycle_time_max_us": max(fc_cycle_time_samples) if fc_cycle_time_samples else 0.0,
+ "fc_status_samples": len(fc_cpu_load_samples),
+ }
+
+
+def write_report(config: Dict[str, Any], baseline: Dict[str, Any], stress: Dict[str, Any]) -> None:
+ out_path = Path(config["output"]["testing_md"])
+ branch_name = str(config.get("meta", {}).get("branch_name", "unknown"))
+ timestamp = datetime.now(timezone.utc).isoformat()
+ lines: List[str] = []
+ lines.append(f"# MAVLink Single-Port Baseline (`{branch_name}`)")
+ lines.append("")
+ lines.append(f"- Generated: `{timestamp}`")
+ lines.append(f"- Branch: `{branch_name}`")
+ lines.append(f"- SITL binary: `{config['sitl']['binary']}`")
+ lines.append(f"- EEPROM: `{config['sitl']['eeprom_path']}`")
+ lines.append("- MSP kept on UART1 by design (`serial 0 ... functionMask=1`).")
+ lines.append("- CLI under test sets `receiver_type=SERIAL` and `serialrx_provider=MAVLINK`.")
+ lines.append(
+ f"- CLI baud config: `rc_baud={config['cli']['rc_baud']}`, "
+ f"`telemetry_baud={config['cli'].get('telemetry_baud', config['cli']['rc_baud'])}`."
+ )
+ lines.append("")
+ lines.append("## Baseline: Single MAVLink RC+Telemetry Port")
+ lines.append("")
+ lines.append(
+ f"- Duration: `{baseline['duration_s']}s` | FC cpuLoad avg/max: `{baseline['fc_cpu_load_avg_pct']:.2f}% / {baseline['fc_cpu_load_max_pct']:.2f}%` | "
+ f"FC cycleTime avg/max: `{baseline['fc_cycle_time_avg_us']:.1f} / {baseline['fc_cycle_time_max_us']:.1f}` us | "
+ f"Status samples: `{baseline['fc_status_samples']}`"
+ )
+ lines.append(
+ f"- MSP success/fail: `{baseline['msp_success']}/{baseline['msp_fail']}` | MSP failure rate: `{baseline['msp_failure_rate']:.4f}` | "
+ f"MSP RC mismatch rate: `{baseline['msp_mismatch_rate']:.4f}`"
+ )
+ lines.append(f"- RC override send rate: `{baseline['rc_sent_hz']:.2f} Hz` (`{baseline['rc_sent']}` packets)")
+ lines.append(
+ f"- HB count/loss: `{baseline['heartbeat_count']}/{baseline['heartbeat_est_lost']}` | HB loss rate: `{baseline['heartbeat_loss_rate']:.4f}`"
+ )
+ lines.append(
+ f"- RC count/loss: `{baseline['rc_count']}/{baseline['rc_est_lost']}` | RC loss rate: `{baseline['rc_loss_rate']:.4f}` | "
+ f"RC mismatch rate: `{baseline['rc_mismatch_rate']:.4f}`"
+ )
+ lines.append("")
+ lines.append("## Stress: Single Port Overload")
+ lines.append("")
+ lines.append(
+ f"- Command load: `{config['tests']['stress_rate_hz']} req/s` for `{stress['duration_s']}s` | "
+ f"FC cpuLoad avg/max: `{stress['fc_cpu_load_avg_pct']:.2f}% / {stress['fc_cpu_load_max_pct']:.2f}%` | "
+ f"FC cycleTime avg/max: `{stress['fc_cycle_time_avg_us']:.1f} / {stress['fc_cycle_time_max_us']:.1f}` us | "
+ f"Status samples: `{stress['fc_status_samples']}`"
+ )
+ lines.append(
+ f"- MSP success/fail: `{stress['msp_success']}/{stress['msp_fail']}` | MSP failure rate: `{stress['msp_failure_rate']:.4f}` | "
+ f"MSP RC mismatch rate: `{stress['msp_mismatch_rate']:.4f}`"
+ )
+ lines.append(f"- RC override send rate: `{stress['rc_sent_hz']:.2f} Hz` (`{stress['rc_sent']}` packets)")
+ lines.append(
+ f"- HB count/loss: `{stress['heartbeat_count']}/{stress['heartbeat_est_lost']}` | HB loss rate: `{stress['heartbeat_loss_rate']:.4f}`"
+ )
+ lines.append(
+ f"- RC count/loss: `{stress['rc_count']}/{stress['rc_est_lost']}` | RC loss rate: `{stress['rc_loss_rate']:.4f}` | "
+ f"RC mismatch rate: `{stress['rc_mismatch_rate']:.4f}`"
+ )
+ lines.append(
+ f"- Command sent/ack: `{stress['command_sent']}/{stress['command_ack_total']}` | "
+ f"ack failure rate: `{stress['command_ack_failure_rate']:.4f}` | non-ok ack rate: `{stress['command_ack_non_ok_rate']:.4f}`"
+ )
+ out_path.parent.mkdir(parents=True, exist_ok=True)
+ out_path.write_text("\n".join(lines) + "\n", encoding="utf-8")
+
+
+if __name__ == "__main__":
+ parser = argparse.ArgumentParser(description="Run single-port MAVLink benchmark and write a baseline markdown report.")
+ parser.add_argument("--config", required=True, help="YAML configuration path")
+ args = parser.parse_args()
+
+ config = load_config(Path(args.config))
+ sitl_bin = Path(config["sitl"]["binary"])
+ sitl_workdir = Path(config["sitl"]["workdir"])
+ sitl_eeprom = str(config["sitl"]["eeprom_path"])
+ sitl_log = Path(config["sitl"]["runtime_log"])
+ sitl_log.parent.mkdir(parents=True, exist_ok=True)
+
+ log_handle = sitl_log.open("w", encoding="utf-8")
+ sitl_proc = subprocess.Popen(
+ [str(sitl_bin), f"--path={sitl_eeprom}"],
+ cwd=str(sitl_workdir),
+ stdout=log_handle,
+ stderr=subprocess.STDOUT,
+ text=True,
+ )
+
+ try:
+ wait_for_tcp_port("127.0.0.1", int(config["ports"]["msp"]), float(config["tests"]["port_ready_timeout_s"]))
+ run_cli_commands("127.0.0.1", int(config["ports"]["msp"]), build_cli_commands(config))
+ wait_for_tcp_port("127.0.0.1", int(config["ports"]["msp"]), float(config["tests"]["port_ready_timeout_s"]))
+ wait_for_tcp_port("127.0.0.1", int(config["ports"]["rc"]), float(config["tests"]["port_ready_timeout_s"]))
+
+ baseline = run_workload(
+ config=config,
+ sitl_pid=sitl_proc.pid,
+ duration_s=float(config["tests"]["baseline_duration_s"]),
+ command_rate_hz=0.0,
+ )
+ stress = run_workload(
+ config=config,
+ sitl_pid=sitl_proc.pid,
+ duration_s=float(config["tests"]["stress_duration_s"]),
+ command_rate_hz=float(config["tests"]["stress_rate_hz"]),
+ rc_tx_hz_override=float(config["tests"]["rc_tx_hz_max"]),
+ )
+ write_report(config, baseline, stress)
+ print(f"report_written={config['output']['testing_md']}", flush=True)
+ finally:
+ sitl_proc.terminate()
+ try:
+ sitl_proc.wait(timeout=5.0)
+ except subprocess.TimeoutExpired:
+ sitl_proc.kill()
+ sitl_proc.wait(timeout=5.0)
+ log_handle.close()
diff --git a/src/utils/mavlink_tests/mav_multi_benchmark.py b/src/utils/mavlink_tests/mav_multi_benchmark.py
new file mode 100644
index 00000000000..6483fa5806e
--- /dev/null
+++ b/src/utils/mavlink_tests/mav_multi_benchmark.py
@@ -0,0 +1,804 @@
+#!/usr/bin/env python3
+"""
+Usage:
+ conda run -n drone python mydev/branch/mav_multi/mav_multi_benchmark.py
+ conda run -n drone python mydev/branch/mav_multi/mav_multi_benchmark.py --config mydev/branch/mav_multi/test_config.yaml
+"""
+
+from __future__ import annotations
+
+import argparse
+import asyncio
+import socket
+import subprocess
+import time
+from datetime import datetime, timezone
+from pathlib import Path
+from typing import Any, Dict, List, Tuple
+
+import yaml
+from mavsdk import System
+from pymavlink import mavutil
+from serial.serialutil import SerialException
+
+try:
+ from mspapi2.msp_api import MSPApi
+ from mspapi2.lib import InavMSP
+except ModuleNotFoundError:
+ repo_root_guess = Path(__file__).resolve().parents[3]
+ mspapi2_repo = repo_root_guess.parent / "mspapi2"
+ if mspapi2_repo.exists():
+ import sys
+
+ sys.path.insert(0, str(mspapi2_repo))
+ from mspapi2.msp_api import MSPApi
+ from mspapi2.lib import InavMSP
+
+
+DEFAULT_CONFIG_PATH = Path("mydev/branch/mav_multi/test_config.yaml")
+CHANNELS = [1500, 1500, 900, 1500] + [900] * 14
+MAV_CMD_REQUEST_MESSAGE = int(mavutil.mavlink.MAV_CMD_REQUEST_MESSAGE)
+MAVLINK_MSG_ID_HEARTBEAT = int(mavutil.mavlink.MAVLINK_MSG_ID_HEARTBEAT)
+
+
+def load_config(config_path: Path) -> Dict[str, Any]:
+ return yaml.safe_load(config_path.read_text(encoding="utf-8"))
+
+
+def wait_for_tcp_port(host: str, port: int, timeout_s: float) -> None:
+ deadline = time.monotonic() + timeout_s
+ while time.monotonic() < deadline:
+ try:
+ with socket.create_connection((host, port), timeout=1.0):
+ return
+ except ConnectionRefusedError:
+ time.sleep(0.2)
+ continue
+ except socket.timeout:
+ time.sleep(0.2)
+ continue
+ raise TimeoutError(f"TCP port {host}:{port} did not become available within {timeout_s}s")
+
+
+def cli_read_until_prompt(cli_socket: socket.socket) -> str:
+ data = b""
+ while b"\n# " not in data:
+ chunk = cli_socket.recv(65536)
+ if not chunk:
+ raise ConnectionError("CLI socket closed before prompt")
+ data += chunk
+ return data.decode("utf-8", errors="replace")
+
+
+def wait_for_cli_ready(host: str, port: int, timeout_s: float) -> None:
+ deadline = time.monotonic() + timeout_s
+ while time.monotonic() < deadline:
+ try:
+ with socket.create_connection((host, port), timeout=1.0) as cli_socket:
+ cli_socket.settimeout(1.0)
+ cli_socket.sendall(b"#\n")
+ cli_read_until_prompt(cli_socket)
+ return
+ except (ConnectionRefusedError, ConnectionError, socket.timeout, OSError):
+ time.sleep(0.2)
+ raise TimeoutError(f"CLI prompt did not become available on {host}:{port} within {timeout_s}s")
+
+
+def run_cli_commands(host: str, port: int, commands: List[str], reboot_timeout_s: float) -> None:
+ sent_save = False
+ with socket.create_connection((host, port), timeout=5.0) as cli_socket:
+ cli_socket.settimeout(3.0)
+ cli_socket.sendall(b"#\n")
+ cli_read_until_prompt(cli_socket)
+ for command in commands:
+ cli_socket.sendall(command.encode("utf-8") + b"\n")
+ if command == "save":
+ sent_save = True
+ break
+ cli_read_until_prompt(cli_socket)
+ if sent_save:
+ # Save triggers reboot; do not send '#' again because that re-enters CLI mode.
+ time.sleep(min(reboot_timeout_s, 1.0))
+
+
+def build_serial_command(index: int, function_mask: int, baud: int) -> str:
+ return f"serial {index} {function_mask} {baud} {baud} 0 {baud}"
+
+
+def build_cli_config_commands(config: Dict[str, Any], mavlink_port_count: int) -> List[str]:
+ cli_cfg = config["cli"]
+ rc_baud = int(cli_cfg["rc_baud"])
+ telemetry_baud = int(cli_cfg["telemetry_baud"])
+ uart2_mask = 320 # FUNCTION_RX_SERIAL + FUNCTION_TELEMETRY_MAVLINK
+ uart3_mask = 256 if mavlink_port_count >= 2 else 0 # FUNCTION_TELEMETRY_MAVLINK
+ uart4_mask = 256 if mavlink_port_count >= 3 else 0 # FUNCTION_TELEMETRY_MAVLINK
+ uart5_mask = 256 if mavlink_port_count >= 4 else 0 # FUNCTION_TELEMETRY_MAVLINK
+ commands = [
+ "feature TELEMETRY",
+ "set receiver_type = SERIAL",
+ "set serialrx_provider = MAVLINK",
+ build_serial_command(0, 1, 115200), # MSP on UART1, always.
+ build_serial_command(1, uart2_mask, rc_baud),
+ build_serial_command(2, uart3_mask, telemetry_baud),
+ build_serial_command(3, uart4_mask, telemetry_baud),
+ build_serial_command(4, uart5_mask, telemetry_baud),
+ "set mavlink_version = 2",
+ "set mavlink_port1_compid = 1",
+ "set mavlink_port2_compid = 2",
+ "set mavlink_port3_compid = 3",
+ "set mavlink_port4_compid = 4",
+ "set mavlink_port1_high_latency = OFF",
+ "set mavlink_port2_high_latency = OFF",
+ "set mavlink_port3_high_latency = OFF",
+ "set mavlink_port4_high_latency = OFF",
+ f"set mavlink_port1_ext_status_rate = {int(cli_cfg['ext_status_rate_hz'])}",
+ f"set mavlink_port1_rc_chan_rate = {int(cli_cfg['rc_chan_rate_hz'])}",
+ f"set mavlink_port1_pos_rate = {int(cli_cfg['pos_rate_hz'])}",
+ f"set mavlink_port1_extra1_rate = {int(cli_cfg['extra1_rate_hz'])}",
+ f"set mavlink_port1_extra2_rate = {int(cli_cfg['extra2_rate_hz'])}",
+ f"set mavlink_port1_extra3_rate = {int(cli_cfg['extra3_rate_hz'])}",
+ f"set mavlink_port2_ext_status_rate = {int(cli_cfg['ext_status_rate_hz'])}",
+ f"set mavlink_port2_rc_chan_rate = {int(cli_cfg['rc_chan_rate_hz'])}",
+ f"set mavlink_port2_pos_rate = {int(cli_cfg['pos_rate_hz'])}",
+ f"set mavlink_port2_extra1_rate = {int(cli_cfg['extra1_rate_hz'])}",
+ f"set mavlink_port2_extra2_rate = {int(cli_cfg['extra2_rate_hz'])}",
+ f"set mavlink_port2_extra3_rate = {int(cli_cfg['extra3_rate_hz'])}",
+ f"set mavlink_port3_ext_status_rate = {int(cli_cfg['ext_status_rate_hz'])}",
+ f"set mavlink_port3_rc_chan_rate = {int(cli_cfg['rc_chan_rate_hz'])}",
+ f"set mavlink_port3_pos_rate = {int(cli_cfg['pos_rate_hz'])}",
+ f"set mavlink_port3_extra1_rate = {int(cli_cfg['extra1_rate_hz'])}",
+ f"set mavlink_port3_extra2_rate = {int(cli_cfg['extra2_rate_hz'])}",
+ f"set mavlink_port3_extra3_rate = {int(cli_cfg['extra3_rate_hz'])}",
+ f"set mavlink_port4_ext_status_rate = {int(cli_cfg['ext_status_rate_hz'])}",
+ f"set mavlink_port4_rc_chan_rate = {int(cli_cfg['rc_chan_rate_hz'])}",
+ f"set mavlink_port4_pos_rate = {int(cli_cfg['pos_rate_hz'])}",
+ f"set mavlink_port4_extra1_rate = {int(cli_cfg['extra1_rate_hz'])}",
+ f"set mavlink_port4_extra2_rate = {int(cli_cfg['extra2_rate_hz'])}",
+ f"set mavlink_port4_extra3_rate = {int(cli_cfg['extra3_rate_hz'])}",
+ "save",
+ ]
+ return commands
+
+
+def apply_config_and_wait(config: Dict[str, Any], mavlink_port_count: int) -> None:
+ ports = config["ports"]
+ commands = build_cli_config_commands(config, mavlink_port_count)
+ run_cli_commands(
+ "127.0.0.1",
+ int(ports["msp"]),
+ commands,
+ reboot_timeout_s=float(config["tests"]["save_reboot_timeout_s"]),
+ )
+ wait_for_tcp_port("127.0.0.1", int(ports["msp"]), float(config["tests"]["port_ready_timeout_s"]))
+ wait_for_tcp_port("127.0.0.1", int(ports["rc"]), float(config["tests"]["port_ready_timeout_s"]))
+ if mavlink_port_count >= 2:
+ wait_for_tcp_port("127.0.0.1", int(ports["telemetry"][0]), float(config["tests"]["port_ready_timeout_s"]))
+ if mavlink_port_count >= 3:
+ wait_for_tcp_port("127.0.0.1", int(ports["telemetry"][1]), float(config["tests"]["port_ready_timeout_s"]))
+ if mavlink_port_count >= 4:
+ wait_for_tcp_port("127.0.0.1", int(ports["telemetry"][2]), float(config["tests"]["port_ready_timeout_s"]))
+
+
+async def mavsdk_probe(address: str, timeout_s: float) -> Dict[str, Any]:
+ drone = System()
+ result: Dict[str, Any] = {
+ "address": address,
+ "connected": False,
+ "flight_mode": None,
+ }
+ await drone.connect(system_address=address)
+ async with asyncio.timeout(timeout_s):
+ async for state in drone.core.connection_state():
+ if state.is_connected:
+ result["connected"] = True
+ break
+ async with asyncio.timeout(timeout_s):
+ async for flight_mode in drone.telemetry.flight_mode():
+ result["flight_mode"] = str(flight_mode)
+ break
+ return result
+
+
+def probe_mavsdk_sync(address: str, timeout_s: float) -> Dict[str, Any]:
+ return asyncio.run(mavsdk_probe(address, timeout_s))
+
+
+def open_mavlink_tcp_connection(port: int, source_system: int, source_component: int, timeout_s: float) -> Any:
+ deadline = time.monotonic() + timeout_s
+ while True:
+ try:
+ return mavutil.mavlink_connection(
+ f"tcp:127.0.0.1:{port}",
+ source_system=source_system,
+ source_component=source_component,
+ autoreconnect=True,
+ )
+ except OSError:
+ if time.monotonic() >= deadline:
+ raise
+ time.sleep(0.2)
+
+
+def run_workload(
+ config: Dict[str, Any],
+ sitl_pid: int,
+ telemetry_ports: List[int],
+ rc_port: int,
+ load_rates_hz: Dict[int, float],
+ duration_s: float,
+ rc_tx_hz_override: float | None = None,
+) -> Dict[str, Any]:
+ print(
+ f"run_workload_start duration_s={duration_s} telemetry_ports={telemetry_ports} rc_port={rc_port} "
+ f"load_rates_hz={load_rates_hz}",
+ flush=True,
+ )
+ tests_cfg = config["tests"]
+ rc_tx_hz = float(tests_cfg["rc_tx_hz"]) if rc_tx_hz_override is None else float(rc_tx_hz_override)
+ msp_poll_hz = float(tests_cfg["msp_poll_hz"])
+ inav_status_hz = float(tests_cfg.get("inav_status_hz", 1.0))
+ msp_request_timeout_s = float(tests_cfg["msp_request_timeout_s"])
+ command_message_id = int(tests_cfg["stress_command_message_id"])
+ rc_target_system = int(tests_cfg["rc_target_system"])
+ rc_target_component = int(tests_cfg["rc_target_component"])
+ port_ready_timeout_s = float(tests_cfg["port_ready_timeout_s"])
+ warmup_s = float(tests_cfg.get("warmup_s", 3.0))
+ warmup_heartbeat_count = int(tests_cfg.get("warmup_heartbeat_count", 3))
+ warmup_timeout_s = float(tests_cfg.get("warmup_timeout_s", 30.0))
+
+ listeners: Dict[int, Any] = {}
+ targets: Dict[int, Tuple[int, int]] = {}
+ port_stats: Dict[int, Dict[str, Any]] = {}
+ load_senders: Dict[int, Any] = {}
+ load_sent: Dict[int, int] = {}
+ load_next_send: Dict[int, float] = {}
+ msp_success = 0
+ msp_fail = 0
+ rc_sent = 0
+ fc_cpu_load_samples: List[float] = []
+ fc_cycle_time_samples: List[float] = []
+ fc_status_fail = 0
+ fc_status_last_error = ""
+
+ source_base = 170
+ ports_to_open = set(telemetry_ports)
+ ports_to_open.update(load_rates_hz.keys())
+ ports_to_open.add(rc_port)
+ for port in sorted(ports_to_open):
+ wait_for_tcp_port("127.0.0.1", int(port), port_ready_timeout_s)
+
+ for idx, port in enumerate(telemetry_ports):
+ conn = open_mavlink_tcp_connection(
+ port=port,
+ source_system=source_base + idx,
+ source_component=190,
+ timeout_s=port_ready_timeout_s,
+ )
+ listeners[port] = conn
+ targets[port] = (rc_target_system, rc_target_component)
+ port_stats[port] = {
+ "heartbeat_count": 0,
+ "rc_count": 0,
+ "command_ack_total": 0,
+ "command_ack_ok": 0,
+ "mav_msg_count": 0,
+ "mav_seq_lost": 0,
+ "last_seq_by_source": {},
+ }
+
+ for idx, port in enumerate(sorted(load_rates_hz.keys())):
+ if port in listeners:
+ sender = listeners[port]
+ else:
+ sender = open_mavlink_tcp_connection(
+ port=port,
+ source_system=210 + idx,
+ source_component=191,
+ timeout_s=port_ready_timeout_s,
+ )
+ load_senders[port] = sender
+ load_sent[port] = 0
+ load_next_send[port] = time.monotonic()
+ if port not in targets:
+ targets[port] = (rc_target_system, rc_target_component)
+
+ if rc_port in listeners:
+ rc_sender = listeners[rc_port]
+ else:
+ rc_sender = open_mavlink_tcp_connection(
+ port=rc_port,
+ source_system=239,
+ source_component=191,
+ timeout_s=port_ready_timeout_s,
+ )
+ if telemetry_ports:
+ telemetry_target = targets[telemetry_ports[0]]
+ rc_target_system, rc_target_component = telemetry_target
+
+ rc_period_s = 1.0 / rc_tx_hz
+ next_rc_send_t = time.monotonic()
+ heartbeat_period_s = 1.0
+ next_heartbeat_send_t = next_rc_send_t
+
+ warmup_hb_seen: Dict[int, int] = {port: 0 for port in telemetry_ports}
+ warmup_start_t = time.monotonic()
+ warmup_deadline_t = warmup_start_t + warmup_timeout_s
+
+ while True:
+ now = time.monotonic()
+
+ if now >= next_heartbeat_send_t:
+ heartbeat_conns: Dict[int, Any] = {}
+ for conn in listeners.values():
+ heartbeat_conns[id(conn)] = conn
+ for conn in load_senders.values():
+ heartbeat_conns[id(conn)] = conn
+ heartbeat_conns[id(rc_sender)] = rc_sender
+ for conn in heartbeat_conns.values():
+ conn.mav.heartbeat_send(
+ mavutil.mavlink.MAV_TYPE_GCS,
+ mavutil.mavlink.MAV_AUTOPILOT_INVALID,
+ 0,
+ 0,
+ 0,
+ )
+ next_heartbeat_send_t += heartbeat_period_s
+ if next_heartbeat_send_t < now:
+ next_heartbeat_send_t = now + heartbeat_period_s
+
+ if now >= next_rc_send_t:
+ rc_target = targets.get(rc_port)
+ if rc_target is not None:
+ rc_target_system, rc_target_component = rc_target
+ rc_sender.mav.rc_channels_override_send(rc_target_system, rc_target_component, *CHANNELS[:8])
+ next_rc_send_t += rc_period_s
+ if next_rc_send_t < now:
+ next_rc_send_t = now + rc_period_s
+
+ for port, conn in listeners.items():
+ while True:
+ msg = conn.recv_match(blocking=False)
+ if msg is None:
+ break
+ msg_type = msg.get_type()
+ if msg_type == "HEARTBEAT":
+ targets[port] = (int(msg.get_srcSystem()), int(msg.get_srcComponent()))
+ warmup_hb_seen[port] += 1
+
+ if telemetry_ports and all(count >= warmup_heartbeat_count for count in warmup_hb_seen.values()) and (now - warmup_start_t) >= warmup_s:
+ break
+ if (not telemetry_ports) and (now - warmup_start_t) >= warmup_s:
+ break
+ if now >= warmup_deadline_t:
+ raise TimeoutError(
+ f"Warmup failed: heartbeat_counts={warmup_hb_seen} required={warmup_heartbeat_count} timeout_s={warmup_timeout_s}"
+ )
+
+ time.sleep(0.001)
+
+ for stats in port_stats.values():
+ stats["heartbeat_count"] = 0
+ stats["rc_count"] = 0
+ stats["command_ack_total"] = 0
+ stats["command_ack_ok"] = 0
+ stats["mav_msg_count"] = 0
+ stats["mav_seq_lost"] = 0
+ stats["last_seq_by_source"] = {}
+
+ rc_sent = 0
+ measurement_start_t = time.monotonic()
+ next_rc_send_t = measurement_start_t
+ next_heartbeat_send_t = measurement_start_t
+ for port in load_next_send:
+ load_next_send[port] = measurement_start_t
+ next_resource_sample_t = measurement_start_t + (1.0 / inav_status_hz)
+ next_msp_poll_t = measurement_start_t + (1.0 / msp_poll_hz)
+ workload_end_t = measurement_start_t + duration_s
+
+ with MSPApi(tcp_endpoint=f"127.0.0.1:{int(config['ports']['msp'])}") as msp_api:
+ msp_api._serial._max_retries = 1
+ msp_api._serial._reconnect_delay = 0.05
+ while time.monotonic() < workload_end_t:
+ now = time.monotonic()
+
+ if now >= next_heartbeat_send_t:
+ heartbeat_conns: Dict[int, Any] = {}
+ for conn in listeners.values():
+ heartbeat_conns[id(conn)] = conn
+ for conn in load_senders.values():
+ heartbeat_conns[id(conn)] = conn
+ heartbeat_conns[id(rc_sender)] = rc_sender
+ for conn in heartbeat_conns.values():
+ conn.mav.heartbeat_send(
+ mavutil.mavlink.MAV_TYPE_GCS,
+ mavutil.mavlink.MAV_AUTOPILOT_INVALID,
+ 0,
+ 0,
+ 0,
+ )
+ next_heartbeat_send_t += heartbeat_period_s
+ if next_heartbeat_send_t < now:
+ next_heartbeat_send_t = now + heartbeat_period_s
+
+ if now >= next_rc_send_t:
+ rc_target = targets.get(rc_port)
+ if rc_target is not None:
+ rc_target_system, rc_target_component = rc_target
+ rc_sender.mav.rc_channels_override_send(rc_target_system, rc_target_component, *CHANNELS[:8])
+ rc_sent += 1
+ next_rc_send_t += rc_period_s
+ if next_rc_send_t < now:
+ next_rc_send_t = now + rc_period_s
+
+ for port, rate_hz in load_rates_hz.items():
+ next_send_t = load_next_send[port]
+ if now >= next_send_t:
+ target_system, target_component = targets[port]
+ load_senders[port].mav.command_long_send(
+ target_system,
+ target_component,
+ MAV_CMD_REQUEST_MESSAGE,
+ 0,
+ float(command_message_id),
+ 0,
+ 0,
+ 0,
+ 0,
+ 0,
+ 0,
+ )
+ load_sent[port] += 1
+ next_send_t += 1.0 / rate_hz
+ if next_send_t < now:
+ next_send_t = now + (1.0 / rate_hz)
+ load_next_send[port] = next_send_t
+
+ for port, conn in listeners.items():
+ while True:
+ msg = conn.recv_match(blocking=False)
+ if msg is None:
+ break
+ msg_type = msg.get_type()
+ stats = port_stats[port]
+ seq = None
+ if hasattr(msg, "get_seq"):
+ try:
+ seq = int(msg.get_seq())
+ except (TypeError, ValueError):
+ seq = None
+ if seq is None:
+ header = getattr(msg, "_header", None)
+ if header is not None and hasattr(header, "seq"):
+ seq = int(header.seq)
+ if seq is not None:
+ src_key = (int(msg.get_srcSystem()), int(msg.get_srcComponent()))
+ last_seq = stats["last_seq_by_source"].get(src_key)
+ if last_seq is not None:
+ seq_delta = (seq - int(last_seq)) & 0xFF
+ if seq_delta > 0:
+ stats["mav_seq_lost"] += max(seq_delta - 1, 0)
+ stats["last_seq_by_source"][src_key] = seq
+ stats["mav_msg_count"] += 1
+
+ if msg_type == "HEARTBEAT":
+ targets[port] = (int(msg.get_srcSystem()), int(msg.get_srcComponent()))
+ stats["heartbeat_count"] += 1
+ elif msg_type == "RC_CHANNELS":
+ stats["rc_count"] += 1
+ elif msg_type == "COMMAND_ACK":
+ if int(msg.command) == MAV_CMD_REQUEST_MESSAGE:
+ stats["command_ack_total"] += 1
+ if int(msg.result) == int(mavutil.mavlink.MAV_RESULT_ACCEPTED):
+ stats["command_ack_ok"] += 1
+
+ if now >= next_msp_poll_t:
+ try:
+ msp_api._request_raw(InavMSP.MSP_RC, timeout=msp_request_timeout_s)
+ msp_success += 1
+ except (SerialException, RuntimeError, TimeoutError, ConnectionRefusedError, OSError):
+ msp_fail += 1
+ next_msp_poll_t += 1.0 / msp_poll_hz
+
+ if now >= next_resource_sample_t:
+ try:
+ status = msp_api.get_inav_status()
+ fc_cpu_load_samples.append(float(status["cpuLoad"]))
+ fc_cycle_time_samples.append(float(status["cycleTime"]))
+ except (SerialException, RuntimeError, TimeoutError, ConnectionRefusedError, OSError, KeyError, ValueError) as exc:
+ fc_status_fail += 1
+ fc_status_last_error = str(exc)
+ next_resource_sample_t += 1.0 / inav_status_hz
+
+ time.sleep(0.001)
+
+ all_connections: Dict[int, Any] = {}
+ for conn in listeners.values():
+ all_connections[id(conn)] = conn
+ for conn in load_senders.values():
+ all_connections[id(conn)] = conn
+ all_connections[id(rc_sender)] = rc_sender
+ for conn in all_connections.values():
+ conn.close()
+
+ if not fc_cpu_load_samples:
+ raise RuntimeError(f"No MSP2_INAV_STATUS samples collected; last_error={fc_status_last_error} fail_count={fc_status_fail}")
+
+ summarized_ports: Dict[int, Dict[str, Any]] = {}
+ for port in telemetry_ports:
+ stats = port_stats[port]
+ mav_total = int(stats["mav_msg_count"])
+ mav_lost = int(stats["mav_seq_lost"])
+ mav_expected = mav_total + mav_lost
+ sent = load_sent.get(port, 0)
+ ack_total = stats["command_ack_total"]
+ ack_ok = stats["command_ack_ok"]
+ ack_missing = max(sent - ack_total, 0)
+ command_failed_total = max(sent - ack_ok, 0)
+ summarized_ports[port] = {
+ "heartbeat_count": stats["heartbeat_count"],
+ "rc_count": stats["rc_count"],
+ "mav_msg_count": mav_total,
+ "mav_seq_lost": mav_lost,
+ "mav_seq_loss_rate": (mav_lost / mav_expected) if mav_expected > 0 else 0.0,
+ "command_sent": sent,
+ "command_ack_total": ack_total,
+ "command_ack_ok": ack_ok,
+ "command_failed_total": command_failed_total,
+ "command_ack_missing": ack_missing,
+ "command_ack_failure_rate": (command_failed_total / sent) if sent > 0 else 0.0,
+ }
+
+ result = {
+ "duration_s": duration_s,
+ "ports": summarized_ports,
+ "msp_success": msp_success,
+ "msp_fail": msp_fail,
+ "rc_sent": rc_sent,
+ "rc_sent_hz": (rc_sent / max(duration_s, 1e-6)),
+ "msp_failure_rate": (msp_fail / max(msp_success + msp_fail, 1)),
+ "fc_cpu_load_avg_pct": (sum(fc_cpu_load_samples) / len(fc_cpu_load_samples)) if fc_cpu_load_samples else 0.0,
+ "fc_cpu_load_max_pct": max(fc_cpu_load_samples) if fc_cpu_load_samples else 0.0,
+ "fc_cycle_time_avg_us": (sum(fc_cycle_time_samples) / len(fc_cycle_time_samples)) if fc_cycle_time_samples else 0.0,
+ "fc_cycle_time_max_us": max(fc_cycle_time_samples) if fc_cycle_time_samples else 0.0,
+ "fc_status_samples": len(fc_cpu_load_samples),
+ }
+ print(
+ f"run_workload_done duration_s={duration_s} fc_cpu_load_avg_pct={result['fc_cpu_load_avg_pct']:.2f} "
+ f"msp_fail_rate={result['msp_failure_rate']:.4f}",
+ flush=True,
+ )
+ return result
+
+
+def format_port_table(port_result: Dict[int, Dict[str, Any]]) -> str:
+ if not port_result:
+ return "_No MAVLink telemetry ports active in this scenario._"
+
+ lines = [
+ "| Port | MAV Msg Count | MAV Seq Lost | MAV Seq Loss % | HB Count | RC_CHANNELS Count | Cmd Sent | Cmd Ack OK | Cmd Failed Total | Cmd Missing Ack |",
+ "| --- | ---: | ---: | ---: | ---: | ---: | ---: | ---: | ---: | ---: |",
+ ]
+ for port in sorted(port_result.keys()):
+ data = port_result[port]
+ lines.append(
+ "| "
+ f"{port} | {data['mav_msg_count']} | {data['mav_seq_lost']} | {(data['mav_seq_loss_rate'] * 100.0):.2f}% | "
+ f"{data['heartbeat_count']} | {data['rc_count']} | {data['command_sent']} | "
+ f"{data['command_ack_ok']} | {data['command_failed_total']} | {data['command_ack_missing']} |"
+ )
+ return "\n".join(lines)
+
+
+def summarize_command_failures(port_result: Dict[int, Dict[str, Any]]) -> Dict[str, float]:
+ sent_total = sum(int(item["command_sent"]) for item in port_result.values())
+ failed_total = sum(int(item["command_failed_total"]) for item in port_result.values())
+ missing_ack_total = sum(int(item["command_ack_missing"]) for item in port_result.values())
+ mav_seq_lost_total = sum(int(item["mav_seq_lost"]) for item in port_result.values())
+ mav_msg_total = sum(int(item["mav_msg_count"]) for item in port_result.values())
+ mav_seq_loss_pct = (mav_seq_lost_total / max(mav_seq_lost_total + mav_msg_total, 1)) * 100.0
+ return {
+ "sent_total": float(sent_total),
+ "failed_total": float(failed_total),
+ "failed_pct": (failed_total / max(sent_total, 1)) * 100.0,
+ "missing_ack_total": float(missing_ack_total),
+ "mav_seq_loss_pct": mav_seq_loss_pct,
+ }
+
+
+def write_testing_report(config: Dict[str, Any], report: Dict[str, Any]) -> None:
+ out_path = Path(config["output"]["testing_md"])
+ timestamp = datetime.now(timezone.utc).isoformat()
+ lines: List[str] = []
+ lines.append("# MAVLink Multiport Testing")
+ lines.append("")
+ lines.append(f"- Generated: `{timestamp}`")
+ lines.append(f"- Conda env: `drone`")
+ lines.append(f"- SITL binary: `{config['sitl']['binary']}`")
+ lines.append(f"- EEPROM: `{config['sitl']['eeprom_path']}`")
+ lines.append("- MSP kept on UART1 by design (`serial 0 ... functionMask=1`).")
+ lines.append("- CLI under test sets `receiver_type=SERIAL` and `serialrx_provider=MAVLINK`.")
+ lines.append("- `RC_CHANNELS` metrics below are MAVLink telemetry stream metrics, not RX input ownership.")
+ lines.append("")
+ lines.append("## MAVSDK Probe")
+ lines.append("")
+ lines.append("| Address | Connected | Flight Mode |")
+ lines.append("| --- | --- | --- |")
+ if report["mavsdk_probes"]:
+ for probe in report["mavsdk_probes"]:
+ lines.append(f"| {probe['address']} | {probe['connected']} | {probe['flight_mode']} |")
+ else:
+ lines.append("| _skipped_ | _skipped_ | _skipped_ |")
+ lines.append("")
+ lines.append("## Port Count Baseline (1 RC, then +Telemetry ports)")
+ lines.append("")
+ for label, result in report["baseline"].items():
+ cmd_summary = summarize_command_failures(result["ports"])
+ lines.append(f"### {label}")
+ lines.append("")
+ lines.append(
+ f"- Duration: `{result['duration_s']}s` | FC cpuLoad avg/max: `{result['fc_cpu_load_avg_pct']:.2f}% / {result['fc_cpu_load_max_pct']:.2f}%` | "
+ f"FC cycleTime avg/max: `{result['fc_cycle_time_avg_us']:.1f} / {result['fc_cycle_time_max_us']:.1f}` us | "
+ f"Status samples: `{result['fc_status_samples']}`"
+ )
+ lines.append(
+ f"- MSP success/fail: `{result['msp_success']}/{result['msp_fail']}` | MSP failure rate: `{(result['msp_failure_rate'] * 100.0):.2f}%`"
+ )
+ lines.append(
+ f"- Commands sent/failed: `{int(cmd_summary['sent_total'])}/{int(cmd_summary['failed_total'])}` (`{cmd_summary['failed_pct']:.2f}%`) | "
+ f"Missing ACK: `{int(cmd_summary['missing_ack_total'])}` | MAVLink seq loss: `{cmd_summary['mav_seq_loss_pct']:.2f}%`"
+ )
+ lines.append(f"- RC override send rate: `{result['rc_sent_hz']:.2f} Hz` (`{result['rc_sent']}` packets)")
+ lines.append("")
+ lines.append(format_port_table(result["ports"]))
+ lines.append("")
+ lines.append("## Stress Test: Progressive Overload On One MAVLink Port")
+ lines.append("")
+ for item in report["single_port_stress"]:
+ rate = item["rate_hz"]
+ result = item["result"]
+ cmd_summary = summarize_command_failures(result["ports"])
+ lines.append(f"### Load Rate `{rate} req/s` on telemetry port")
+ lines.append("")
+ lines.append(
+ f"- Duration: `{result['duration_s']}s` | FC cpuLoad avg/max: `{result['fc_cpu_load_avg_pct']:.2f}% / {result['fc_cpu_load_max_pct']:.2f}%` | "
+ f"FC cycleTime avg/max: `{result['fc_cycle_time_avg_us']:.1f} / {result['fc_cycle_time_max_us']:.1f}` us | "
+ f"Status samples: `{result['fc_status_samples']}`"
+ )
+ lines.append(
+ f"- MSP success/fail: `{result['msp_success']}/{result['msp_fail']}` | MSP failure rate: `{(result['msp_failure_rate'] * 100.0):.2f}%`"
+ )
+ lines.append(
+ f"- Commands sent/failed: `{int(cmd_summary['sent_total'])}/{int(cmd_summary['failed_total'])}` (`{cmd_summary['failed_pct']:.2f}%`) | "
+ f"Missing ACK: `{int(cmd_summary['missing_ack_total'])}` | MAVLink seq loss: `{cmd_summary['mav_seq_loss_pct']:.2f}%`"
+ )
+ lines.append(f"- RC override send rate: `{result['rc_sent_hz']:.2f} Hz` (`{result['rc_sent']}` packets)")
+ lines.append("")
+ lines.append(format_port_table(result["ports"]))
+ lines.append("")
+ max_result = report["all_ports_max"]
+ cmd_summary = summarize_command_failures(max_result["ports"])
+ max_ports = len(max_result["ports"])
+ lines.append(f"## Stress Test: All {max_ports} MAVLink Ports At Max Load")
+ lines.append("")
+ lines.append(
+ f"- Duration: `{max_result['duration_s']}s` | FC cpuLoad avg/max: `{max_result['fc_cpu_load_avg_pct']:.2f}% / {max_result['fc_cpu_load_max_pct']:.2f}%` | "
+ f"FC cycleTime avg/max: `{max_result['fc_cycle_time_avg_us']:.1f} / {max_result['fc_cycle_time_max_us']:.1f}` us | "
+ f"Status samples: `{max_result['fc_status_samples']}`"
+ )
+ lines.append(
+ f"- MSP success/fail: `{max_result['msp_success']}/{max_result['msp_fail']}` | MSP failure rate: `{(max_result['msp_failure_rate'] * 100.0):.2f}%`"
+ )
+ lines.append(
+ f"- Commands sent/failed: `{int(cmd_summary['sent_total'])}/{int(cmd_summary['failed_total'])}` (`{cmd_summary['failed_pct']:.2f}%`) | "
+ f"Missing ACK: `{int(cmd_summary['missing_ack_total'])}` | MAVLink seq loss: `{cmd_summary['mav_seq_loss_pct']:.2f}%`"
+ )
+ lines.append(f"- RC override send rate: `{max_result['rc_sent_hz']:.2f} Hz` (`{max_result['rc_sent']}` packets)")
+ lines.append("")
+ lines.append(format_port_table(max_result["ports"]))
+ lines.append("")
+ out_path.write_text("\n".join(lines) + "\n", encoding="utf-8")
+
+
+if __name__ == "__main__":
+ parser = argparse.ArgumentParser(description="Run MAVLink multiport RC/telemetry/stress benchmark and write TESTING.md")
+ parser.add_argument("--config", default=str(DEFAULT_CONFIG_PATH), help="YAML configuration path")
+ args = parser.parse_args()
+
+ config_path = Path(args.config)
+ config = load_config(config_path)
+
+ sitl_bin = Path(config["sitl"]["binary"])
+ sitl_workdir = Path(config["sitl"]["workdir"])
+ sitl_eeprom = str(config["sitl"]["eeprom_path"])
+ sitl_log = Path(config["sitl"]["runtime_log"])
+ sitl_log.parent.mkdir(parents=True, exist_ok=True)
+ log_handle = sitl_log.open("w", encoding="utf-8")
+ sitl_proc = subprocess.Popen(
+ [str(sitl_bin), f"--path={sitl_eeprom}"],
+ cwd=str(sitl_workdir),
+ stdout=log_handle,
+ stderr=subprocess.STDOUT,
+ text=True,
+ )
+
+ report: Dict[str, Any] = {
+ "mavsdk_probes": [],
+ "baseline": {},
+ "single_port_stress": [],
+ "all_ports_max": {},
+ }
+
+ try:
+ wait_for_tcp_port("127.0.0.1", int(config["ports"]["msp"]), float(config["tests"]["port_ready_timeout_s"]))
+
+ configured_port_count = 1 + len(config["ports"]["telemetry"])
+ print(f"single_config_start count={configured_port_count}", flush=True)
+ apply_config_and_wait(config, configured_port_count)
+ print(f"single_config_done count={configured_port_count}", flush=True)
+
+ baseline_scenarios: List[Tuple[str, List[int]]] = []
+ rc_port = int(config["ports"]["rc"])
+ telemetry_ports = [int(port) for port in config["ports"]["telemetry"]]
+ for count in range(1, configured_port_count + 1):
+ baseline_scenarios.append((f"{count} MAVLink port(s)", [rc_port] + telemetry_ports[: max(0, count - 1)]))
+ for label, active_telemetry_ports in baseline_scenarios:
+ print(f"baseline_run_start label={label} ports={active_telemetry_ports}", flush=True)
+ result = run_workload(
+ config=config,
+ sitl_pid=sitl_proc.pid,
+ telemetry_ports=active_telemetry_ports,
+ rc_port=int(config["ports"]["rc"]),
+ load_rates_hz={},
+ duration_s=float(config["tests"]["baseline_duration_s"]),
+ )
+ report["baseline"][label] = result
+ print(f"baseline_run_done label={label}", flush=True)
+
+ if bool(config["tests"].get("run_mavsdk_probe", True)):
+ print("mavsdk_probe_start", flush=True)
+ mavsdk_probe_ports = [int(config["ports"]["rc"])] + [int(p) for p in config["ports"]["telemetry"]]
+ for port in mavsdk_probe_ports:
+ probe = probe_mavsdk_sync(f"tcp://127.0.0.1:{port}", float(config["tests"]["mavsdk_probe_timeout_s"]))
+ report["mavsdk_probes"].append(probe)
+ print("mavsdk_probe_done", flush=True)
+ else:
+ print("mavsdk_probe_skipped", flush=True)
+
+ stress_port = int(config["ports"]["telemetry"][0])
+ active_telemetry_ports = [int(config["ports"]["rc"])] + [int(port) for port in config["ports"]["telemetry"]]
+ for rate in config["tests"]["progressive_rates_hz"]:
+ print(f"single_port_stress_start rate={rate}", flush=True)
+ result = run_workload(
+ config=config,
+ sitl_pid=sitl_proc.pid,
+ telemetry_ports=active_telemetry_ports,
+ rc_port=int(config["ports"]["rc"]),
+ load_rates_hz={stress_port: float(rate)},
+ duration_s=float(config["tests"]["stress_duration_s"]),
+ )
+ report["single_port_stress"].append({"rate_hz": rate, "result": result})
+
+ print("all_ports_max_start", flush=True)
+ max_rate = float(config["tests"]["max_rate_hz"])
+ max_loads = {port: max_rate for port in active_telemetry_ports}
+ result = run_workload(
+ config=config,
+ sitl_pid=sitl_proc.pid,
+ telemetry_ports=active_telemetry_ports,
+ rc_port=int(config["ports"]["rc"]),
+ load_rates_hz=max_loads,
+ duration_s=float(config["tests"]["all_ports_max_duration_s"]),
+ )
+ report["all_ports_max"] = result
+ print("all_ports_max_done", flush=True)
+
+ write_testing_report(config, report)
+ print(f"report_written={config['output']['testing_md']}")
+ finally:
+ sitl_proc.terminate()
+ try:
+ sitl_proc.wait(timeout=5.0)
+ except subprocess.TimeoutExpired:
+ sitl_proc.kill()
+ sitl_proc.wait(timeout=5.0)
+ log_handle.close()
diff --git a/src/utils/mavlink_tests/mav_multi_sweep.py b/src/utils/mavlink_tests/mav_multi_sweep.py
new file mode 100644
index 00000000000..0915e1a1485
--- /dev/null
+++ b/src/utils/mavlink_tests/mav_multi_sweep.py
@@ -0,0 +1,152 @@
+#!/usr/bin/env python3
+"""
+Usage:
+ conda run -n drone python src/utils/mavlink_tests/mav_multi_sweep.py
+ conda run -n drone python src/utils/mavlink_tests/mav_multi_sweep.py --config src/utils/mavlink_tests/test_config_multiport4_sweep_rc460800_tele115200.yaml
+"""
+
+from __future__ import annotations
+
+import argparse
+import importlib.util
+import subprocess
+from datetime import datetime, timezone
+from pathlib import Path
+from typing import Any, Dict, List, Tuple
+
+import yaml
+
+
+TESTS_DIR = Path(__file__).resolve().parent
+DEFAULT_CONFIG_PATH = TESTS_DIR / "test_config_multiport4_sweep_rc460800_tele115200.yaml"
+BENCHMARK_MODULE_PATH = TESTS_DIR / "mav_multi_benchmark.py"
+
+spec = importlib.util.spec_from_file_location("mav_multi_benchmark", BENCHMARK_MODULE_PATH)
+benchmark = importlib.util.module_from_spec(spec)
+assert spec is not None
+assert spec.loader is not None
+spec.loader.exec_module(benchmark)
+
+
+parser = argparse.ArgumentParser(description="Run MAVLink load sweep table for 1..4 ports and [50,100,200,max] req/s")
+parser.add_argument("--config", default=str(DEFAULT_CONFIG_PATH), help="YAML configuration path")
+args = parser.parse_args()
+
+config_path = Path(args.config)
+config: Dict[str, Any] = yaml.safe_load(config_path.read_text(encoding="utf-8"))
+
+sitl_bin = Path(config["sitl"]["binary"])
+sitl_workdir = Path(config["sitl"]["workdir"])
+sitl_eeprom = str(config["sitl"]["eeprom_path"])
+sitl_log = Path(config["sitl"]["runtime_log"])
+sitl_log.parent.mkdir(parents=True, exist_ok=True)
+
+rate_labels: List[Tuple[str, float]] = [
+ ("50", 50.0),
+ ("100", 100.0),
+ ("200", 200.0),
+ ("max", float(config["tests"]["max_rate_hz"])),
+]
+
+results: Dict[str, Dict[int, Dict[str, Any]]] = {}
+
+rc_port = int(config["ports"]["rc"])
+telemetry_ports = [int(port) for port in config["ports"]["telemetry"]]
+sweep_duration_s = float(config["tests"]["sweep_duration_s"])
+
+rate_cache: Dict[float, Dict[int, Dict[str, Any]]] = {}
+
+for label, rate_hz in rate_labels:
+ if rate_hz not in rate_cache:
+ rate_cache[rate_hz] = {}
+ for port_count in range(1, 5):
+ scenario_log = sitl_log.with_name(f"{sitl_log.stem}_{label}_{port_count}{sitl_log.suffix}")
+ log_handle = scenario_log.open("w", encoding="utf-8")
+ sitl_proc = subprocess.Popen(
+ [str(sitl_bin), f"--path={sitl_eeprom}"],
+ cwd=str(sitl_workdir),
+ stdout=log_handle,
+ stderr=subprocess.STDOUT,
+ text=True,
+ )
+ try:
+ benchmark.wait_for_tcp_port("127.0.0.1", int(config["ports"]["msp"]), float(config["tests"]["port_ready_timeout_s"]))
+ benchmark.apply_config_and_wait(config, 4)
+ active_ports = [rc_port] + telemetry_ports[: max(0, port_count - 1)]
+ load_rates_hz = {port: rate_hz for port in active_ports}
+ print(f"sweep_run_start label={label} rate={rate_hz} ports={port_count}", flush=True)
+ result = benchmark.run_workload(
+ config=config,
+ sitl_pid=sitl_proc.pid,
+ telemetry_ports=active_ports,
+ rc_port=rc_port,
+ load_rates_hz=load_rates_hz,
+ duration_s=sweep_duration_s,
+ )
+ rate_cache[rate_hz][port_count] = result
+ print(f"sweep_run_done label={label} rate={rate_hz} ports={port_count}", flush=True)
+ finally:
+ sitl_proc.terminate()
+ try:
+ sitl_proc.wait(timeout=5.0)
+ except subprocess.TimeoutExpired:
+ sitl_proc.kill()
+ sitl_proc.wait(timeout=5.0)
+ log_handle.close()
+ scenario_log.unlink(missing_ok=True)
+ results[label] = rate_cache[rate_hz]
+
+output_path = Path(config["output"]["testing_md"])
+lines: List[str] = [
+ "# MAVLink Port Load Sweep",
+ "",
+ f"- Generated: `{datetime.now(timezone.utc).isoformat()}`",
+ f"- SITL binary: `{config['sitl']['binary']}`",
+ f"- EEPROM: `{config['sitl']['eeprom_path']}`",
+ "- UART1 MSP only.",
+ "- UART2 is MAVLink RC (460800), RC override target is 100 Hz.",
+ "- Additional MAVLink telemetry ports are 115200 baud.",
+ "",
+ "## Comparison Table",
+ "",
+ "| Load Label | Msg/s per active port | Active MAVLink ports | FC cpuLoad avg/max | FC cycleTime avg/max (us) | MAV seq loss max | Cmd failed total | Cmd failed % | MSP fail % |",
+ "| --- | ---: | ---: | --- | --- | ---: | ---: | ---: | ---: |",
+]
+
+for label, rate_hz in rate_labels:
+ rate_results = results[label]
+ for port_count in range(1, 5):
+ result = rate_results[port_count]
+ per_port = list(result["ports"].values())
+ mav_seq_loss_max_pct = max(item["mav_seq_loss_rate"] * 100.0 for item in per_port)
+ cmd_sent_total = sum(int(item["command_sent"]) for item in per_port)
+ cmd_failed_total = sum(int(item["command_failed_total"]) for item in per_port)
+ cmd_failed_pct = (cmd_failed_total / max(cmd_sent_total, 1)) * 100.0
+ lines.append(
+ f"| {label} | {rate_hz:.1f} | {port_count} | "
+ f"{result['fc_cpu_load_avg_pct']:.2f}% / {result['fc_cpu_load_max_pct']:.2f}% | "
+ f"{result['fc_cycle_time_avg_us']:.1f} / {result['fc_cycle_time_max_us']:.1f} | "
+ f"{mav_seq_loss_max_pct:.2f}% | {cmd_failed_total} | {cmd_failed_pct:.2f}% | {(result['msp_failure_rate'] * 100.0):.2f}% |"
+ )
+
+lines.append("")
+lines.append("## Raw Scenario Details")
+lines.append("")
+for label, rate_hz in rate_labels:
+ lines.append(f"### {label} ({rate_hz:.1f} msg/s per active port)")
+ lines.append("")
+ for port_count in range(1, 5):
+ result = results[label][port_count]
+ lines.append(f"#### {port_count} active MAVLink port(s)")
+ lines.append("")
+ lines.append(
+ f"- FC cpuLoad avg/max: `{result['fc_cpu_load_avg_pct']:.2f}% / {result['fc_cpu_load_max_pct']:.2f}%` | "
+ f"FC cycleTime avg/max: `{result['fc_cycle_time_avg_us']:.1f} / {result['fc_cycle_time_max_us']:.1f}` us | "
+ f"MSP fail rate: `{(result['msp_failure_rate'] * 100.0):.2f}%`"
+ )
+ lines.append("")
+ lines.append(benchmark.format_port_table(result["ports"]))
+ lines.append("")
+
+output_path.write_text("\n".join(lines) + "\n", encoding="utf-8")
+print(f"report_written={output_path}", flush=True)
diff --git a/src/utils/mavlink_tests/mavlink_routing_compliance_test.py b/src/utils/mavlink_tests/mavlink_routing_compliance_test.py
new file mode 100644
index 00000000000..e202e649af8
--- /dev/null
+++ b/src/utils/mavlink_tests/mavlink_routing_compliance_test.py
@@ -0,0 +1,499 @@
+#!/usr/bin/env python3
+"""
+Usage:
+ conda run -n drone python mydev/branch/mav_multi/mavlink_routing_compliance_test.py --config mydev/branch/mav_multi/routing_test_config.yaml
+"""
+
+from __future__ import annotations
+
+import argparse
+import math
+import time
+from pathlib import Path
+from typing import Any, Dict, List
+
+import yaml
+from pymavlink import mavutil
+
+
+MAV_AUTOPILOT_INVALID = int(mavutil.mavlink.MAV_AUTOPILOT_INVALID)
+MAV_MODE_FLAG_CUSTOM_MODE_ENABLED = int(mavutil.mavlink.MAV_MODE_FLAG_CUSTOM_MODE_ENABLED)
+MAV_STATE_ACTIVE = int(mavutil.mavlink.MAV_STATE_ACTIVE)
+MAV_TYPE_GCS = int(mavutil.mavlink.MAV_TYPE_GCS)
+
+ROUTING_RULE_REFERENCES = {
+ "broadcast_forward": "routing.md:25-27,48-49",
+ "known_target_forward": "routing.md:49-50; MAVLink_routing.cpp:66-80",
+ "unknown_target_blocked": "routing.md:26-27,53",
+ "no_ingress_loop": "MAVLink_routing.cpp:197-209",
+ "no_repack": "routing.md:29-31",
+}
+
+
+def load_config(config_path: Path) -> Dict[str, Any]:
+ return yaml.safe_load(config_path.read_text(encoding="utf-8"))
+
+
+def open_mavlink_connection(endpoint: str, source_system: int, source_component: int, timeout_s: float) -> Any:
+ deadline = time.monotonic() + timeout_s
+ while True:
+ try:
+ return mavutil.mavlink_connection(
+ endpoint,
+ source_system=source_system,
+ source_component=source_component,
+ autoreconnect=True,
+ )
+ except OSError as error:
+ if time.monotonic() >= deadline:
+ raise TimeoutError(
+ f"endpoint={endpoint} source_system={source_system} source_component={source_component} timeout_s={timeout_s}"
+ ) from error
+ time.sleep(0.2)
+
+
+def set_source_identity(connection: Any, system_id: int, component_id: int) -> None:
+ connection.mav.srcSystem = system_id
+ connection.mav.srcComponent = component_id
+
+
+def send_heartbeat(connection: Any, system_id: int, component_id: int, mav_type: int) -> None:
+ set_source_identity(connection, system_id, component_id)
+ connection.mav.heartbeat_send(
+ mav_type,
+ MAV_AUTOPILOT_INVALID,
+ MAV_MODE_FLAG_CUSTOM_MODE_ENABLED,
+ 0,
+ MAV_STATE_ACTIVE,
+ )
+
+
+def drain_link(connection: Any, duration_s: float) -> None:
+ deadline = time.monotonic() + duration_s
+ while time.monotonic() < deadline:
+ message = connection.recv_match(blocking=False)
+ if message is None:
+ time.sleep(0.002)
+
+
+def drain_all_links(connections: Dict[str, Any], duration_s: float) -> None:
+ for connection in connections.values():
+ drain_link(connection, duration_s)
+
+
+def collect_command_observations(connections: Dict[str, Any], command_id: int, observation_window_s: float) -> Dict[str, List[Dict[str, Any]]]:
+ observations: Dict[str, List[Dict[str, Any]]] = {link_name: [] for link_name in connections}
+ deadline = time.monotonic() + observation_window_s
+ while time.monotonic() < deadline:
+ saw_message = False
+ for link_name, connection in connections.items():
+ while True:
+ message = connection.recv_match(type=["COMMAND_LONG"], blocking=False)
+ if message is None:
+ break
+ if int(message.command) != command_id:
+ continue
+ observations[link_name].append(
+ {
+ "src_system": int(message.get_srcSystem()),
+ "src_component": int(message.get_srcComponent()),
+ "target_system": int(message.target_system),
+ "target_component": int(message.target_component),
+ "command": int(message.command),
+ "confirmation": int(message.confirmation),
+ "params": [
+ float(message.param1),
+ float(message.param2),
+ float(message.param3),
+ float(message.param4),
+ float(message.param5),
+ float(message.param6),
+ float(message.param7),
+ ],
+ }
+ )
+ saw_message = True
+ if not saw_message:
+ time.sleep(0.002)
+ return observations
+
+
+if __name__ == "__main__":
+ parser = argparse.ArgumentParser(description="Run MAVLink routing compliance checks against INAV multiport routing.")
+ parser.add_argument("--config", required=True, type=Path, help="YAML config path")
+ args = parser.parse_args()
+
+ config = load_config(args.config)
+ timing = config["timing"]
+ network = config["network"]
+ tests = config["tests"]
+ components_cfg = config["components"]
+ vehicle = config["vehicle"]
+
+ gcs_link_name = network["gcs_link"]
+ fc_system_id = int(vehicle["fc_system_id"])
+ unknown_component_id = int(tests["unknown_component_id"])
+ unknown_system_id = int(tests["unknown_system_id"])
+ marker_command_base = int(tests["marker_command_base"])
+ report_path = Path(tests["report_markdown"])
+
+ link_cfgs = network["links"]
+ if gcs_link_name not in link_cfgs:
+ raise ValueError(f"gcs_link={gcs_link_name} missing from network.links")
+
+ components: List[Dict[str, Any]] = []
+ for component in components_cfg:
+ if component["link"] not in link_cfgs:
+ raise ValueError(f"component={component['name']} link={component['link']} missing from network.links")
+ components.append(
+ {
+ "name": component["name"],
+ "link": component["link"],
+ "system_id": int(component["system_id"]),
+ "component_id": int(component["component_id"]),
+ "mav_type": int(component["mav_type"]),
+ }
+ )
+
+ component_ids = {component["component_id"] for component in components}
+ component_system_ids = {component["system_id"] for component in components}
+ if unknown_component_id in component_ids:
+ raise ValueError(f"unknown_component_id={unknown_component_id} collides with configured component IDs")
+ if unknown_system_id in component_system_ids or unknown_system_id == fc_system_id:
+ raise ValueError(f"unknown_system_id={unknown_system_id} collides with configured systems")
+
+ gcs_actor = {
+ "name": "gcs",
+ "link": gcs_link_name,
+ "system_id": int(link_cfgs[gcs_link_name]["source_system"]),
+ "component_id": int(link_cfgs[gcs_link_name]["source_component"]),
+ "mav_type": MAV_TYPE_GCS,
+ }
+
+ inter_source = components[0]
+ inter_target = None
+ for component in components:
+ if component["link"] != inter_source["link"]:
+ inter_target = component
+ break
+ if inter_target is None:
+ raise ValueError("Need at least one component on a different link for inter-component routing test")
+
+ connections: Dict[str, Any] = {}
+ fc_heartbeats: Dict[str, Dict[str, int]] = {}
+
+ try:
+ for link_name, link_cfg in link_cfgs.items():
+ connection = open_mavlink_connection(
+ endpoint=link_cfg["endpoint"],
+ source_system=int(link_cfg["source_system"]),
+ source_component=int(link_cfg["source_component"]),
+ timeout_s=float(timing["connect_timeout_s"]),
+ )
+ connections[link_name] = connection
+
+ for link_name, connection in connections.items():
+ heartbeat = connection.wait_heartbeat(timeout=float(timing["connect_timeout_s"]))
+ if heartbeat is None:
+ raise TimeoutError(f"link={link_name} wait_heartbeat timed out")
+ fc_heartbeats[link_name] = {
+ "system_id": int(heartbeat.get_srcSystem()),
+ "component_id": int(heartbeat.get_srcComponent()),
+ }
+ print(
+ f"fc_heartbeat link={link_name} system_id={fc_heartbeats[link_name]['system_id']} "
+ f"component_id={fc_heartbeats[link_name]['component_id']}",
+ flush=True,
+ )
+
+ time.sleep(float(timing["settle_after_connect_s"]))
+ drain_all_links(connections, float(timing["drain_window_s"]))
+
+ send_heartbeat(
+ connections[gcs_actor["link"]],
+ gcs_actor["system_id"],
+ gcs_actor["component_id"],
+ gcs_actor["mav_type"],
+ )
+ for component in components:
+ send_heartbeat(
+ connections[component["link"]],
+ component["system_id"],
+ component["component_id"],
+ component["mav_type"],
+ )
+ print(
+ f"route_learn_heartbeat component={component['name']} link={component['link']} "
+ f"system_id={component['system_id']} component_id={component['component_id']} mav_type={component['mav_type']}",
+ flush=True,
+ )
+ time.sleep(float(timing["route_learn_settle_s"]))
+ drain_all_links(connections, float(timing["drain_window_s"]))
+
+ cases: List[Dict[str, Any]] = []
+ all_other_than_gcs = sorted([link_name for link_name in connections if link_name != gcs_link_name])
+
+ cases.append(
+ {
+ "name": "gcs_broadcast",
+ "source": gcs_actor,
+ "target_system": 0,
+ "target_component": 0,
+ "expected_links": all_other_than_gcs,
+ "rules": [ROUTING_RULE_REFERENCES["broadcast_forward"], ROUTING_RULE_REFERENCES["no_ingress_loop"]],
+ }
+ )
+
+ cases.append(
+ {
+ "name": "gcs_target_local_system_component_broadcast",
+ "source": gcs_actor,
+ "target_system": fc_system_id,
+ "target_component": 0,
+ "expected_links": all_other_than_gcs,
+ "rules": [ROUTING_RULE_REFERENCES["broadcast_forward"], ROUTING_RULE_REFERENCES["no_ingress_loop"]],
+ }
+ )
+
+ for component in components:
+ expected_links = [component["link"]]
+ if component["link"] == gcs_link_name:
+ expected_links = []
+ cases.append(
+ {
+ "name": f"gcs_target_{component['name']}",
+ "source": gcs_actor,
+ "target_system": component["system_id"],
+ "target_component": component["component_id"],
+ "expected_links": sorted(expected_links),
+ "rules": [ROUTING_RULE_REFERENCES["known_target_forward"], ROUTING_RULE_REFERENCES["no_ingress_loop"]],
+ }
+ )
+
+ cases.append(
+ {
+ "name": "gcs_target_unknown_component",
+ "source": gcs_actor,
+ "target_system": fc_system_id,
+ "target_component": unknown_component_id,
+ "expected_links": [],
+ "rules": [ROUTING_RULE_REFERENCES["unknown_target_blocked"]],
+ }
+ )
+
+ cases.append(
+ {
+ "name": "gcs_target_unknown_system",
+ "source": gcs_actor,
+ "target_system": unknown_system_id,
+ "target_component": 1,
+ "expected_links": [],
+ "rules": [ROUTING_RULE_REFERENCES["unknown_target_blocked"]],
+ }
+ )
+
+ component_broadcast_expected = sorted([link_name for link_name in connections if link_name != inter_source["link"]])
+ cases.append(
+ {
+ "name": f"{inter_source['name']}_broadcast",
+ "source": inter_source,
+ "target_system": 0,
+ "target_component": 0,
+ "expected_links": component_broadcast_expected,
+ "rules": [ROUTING_RULE_REFERENCES["broadcast_forward"], ROUTING_RULE_REFERENCES["no_ingress_loop"]],
+ }
+ )
+
+ cases.append(
+ {
+ "name": f"{inter_source['name']}_to_{inter_target['name']}",
+ "source": inter_source,
+ "target_system": inter_target["system_id"],
+ "target_component": inter_target["component_id"],
+ "expected_links": [inter_target["link"]],
+ "rules": [ROUTING_RULE_REFERENCES["known_target_forward"], ROUTING_RULE_REFERENCES["no_ingress_loop"]],
+ }
+ )
+
+ cases.append(
+ {
+ "name": f"{inter_source['name']}_to_gcs",
+ "source": inter_source,
+ "target_system": gcs_actor["system_id"],
+ "target_component": gcs_actor["component_id"],
+ "expected_links": [gcs_actor["link"]],
+ "rules": [ROUTING_RULE_REFERENCES["known_target_forward"], ROUTING_RULE_REFERENCES["no_ingress_loop"]],
+ }
+ )
+
+ if marker_command_base + len(cases) > 65535:
+ raise ValueError(f"marker_command_base={marker_command_base} too high for case_count={len(cases)}")
+
+ results: List[Dict[str, Any]] = []
+ for case_index, case in enumerate(cases, start=1):
+ drain_all_links(connections, float(timing["drain_window_s"]))
+ command_id = marker_command_base + case_index
+ confirmation = case_index % 256
+ params = [
+ float(1000 + case_index),
+ float(2000 + case_index),
+ float(3000 + case_index),
+ float(4000 + case_index),
+ float(5000 + case_index),
+ float(6000 + case_index),
+ float(7000 + case_index),
+ ]
+
+ source = case["source"]
+ source_connection = connections[source["link"]]
+ set_source_identity(source_connection, source["system_id"], source["component_id"])
+ source_connection.mav.command_long_send(
+ int(case["target_system"]),
+ int(case["target_component"]),
+ command_id,
+ confirmation,
+ params[0],
+ params[1],
+ params[2],
+ params[3],
+ params[4],
+ params[5],
+ params[6],
+ )
+
+ observations = collect_command_observations(
+ connections=connections,
+ command_id=command_id,
+ observation_window_s=float(timing["observation_window_s"]),
+ )
+ observed_links = sorted([link_name for link_name, msgs in observations.items() if len(msgs) > 0])
+ expected_links = sorted(case["expected_links"])
+ no_ingress_loop = source["link"] not in observed_links
+ routing_match = observed_links == expected_links
+
+ payload_intact = True
+ payload_issues: List[str] = []
+ for link_name, messages in observations.items():
+ for message in messages:
+ if message["src_system"] != int(source["system_id"]) or message["src_component"] != int(source["component_id"]):
+ payload_intact = False
+ payload_issues.append(
+ f"link={link_name} src_mismatch expected=({source['system_id']},{source['component_id']}) "
+ f"observed=({message['src_system']},{message['src_component']})"
+ )
+ if message["target_system"] != int(case["target_system"]) or message["target_component"] != int(case["target_component"]):
+ payload_intact = False
+ payload_issues.append(
+ f"link={link_name} target_mismatch expected=({case['target_system']},{case['target_component']}) "
+ f"observed=({message['target_system']},{message['target_component']})"
+ )
+ if message["command"] != command_id or message["confirmation"] != confirmation:
+ payload_intact = False
+ payload_issues.append(
+ f"link={link_name} cmd_mismatch expected=(command={command_id},confirmation={confirmation}) "
+ f"observed=(command={message['command']},confirmation={message['confirmation']})"
+ )
+ for index, observed_value in enumerate(message["params"]):
+ expected_value = params[index]
+ if not math.isclose(observed_value, expected_value, rel_tol=0.0, abs_tol=1e-3):
+ payload_intact = False
+ payload_issues.append(
+ f"link={link_name} param{index + 1}_mismatch expected={expected_value} observed={observed_value}"
+ )
+
+ case_pass = routing_match and no_ingress_loop and payload_intact
+ results.append(
+ {
+ "name": case["name"],
+ "source": source["name"],
+ "source_link": source["link"],
+ "target_system": int(case["target_system"]),
+ "target_component": int(case["target_component"]),
+ "command_id": command_id,
+ "expected_links": expected_links,
+ "observed_links": observed_links,
+ "routing_match": routing_match,
+ "no_ingress_loop": no_ingress_loop,
+ "payload_intact": payload_intact,
+ "pass": case_pass,
+ "rules": case["rules"],
+ "payload_issues": payload_issues,
+ }
+ )
+
+ print(
+ f"case={case['name']} command_id={command_id} source={source['name']} source_link={source['link']} "
+ f"target=({case['target_system']},{case['target_component']}) expected_links={expected_links} observed_links={observed_links} "
+ f"routing_match={routing_match} no_ingress_loop={no_ingress_loop} payload_intact={payload_intact} pass={case_pass}",
+ flush=True,
+ )
+ time.sleep(float(timing["inter_case_pause_s"]))
+
+ finally:
+ for connection in connections.values():
+ connection.close()
+
+ pass_count = sum(1 for result in results if result["pass"])
+ fail_count = len(results) - pass_count
+
+ markdown_lines: List[str] = []
+ markdown_lines.append("# MAVLink Routing Compliance Test")
+ markdown_lines.append("")
+ markdown_lines.append(
+ f"- fc_system_id: `{fc_system_id}`"
+ )
+ markdown_lines.append(
+ f"- links: `{sorted(list(link_cfgs.keys()))}`"
+ )
+ markdown_lines.append(
+ f"- gcs_link: `{gcs_link_name}`"
+ )
+ markdown_lines.append(
+ f"- components: `{[(component['name'], component['system_id'], component['component_id'], component['link']) for component in components]}`"
+ )
+ markdown_lines.append("")
+ markdown_lines.append("## Rule References")
+ markdown_lines.append("")
+ markdown_lines.append(f"- broadcast_forward: `{ROUTING_RULE_REFERENCES['broadcast_forward']}`")
+ markdown_lines.append(f"- known_target_forward: `{ROUTING_RULE_REFERENCES['known_target_forward']}`")
+ markdown_lines.append(f"- unknown_target_blocked: `{ROUTING_RULE_REFERENCES['unknown_target_blocked']}`")
+ markdown_lines.append(f"- no_ingress_loop: `{ROUTING_RULE_REFERENCES['no_ingress_loop']}`")
+ markdown_lines.append(f"- no_repack: `{ROUTING_RULE_REFERENCES['no_repack']}`")
+ markdown_lines.append("")
+ markdown_lines.append("## Results")
+ markdown_lines.append("")
+ markdown_lines.append("| Case | Source(link) | Target(sys,comp) | Expected Links | Observed Links | Routing | No Ingress Loop | Payload Intact | Pass |")
+ markdown_lines.append("| --- | --- | --- | --- | --- | --- | --- | --- | --- |")
+ for result in results:
+ markdown_lines.append(
+ f"| `{result['name']}` | `{result['source']} ({result['source_link']})` | "
+ f"`({result['target_system']},{result['target_component']})` | "
+ f"`{result['expected_links']}` | `{result['observed_links']}` | "
+ f"`{result['routing_match']}` | `{result['no_ingress_loop']}` | `{result['payload_intact']}` | `{result['pass']}` |"
+ )
+ markdown_lines.append("")
+ markdown_lines.append(f"summary pass_count={pass_count} fail_count={fail_count} total={len(results)}")
+ markdown_lines.append("")
+
+ failures = [result for result in results if not result["pass"]]
+ if failures:
+ markdown_lines.append("## Failure Details")
+ markdown_lines.append("")
+ for failure in failures:
+ markdown_lines.append(f"### {failure['name']}")
+ markdown_lines.append("")
+ markdown_lines.append(
+ f"- expected_links: `{failure['expected_links']}` observed_links: `{failure['observed_links']}` "
+ f"routing_match: `{failure['routing_match']}` no_ingress_loop: `{failure['no_ingress_loop']}` "
+ f"payload_intact: `{failure['payload_intact']}`"
+ )
+ if failure["payload_issues"]:
+ markdown_lines.append(f"- payload_issues: `{failure['payload_issues']}`")
+ markdown_lines.append(f"- rule_refs: `{failure['rules']}`")
+ markdown_lines.append("")
+
+ report_path.write_text("\n".join(markdown_lines) + "\n", encoding="utf-8")
+ print(f"report_path={report_path} pass_count={pass_count} fail_count={fail_count} total={len(results)}", flush=True)
+
+ if fail_count > 0:
+ raise SystemExit(1)
diff --git a/src/utils/mavlink_tests/mavlink_test_rc.py b/src/utils/mavlink_tests/mavlink_test_rc.py
new file mode 100644
index 00000000000..4862ec7aad2
--- /dev/null
+++ b/src/utils/mavlink_tests/mavlink_test_rc.py
@@ -0,0 +1,141 @@
+#!/usr/bin/env python3
+"""
+Usage:
+ conda run -n drone python mydev/branch/mav_multi/mavlink_test_rc.py --master tcp:127.0.0.1:5761
+ conda run -n drone python mydev/branch/mav_multi/mavlink_test_rc.py --master tcp:127.0.0.1:5761 --duration 20 --tx-hz 100 --roll MID --pitch MID --yaw MID --throttle LOW
+"""
+
+from __future__ import annotations
+
+import argparse
+import time
+from collections import Counter
+from typing import List
+
+from pymavlink import mavutil
+
+
+CHANNEL_ORDER = [
+ "roll",
+ "pitch",
+ "throttle",
+ "yaw",
+ "ch5",
+ "ch6",
+ "ch7",
+ "ch8",
+ "ch9",
+ "ch10",
+ "ch11",
+ "ch12",
+ "ch13",
+ "ch14",
+ "ch15",
+ "ch16",
+ "ch17",
+ "ch18",
+]
+DEFAULT_CHANNELS = [900] * 18
+DEFAULT_CHANNELS[0] = 1500
+DEFAULT_CHANNELS[1] = 1500
+DEFAULT_CHANNELS[3] = 1500
+LEVEL_TO_PWM = {"LOW": 900, "MID": 1500, "HIGH": 2100}
+
+
+if __name__ == "__main__":
+ parser = argparse.ArgumentParser(description="Send MAVLink RC_CHANNELS_OVERRIDE stream and monitor RC echo.")
+ parser.add_argument("--master", required=True, help='pymavlink master endpoint, e.g. "tcp:127.0.0.1:5761"')
+ parser.add_argument("--tx-hz", type=float, default=100.0, help="RC override transmit rate in Hz")
+ parser.add_argument("--duration", type=float, default=0.0, help="Test duration in seconds, 0 means run forever")
+ parser.add_argument("--source-system", type=int, default=240, help="MAVLink source system ID")
+ parser.add_argument("--source-component", type=int, default=191, help="MAVLink source component ID")
+ parser.add_argument("--echo-tolerance", type=int, default=20, help="Allowed absolute PWM error for RC_CHANNELS echo checks")
+ for channel_name in CHANNEL_ORDER:
+ parser.add_argument(f"--{channel_name}", default=None, help="LOW/MID/HIGH or integer PWM")
+ args = parser.parse_args()
+
+ channels: List[int] = list(DEFAULT_CHANNELS)
+ for idx, channel_name in enumerate(CHANNEL_ORDER):
+ raw_value = getattr(args, channel_name)
+ if raw_value is None:
+ continue
+ level_name = raw_value.upper()
+ if level_name in LEVEL_TO_PWM:
+ channels[idx] = LEVEL_TO_PWM[level_name]
+ else:
+ channels[idx] = int(raw_value)
+
+ print(
+ f"master={args.master} tx_hz={args.tx_hz} duration={args.duration} "
+ f"source_system={args.source_system} source_component={args.source_component} channels={channels}",
+ flush=True,
+ )
+
+ master = mavutil.mavlink_connection(
+ args.master,
+ source_system=args.source_system,
+ source_component=args.source_component,
+ autoreconnect=True,
+ )
+ heartbeat = master.wait_heartbeat(timeout=10)
+ if heartbeat is None:
+ raise TimeoutError("No heartbeat received from FC")
+ target_system = heartbeat.get_srcSystem()
+ target_component = heartbeat.get_srcComponent()
+ print(f"target_system={target_system} target_component={target_component}", flush=True)
+
+ period_s = 1.0 / args.tx_hz
+ tx_count = 0
+ rx_count = 0
+ mismatch_count = 0
+ decode_errors = 0
+ last_rx_time = 0.0
+ loop_start = time.monotonic()
+ next_tx_time = loop_start
+ next_report_time = loop_start + 1.0
+ mismatch_hist = Counter()
+
+ while True:
+ now = time.monotonic()
+ if args.duration > 0 and (now - loop_start) >= args.duration:
+ break
+
+ if now >= next_tx_time:
+ master.mav.rc_channels_override_send(target_system, target_component, *channels[:8])
+ tx_count += 1
+ next_tx_time += period_s
+ if next_tx_time < now:
+ next_tx_time = now + period_s
+
+ message = master.recv_match(type=["RC_CHANNELS", "RC_CHANNELS_RAW"], blocking=False)
+ if message is not None:
+ rx_count += 1
+ last_rx_time = now
+ if message.get_type() == "RC_CHANNELS":
+ for i in range(4):
+ key = f"chan{i + 1}_raw"
+ observed = int(getattr(message, key))
+ err = abs(observed - channels[i])
+ if err > args.echo_tolerance:
+ mismatch_count += 1
+ mismatch_hist[i + 1] += 1
+ else:
+ decode_errors += 1
+
+ if now >= next_report_time:
+ rx_age = -1.0 if last_rx_time == 0.0 else (now - last_rx_time)
+ print(
+ f"status_s={now - loop_start:.1f} tx={tx_count} rx={rx_count} mismatches={mismatch_count} "
+ f"decode_errors={decode_errors} rx_age_s={rx_age:.3f} mismatch_hist={dict(mismatch_hist)}",
+ flush=True,
+ )
+ next_report_time += 1.0
+
+ time.sleep(0.001)
+
+ elapsed = max(time.monotonic() - loop_start, 1e-6)
+ print(
+ f"summary elapsed_s={elapsed:.2f} tx={tx_count} rx={rx_count} mismatch_count={mismatch_count} "
+ f"mismatch_rate={mismatch_count / max(rx_count, 1):.6f} tx_hz={tx_count / elapsed:.2f} rx_hz={rx_count / elapsed:.2f}",
+ flush=True,
+ )
diff --git a/src/utils/mavlink_tests/msp_test_rc.py b/src/utils/mavlink_tests/msp_test_rc.py
new file mode 100644
index 00000000000..9cd41cb6c5d
--- /dev/null
+++ b/src/utils/mavlink_tests/msp_test_rc.py
@@ -0,0 +1,145 @@
+#!/usr/bin/env python3
+"""
+Usage:
+ conda run -n drone python mydev/branch/mav_multi/msp_test_rc.py --msp-endpoint 127.0.0.1:5760 --duration 20
+ conda run -n drone python mydev/branch/mav_multi/msp_test_rc.py --msp-endpoint 127.0.0.1:5760 --poll-hz 25 --roll MID --pitch MID --yaw MID --throttle LOW
+"""
+
+from __future__ import annotations
+
+import argparse
+import struct
+import time
+from collections import Counter
+from pathlib import Path
+from typing import List
+
+from serial.serialutil import SerialException
+
+try:
+ from mspapi2.msp_api import MSPApi
+ from mspapi2.lib import InavMSP
+except ModuleNotFoundError:
+ repo_root_guess = Path(__file__).resolve().parents[3]
+ mspapi2_repo = repo_root_guess.parent / "mspapi2"
+ if mspapi2_repo.exists():
+ import sys
+
+ sys.path.insert(0, str(mspapi2_repo))
+ from mspapi2.msp_api import MSPApi
+ from mspapi2.lib import InavMSP
+
+
+CHANNEL_ORDER = [
+ "roll",
+ "pitch",
+ "throttle",
+ "yaw",
+ "ch5",
+ "ch6",
+ "ch7",
+ "ch8",
+ "ch9",
+ "ch10",
+ "ch11",
+ "ch12",
+ "ch13",
+ "ch14",
+ "ch15",
+ "ch16",
+ "ch17",
+ "ch18",
+]
+DEFAULT_CHANNELS = [900] * 18
+DEFAULT_CHANNELS[0] = 1500
+DEFAULT_CHANNELS[1] = 1500
+DEFAULT_CHANNELS[3] = 1500
+LEVEL_TO_PWM = {"LOW": 900, "MID": 1500, "HIGH": 2100}
+
+
+if __name__ == "__main__":
+ parser = argparse.ArgumentParser(description="Poll MSP_RC and monitor RC values against expected channels.")
+ parser.add_argument("--msp-endpoint", required=True, help='MSP endpoint, e.g. "127.0.0.1:5760"')
+ parser.add_argument("--poll-hz", type=float, default=25.0, help="MSP_RC poll rate in Hz")
+ parser.add_argument("--timeout-s", type=float, default=0.2, help="Per MSP request timeout")
+ parser.add_argument("--duration", type=float, default=0.0, help="Test duration in seconds, 0 means run forever")
+ parser.add_argument("--echo-tolerance", type=int, default=40, help="Allowed absolute PWM error per channel")
+ for channel_name in CHANNEL_ORDER:
+ parser.add_argument(f"--{channel_name}", default=None, help="LOW/MID/HIGH or integer PWM")
+ args = parser.parse_args()
+
+ expected_channels: List[int] = list(DEFAULT_CHANNELS)
+ for idx, channel_name in enumerate(CHANNEL_ORDER):
+ raw_value = getattr(args, channel_name)
+ if raw_value is None:
+ continue
+ level_name = raw_value.upper()
+ if level_name in LEVEL_TO_PWM:
+ expected_channels[idx] = LEVEL_TO_PWM[level_name]
+ else:
+ expected_channels[idx] = int(raw_value)
+
+ print(
+ f"msp_endpoint={args.msp_endpoint} poll_hz={args.poll_hz} duration={args.duration} "
+ f"timeout_s={args.timeout_s} expected_channels={expected_channels}",
+ flush=True,
+ )
+
+ poll_period_s = 1.0 / args.poll_hz
+ success_count = 0
+ fail_count = 0
+ mismatch_count = 0
+ mismatch_hist = Counter()
+ last_success_time = 0.0
+ start_t = time.monotonic()
+ next_poll_t = start_t
+ next_report_t = start_t + 1.0
+
+ with MSPApi(tcp_endpoint=args.msp_endpoint) as msp_api:
+ msp_api._serial._max_retries = 1
+ msp_api._serial._reconnect_delay = 0.05
+ while True:
+ now = time.monotonic()
+ if args.duration > 0 and (now - start_t) >= args.duration:
+ break
+
+ if now >= next_poll_t:
+ try:
+ _, payload = msp_api._request_raw(InavMSP.MSP_RC, timeout=args.timeout_s)
+ if len(payload) % 2:
+ raise ValueError("MSP RC payload length must be even")
+ channel_count = len(payload) // 2
+ observed_channels = list(struct.unpack(f"<{channel_count}H", payload))
+ success_count += 1
+ last_success_time = now
+ for i in range(min(channel_count, len(expected_channels))):
+ error = abs(observed_channels[i] - expected_channels[i])
+ if error > args.echo_tolerance:
+ mismatch_count += 1
+ mismatch_hist[i + 1] += 1
+ except (SerialException, RuntimeError, TimeoutError, ConnectionRefusedError):
+ fail_count += 1
+ next_poll_t += poll_period_s
+ if next_poll_t < now:
+ next_poll_t = now + poll_period_s
+
+ if now >= next_report_t:
+ last_ok_age_s = -1.0 if last_success_time == 0.0 else (now - last_success_time)
+ total = success_count + fail_count
+ print(
+ f"status_s={now - start_t:.1f} ok={success_count} fail={fail_count} fail_rate={fail_count / max(total, 1):.6f} "
+ f"mismatch={mismatch_count} mismatch_rate={mismatch_count / max(success_count, 1):.6f} "
+ f"last_ok_age_s={last_ok_age_s:.3f} mismatch_hist={dict(mismatch_hist)}",
+ flush=True,
+ )
+ next_report_t += 1.0
+
+ time.sleep(0.001)
+
+ elapsed = max(time.monotonic() - start_t, 1e-6)
+ total = success_count + fail_count
+ print(
+ f"summary elapsed_s={elapsed:.2f} ok={success_count} fail={fail_count} fail_rate={fail_count / max(total, 1):.6f} "
+ f"mismatch={mismatch_count} mismatch_rate={mismatch_count / max(success_count, 1):.6f} poll_hz={success_count / elapsed:.2f}",
+ flush=True,
+ )
diff --git a/src/utils/mavlink_tests/routing_test_config.yaml b/src/utils/mavlink_tests/routing_test_config.yaml
new file mode 100644
index 00000000000..e4d17865675
--- /dev/null
+++ b/src/utils/mavlink_tests/routing_test_config.yaml
@@ -0,0 +1,58 @@
+timing:
+ connect_timeout_s: 10.0
+ settle_after_connect_s: 0.5
+ route_learn_settle_s: 0.5
+ drain_window_s: 0.15
+ observation_window_s: 0.8
+ inter_case_pause_s: 0.15
+
+network:
+ gcs_link: link_gcs
+ links:
+ link_gcs:
+ endpoint: tcp:127.0.0.1:5761
+ source_system: 255
+ source_component: 190
+ link_components_a:
+ endpoint: tcp:127.0.0.1:5762
+ source_system: 254
+ source_component: 200
+ link_camera:
+ endpoint: tcp:127.0.0.1:5763
+ source_system: 253
+ source_component: 201
+ link_gimbal:
+ endpoint: tcp:127.0.0.1:5764
+ source_system: 252
+ source_component: 202
+
+vehicle:
+ fc_system_id: 1
+
+tests:
+ marker_command_base: 31000
+ unknown_component_id: 199
+ unknown_system_id: 42
+ report_markdown: mydev/branch/mav_multi/ROUTING_TEST.md
+
+components:
+ - name: mav1_elrs_receiver
+ link: link_components_a
+ system_id: 1
+ component_id: 68
+ mav_type: 49
+ - name: mav2_companion_computer
+ link: link_components_a
+ system_id: 1
+ component_id: 191
+ mav_type: 18
+ - name: mav3_camera
+ link: link_camera
+ system_id: 1
+ component_id: 100
+ mav_type: 30
+ - name: mav4_gimbal
+ link: link_gimbal
+ system_id: 1
+ component_id: 154
+ mav_type: 26
diff --git a/src/utils/mavlink_tests/test_config_multiport4_sweep_rc460800_tele115200.yaml b/src/utils/mavlink_tests/test_config_multiport4_sweep_rc460800_tele115200.yaml
new file mode 100644
index 00000000000..a73523f0698
--- /dev/null
+++ b/src/utils/mavlink_tests/test_config_multiport4_sweep_rc460800_tele115200.yaml
@@ -0,0 +1,51 @@
+sitl:
+ binary: /media/anon/WD2TB/DataVault/TechProjects/Software/GitRepos/inav/cmake/build_SITL/inav_9.0.0_SITL
+ workdir: /media/anon/WD2TB/DataVault/TechProjects/Software/GitRepos/inav/cmake
+ eeprom_path: /media/anon/WD2TB/DataVault/TechProjects/Software/GitRepos/inav/mydev/branch/mav_multi/eeprom_multi4_sweep.bin
+ runtime_log: /media/anon/WD2TB/DataVault/TechProjects/Software/GitRepos/inav/mydev/branch/mav_multi/sitl_runtime_multi4_sweep.log
+
+ports:
+ msp: 5760
+ rc: 5761
+ telemetry:
+ - 5762
+ - 5763
+ - 5764
+
+cli:
+ rc_baud: 460800
+ telemetry_baud: 115200
+ ext_status_rate_hz: 10
+ rc_chan_rate_hz: 25
+ pos_rate_hz: 10
+ extra1_rate_hz: 10
+ extra2_rate_hz: 10
+ extra3_rate_hz: 5
+
+tests:
+ port_ready_timeout_s: 30
+ save_reboot_timeout_s: 45
+ mavsdk_probe_timeout_s: 10
+ heartbeat_expected_hz: 1.0
+ rc_expected_hz: 25.0
+ rc_target_system: 1
+ rc_target_component: 1
+ rc_tx_hz: 100.0
+ rc_tx_hz_max: 400.0
+ msp_poll_hz: 50.0
+ inav_status_hz: 5.0
+ msp_request_timeout_s: 0.2
+ stress_command_message_id: 33
+ baseline_duration_s: 30
+ progressive_rates_hz:
+ - 50
+ - 100
+ - 200
+ - 400
+ stress_duration_s: 20
+ max_rate_hz: 400
+ all_ports_max_duration_s: 30
+ sweep_duration_s: 8
+
+output:
+ testing_md: /media/anon/WD2TB/DataVault/TechProjects/Software/GitRepos/inav/mydev/branch/mav_multi/TESTING_multiport4_sweep_rc460800_tele115200.md
From 27d98b54f12be2e75eb1fdce91f3ceb81d2404ad Mon Sep 17 00:00:00 2001
From: frogmane <7685285+xznhj8129@users.noreply.github.com>
Date: Tue, 3 Mar 2026 15:47:12 -0500
Subject: [PATCH 27/46] only initialize streams for port 1
---
.gitignore | 1 +
docs/Mavlink.md | 6 +-
docs/Settings.md | 180 ------------------
src/main/fc/settings.yaml | 126 ------------
src/main/telemetry/mavlink.c | 55 ++++--
src/main/telemetry/mavlink.h | 5 +-
src/main/telemetry/telemetry.c | 38 ++--
src/main/telemetry/telemetry.h | 1 +
src/test/unit/mavlink_unittest.cc | 38 ++++
src/utils/mavlink_tests/ROUTING_TEST.md | 29 +--
.../mav_fix2_singleport_benchmark.py | 66 ++++++-
.../mavlink_tests/mav_multi_benchmark.py | 87 ++++++---
.../mavlink_routing_compliance_test.py | 2 +-
.../mavlink_tests/routing_test_config.yaml | 36 ++--
14 files changed, 260 insertions(+), 410 deletions(-)
diff --git a/.gitignore b/.gitignore
index 6d7138e6bd5..887f6707141 100644
--- a/.gitignore
+++ b/.gitignore
@@ -7,6 +7,7 @@
*.bak
*.uvgui.*
*.ubx
+*.log
.project
.settings
.cproject
diff --git a/docs/Mavlink.md b/docs/Mavlink.md
index d39c1165c25..98bc3c681ad 100644
--- a/docs/Mavlink.md
+++ b/docs/Mavlink.md
@@ -95,7 +95,8 @@ Limited implementation of the Command protocol.
## Datastream groups and defaults
-Default rates (Hz) are shown; adjust with the CLI keys above.
+Default rates (Hz) are shown; adjust with the CLI keys above for port 1.
+Ports 2..N use a secondary startup profile (heartbeat at 1 Hz, other streams disabled).
| Datastream group | Messages | Default rate |
| --- | --- | --- |
@@ -103,7 +104,8 @@ Default rates (Hz) are shown; adjust with the CLI keys above.
| `RC_CHANNELS` | `RC_CHANNELS_RAW` (v1) / `RC_CHANNELS` (v2) | 1 Hz |
| `POSITION` | `GPS_RAW_INT`, `GLOBAL_POSITION_INT`, `GPS_GLOBAL_ORIGIN` | 2 Hz |
| `EXTRA1` | `ATTITUDE` | 3 Hz |
-| `EXTRA2` | `VFR_HUD`, `HEARTBEAT` | 2 Hz |
+| `EXTRA2` | `VFR_HUD` | 2 Hz |
+| `HEARTBEAT` | `HEARTBEAT` | 1 Hz (independent of stream groups) |
| `EXT_SYS_STATE` | `EXTENDED_SYS_STATE` | 1 Hz (defaults to `mavlink_port1_extra3_rate`) |
| `EXTRA3` | `BATTERY_STATUS`, `SCALED_PRESSURE`, `STATUSTEXT` (when present) | 1 Hz |
diff --git a/docs/Settings.md b/docs/Settings.md
index 939991a9792..31e8095d34e 100644
--- a/docs/Settings.md
+++ b/docs/Settings.md
@@ -2762,46 +2762,6 @@ MAVLink Component ID for MAVLink port 2
---
-### mavlink_port2_ext_status_rate
-
-Rate of the extended status message for MAVLink telemetry on port 2
-
-| Default | Min | Max |
-| --- | --- | --- |
-| 2 | 0 | 255 |
-
----
-
-### mavlink_port2_extra1_rate
-
-Rate of the extra1 message for MAVLink telemetry on port 2
-
-| Default | Min | Max |
-| --- | --- | --- |
-| 2 | 0 | 255 |
-
----
-
-### mavlink_port2_extra2_rate
-
-Rate of the extra2 message for MAVLink telemetry on port 2
-
-| Default | Min | Max |
-| --- | --- | --- |
-| 2 | 0 | 255 |
-
----
-
-### mavlink_port2_extra3_rate
-
-Rate of the extra3 message for MAVLink telemetry on port 2
-
-| Default | Min | Max |
-| --- | --- | --- |
-| 1 | 0 | 255 |
-
----
-
### mavlink_port2_high_latency
Enable MAVLink high-latency mode on port 2
@@ -2822,16 +2782,6 @@ Minimum percent of TX buffer space free for MAVLink port 2. Requires RADIO_STATU
---
-### mavlink_port2_pos_rate
-
-Rate of the position message for MAVLink telemetry on port 2
-
-| Default | Min | Max |
-| --- | --- | --- |
-| 2 | 0 | 255 |
-
----
-
### mavlink_port2_radio_type
MAVLink radio type for port 2. Affects RSSI and LQ reporting on OSD.
@@ -2842,16 +2792,6 @@ MAVLink radio type for port 2. Affects RSSI and LQ reporting on OSD.
---
-### mavlink_port2_rc_chan_rate
-
-Rate of the RC channels message for MAVLink telemetry on port 2
-
-| Default | Min | Max |
-| --- | --- | --- |
-| 1 | 0 | 255 |
-
----
-
### mavlink_port3_compid
MAVLink Component ID for MAVLink port 3
@@ -2862,46 +2802,6 @@ MAVLink Component ID for MAVLink port 3
---
-### mavlink_port3_ext_status_rate
-
-Rate of the extended status message for MAVLink telemetry on port 3
-
-| Default | Min | Max |
-| --- | --- | --- |
-| 2 | 0 | 255 |
-
----
-
-### mavlink_port3_extra1_rate
-
-Rate of the extra1 message for MAVLink telemetry on port 3
-
-| Default | Min | Max |
-| --- | --- | --- |
-| 2 | 0 | 255 |
-
----
-
-### mavlink_port3_extra2_rate
-
-Rate of the extra2 message for MAVLink telemetry on port 3
-
-| Default | Min | Max |
-| --- | --- | --- |
-| 2 | 0 | 255 |
-
----
-
-### mavlink_port3_extra3_rate
-
-Rate of the extra3 message for MAVLink telemetry on port 3
-
-| Default | Min | Max |
-| --- | --- | --- |
-| 1 | 0 | 255 |
-
----
-
### mavlink_port3_high_latency
Enable MAVLink high-latency mode on port 3
@@ -2922,16 +2822,6 @@ Minimum percent of TX buffer space free for MAVLink port 3. Requires RADIO_STATU
---
-### mavlink_port3_pos_rate
-
-Rate of the position message for MAVLink telemetry on port 3
-
-| Default | Min | Max |
-| --- | --- | --- |
-| 2 | 0 | 255 |
-
----
-
### mavlink_port3_radio_type
MAVLink radio type for port 3. Affects RSSI and LQ reporting on OSD.
@@ -2942,16 +2832,6 @@ MAVLink radio type for port 3. Affects RSSI and LQ reporting on OSD.
---
-### mavlink_port3_rc_chan_rate
-
-Rate of the RC channels message for MAVLink telemetry on port 3
-
-| Default | Min | Max |
-| --- | --- | --- |
-| 1 | 0 | 255 |
-
----
-
### mavlink_port4_compid
MAVLink Component ID for MAVLink port 4
@@ -2962,46 +2842,6 @@ MAVLink Component ID for MAVLink port 4
---
-### mavlink_port4_ext_status_rate
-
-Rate of the extended status message for MAVLink telemetry on port 4
-
-| Default | Min | Max |
-| --- | --- | --- |
-| 2 | 0 | 255 |
-
----
-
-### mavlink_port4_extra1_rate
-
-Rate of the extra1 message for MAVLink telemetry on port 4
-
-| Default | Min | Max |
-| --- | --- | --- |
-| 2 | 0 | 255 |
-
----
-
-### mavlink_port4_extra2_rate
-
-Rate of the extra2 message for MAVLink telemetry on port 4
-
-| Default | Min | Max |
-| --- | --- | --- |
-| 2 | 0 | 255 |
-
----
-
-### mavlink_port4_extra3_rate
-
-Rate of the extra3 message for MAVLink telemetry on port 4
-
-| Default | Min | Max |
-| --- | --- | --- |
-| 1 | 0 | 255 |
-
----
-
### mavlink_port4_high_latency
Enable MAVLink high-latency mode on port 4
@@ -3022,16 +2862,6 @@ Minimum percent of TX buffer space free for MAVLink port 4. Requires RADIO_STATU
---
-### mavlink_port4_pos_rate
-
-Rate of the position message for MAVLink telemetry on port 4
-
-| Default | Min | Max |
-| --- | --- | --- |
-| 2 | 0 | 255 |
-
----
-
### mavlink_port4_radio_type
MAVLink radio type for port 4. Affects RSSI and LQ reporting on OSD.
@@ -3042,16 +2872,6 @@ MAVLink radio type for port 4. Affects RSSI and LQ reporting on OSD.
---
-### mavlink_port4_rc_chan_rate
-
-Rate of the RC channels message for MAVLink telemetry on port 4
-
-| Default | Min | Max |
-| --- | --- | --- |
-| 1 | 0 | 255 |
-
----
-
### mavlink_sysid
MAVLink System ID
diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml
index 4d262c9b63e..18fda6bc4e6 100644
--- a/src/main/fc/settings.yaml
+++ b/src/main/fc/settings.yaml
@@ -3310,48 +3310,6 @@ groups:
description: "Enable MAVLink high-latency mode on port 1"
type: bool
default_value: OFF
- - name: mavlink_port2_ext_status_rate
- field: mavlink[1].extended_status_rate
- description: "Rate of the extended status message for MAVLink telemetry on port 2"
- type: uint8_t
- min: 0
- max: 255
- default_value: 2
- - name: mavlink_port2_rc_chan_rate
- description: "Rate of the RC channels message for MAVLink telemetry on port 2"
- field: mavlink[1].rc_channels_rate
- type: uint8_t
- min: 0
- max: 255
- default_value: 1
- - name: mavlink_port2_pos_rate
- description: "Rate of the position message for MAVLink telemetry on port 2"
- field: mavlink[1].position_rate
- type: uint8_t
- min: 0
- max: 255
- default_value: 2
- - name: mavlink_port2_extra1_rate
- description: "Rate of the extra1 message for MAVLink telemetry on port 2"
- field: mavlink[1].extra1_rate
- type: uint8_t
- min: 0
- max: 255
- default_value: 2
- - name: mavlink_port2_extra2_rate
- description: "Rate of the extra2 message for MAVLink telemetry on port 2"
- field: mavlink[1].extra2_rate
- type: uint8_t
- min: 0
- max: 255
- default_value: 2
- - name: mavlink_port2_extra3_rate
- description: "Rate of the extra3 message for MAVLink telemetry on port 2"
- field: mavlink[1].extra3_rate
- type: uint8_t
- min: 0
- max: 255
- default_value: 1
- name: mavlink_port2_min_txbuffer
field: mavlink[1].min_txbuff
description: "Minimum percent of TX buffer space free for MAVLink port 2. Requires RADIO_STATUS messages."
@@ -3376,48 +3334,6 @@ groups:
description: "Enable MAVLink high-latency mode on port 2"
type: bool
default_value: OFF
- - name: mavlink_port3_ext_status_rate
- field: mavlink[2].extended_status_rate
- description: "Rate of the extended status message for MAVLink telemetry on port 3"
- type: uint8_t
- min: 0
- max: 255
- default_value: 2
- - name: mavlink_port3_rc_chan_rate
- description: "Rate of the RC channels message for MAVLink telemetry on port 3"
- field: mavlink[2].rc_channels_rate
- type: uint8_t
- min: 0
- max: 255
- default_value: 1
- - name: mavlink_port3_pos_rate
- description: "Rate of the position message for MAVLink telemetry on port 3"
- field: mavlink[2].position_rate
- type: uint8_t
- min: 0
- max: 255
- default_value: 2
- - name: mavlink_port3_extra1_rate
- description: "Rate of the extra1 message for MAVLink telemetry on port 3"
- field: mavlink[2].extra1_rate
- type: uint8_t
- min: 0
- max: 255
- default_value: 2
- - name: mavlink_port3_extra2_rate
- description: "Rate of the extra2 message for MAVLink telemetry on port 3"
- field: mavlink[2].extra2_rate
- type: uint8_t
- min: 0
- max: 255
- default_value: 2
- - name: mavlink_port3_extra3_rate
- description: "Rate of the extra3 message for MAVLink telemetry on port 3"
- field: mavlink[2].extra3_rate
- type: uint8_t
- min: 0
- max: 255
- default_value: 1
- name: mavlink_port3_min_txbuffer
field: mavlink[2].min_txbuff
description: "Minimum percent of TX buffer space free for MAVLink port 3. Requires RADIO_STATUS messages."
@@ -3442,48 +3358,6 @@ groups:
description: "Enable MAVLink high-latency mode on port 3"
type: bool
default_value: OFF
- - name: mavlink_port4_ext_status_rate
- field: mavlink[3].extended_status_rate
- description: "Rate of the extended status message for MAVLink telemetry on port 4"
- type: uint8_t
- min: 0
- max: 255
- default_value: 2
- - name: mavlink_port4_rc_chan_rate
- description: "Rate of the RC channels message for MAVLink telemetry on port 4"
- field: mavlink[3].rc_channels_rate
- type: uint8_t
- min: 0
- max: 255
- default_value: 1
- - name: mavlink_port4_pos_rate
- description: "Rate of the position message for MAVLink telemetry on port 4"
- field: mavlink[3].position_rate
- type: uint8_t
- min: 0
- max: 255
- default_value: 2
- - name: mavlink_port4_extra1_rate
- description: "Rate of the extra1 message for MAVLink telemetry on port 4"
- field: mavlink[3].extra1_rate
- type: uint8_t
- min: 0
- max: 255
- default_value: 2
- - name: mavlink_port4_extra2_rate
- description: "Rate of the extra2 message for MAVLink telemetry on port 4"
- field: mavlink[3].extra2_rate
- type: uint8_t
- min: 0
- max: 255
- default_value: 2
- - name: mavlink_port4_extra3_rate
- description: "Rate of the extra3 message for MAVLink telemetry on port 4"
- field: mavlink[3].extra3_rate
- type: uint8_t
- min: 0
- max: 255
- default_value: 1
- name: mavlink_port4_min_txbuffer
field: mavlink[3].min_txbuff
description: "Minimum percent of TX buffer space free for MAVLink port 4. Requires RADIO_STATUS messages."
diff --git a/src/main/telemetry/mavlink.c b/src/main/telemetry/mavlink.c
index 9198e982ac8..713c0967f0f 100644
--- a/src/main/telemetry/mavlink.c
+++ b/src/main/telemetry/mavlink.c
@@ -90,15 +90,16 @@
#include "scheduler/scheduler.h"
-/* MAVLink datastream rates in Hz */
-const uint8_t mavDefaultRates[MAVLINK_STREAM_COUNT] = {
- [MAV_DATA_STREAM_EXTENDED_STATUS] = 2, // 2Hz
- [MAV_DATA_STREAM_RC_CHANNELS] = 1, // 1Hz
- [MAV_DATA_STREAM_POSITION] = 2, // 2Hz
- [MAV_DATA_STREAM_EXTRA1] = 3, // 3Hz
- [MAV_DATA_STREAM_EXTRA2] = 2, // 2Hz, HEARTBEATs are important
- [MAV_DATA_STREAM_EXTRA3] = 1, // 1Hz
- [MAV_DATA_STREAM_EXTENDED_SYS_STATE] = 1 // 1Hz
+/* Secondary profile for ports 2..N: heartbeat only. */
+static const uint8_t mavSecondaryRates[MAVLINK_STREAM_COUNT] = {
+ [MAV_DATA_STREAM_EXTENDED_STATUS] = 0,
+ [MAV_DATA_STREAM_RC_CHANNELS] = 0,
+ [MAV_DATA_STREAM_POSITION] = 0,
+ [MAV_DATA_STREAM_EXTRA1] = 0,
+ [MAV_DATA_STREAM_EXTRA2] = 0,
+ [MAV_DATA_STREAM_EXTRA3] = 0,
+ [MAV_DATA_STREAM_EXTENDED_SYS_STATE] = 0,
+ [MAV_DATA_STREAM_HEARTBEAT] = 1
};
static mavlinkPortRuntime_t mavPortStates[MAX_MAVLINK_PORTS];
@@ -317,15 +318,26 @@ static int32_t mavlinkStreamIntervalUs(uint8_t streamNum)
static void configureMAVLinkStreamRates(uint8_t portIndex)
{
- mavlinkSetActivePortContext(portIndex);
- mavlinkSetStreamRate(MAV_DATA_STREAM_EXTENDED_STATUS, mavActiveConfig->extended_status_rate);
- mavlinkSetStreamRate(MAV_DATA_STREAM_RC_CHANNELS, mavActiveConfig->rc_channels_rate);
- mavlinkSetStreamRate(MAV_DATA_STREAM_POSITION, mavActiveConfig->position_rate);
- mavlinkSetStreamRate(MAV_DATA_STREAM_EXTRA1, mavActiveConfig->extra1_rate);
- mavlinkSetStreamRate(MAV_DATA_STREAM_EXTRA2, mavActiveConfig->extra2_rate);
- mavlinkSetStreamRate(MAV_DATA_STREAM_EXTRA3, mavActiveConfig->extra3_rate);
- mavlinkSetStreamRate(MAV_DATA_STREAM_EXTENDED_SYS_STATE, mavActiveConfig->extra3_rate);
- memcpy(mavActivePort->mavRatesConfigured, mavActivePort->mavRates, sizeof(mavActivePort->mavRatesConfigured));
+ const mavlinkTelemetryPortConfig_t *primaryConfig = &telemetryConfig()->mavlink[0];
+ const uint8_t mavPrimaryRates[MAVLINK_STREAM_COUNT] = {
+ [MAV_DATA_STREAM_EXTENDED_STATUS] = primaryConfig->extended_status_rate,
+ [MAV_DATA_STREAM_RC_CHANNELS] = primaryConfig->rc_channels_rate,
+ [MAV_DATA_STREAM_POSITION] = primaryConfig->position_rate,
+ [MAV_DATA_STREAM_EXTRA1] = primaryConfig->extra1_rate,
+ [MAV_DATA_STREAM_EXTRA2] = primaryConfig->extra2_rate,
+ [MAV_DATA_STREAM_EXTRA3] = primaryConfig->extra3_rate,
+ [MAV_DATA_STREAM_EXTENDED_SYS_STATE] = primaryConfig->extra3_rate,
+ [MAV_DATA_STREAM_HEARTBEAT] = 1
+ };
+
+ const uint8_t *selectedRates = (portIndex == 0) ? mavPrimaryRates : mavSecondaryRates;
+ mavlinkPortRuntime_t *state = &mavPortStates[portIndex];
+
+ for (uint8_t stream = 0; stream < MAVLINK_STREAM_COUNT; stream++) {
+ state->mavRates[stream] = selectedRates[stream];
+ state->mavRatesConfigured[stream] = selectedRates[stream];
+ state->mavTicks[stream] = 0;
+ }
}
static void freeMAVLinkTelemetryPortByIndex(uint8_t portIndex)
@@ -1549,6 +1561,9 @@ void processMAVLinkTelemetry(timeUs_t currentTimeUs)
if (mavlinkStreamTrigger(MAV_DATA_STREAM_EXTRA2)) {
mavlinkSendVfrHud();
+ }
+
+ if (mavlinkStreamTrigger(MAV_DATA_STREAM_HEARTBEAT)) {
mavlinkSendHeartbeat();
}
@@ -1980,6 +1995,8 @@ static bool mavlinkMessageToStream(uint16_t messageId, uint8_t *streamNum)
{
switch (messageId) {
case MAVLINK_MSG_ID_HEARTBEAT:
+ *streamNum = MAV_DATA_STREAM_HEARTBEAT;
+ return true;
case MAVLINK_MSG_ID_VFR_HUD:
*streamNum = MAV_DATA_STREAM_EXTRA2;
return true;
@@ -2491,6 +2508,8 @@ static bool handleIncoming_PARAM_REQUEST_LIST(void) {
static void mavlinkParseRxStats(const mavlink_radio_status_t *msg) {
switch(mavActiveConfig->radio_type) {
+ case MAVLINK_RADIO_NONE:
+ break;
case MAVLINK_RADIO_SIK:
// rssi scaling info from: https://ardupilot.org/rover/docs/common-3dr-radio-advanced-configuration-and-technical-information.html
rxLinkStatistics.uplinkRSSI = (msg->rssi / 1.9) - 127;
diff --git a/src/main/telemetry/mavlink.h b/src/main/telemetry/mavlink.h
index 57d03e1d64e..d774e6cb07b 100755
--- a/src/main/telemetry/mavlink.h
+++ b/src/main/telemetry/mavlink.h
@@ -36,7 +36,8 @@
#define TELEMETRY_MAVLINK_DELAY ((1000 * 1000) / TELEMETRY_MAVLINK_MAXRATE)
#define TELEMETRY_MAVLINK_HIGH_LATENCY_INTERVAL_US (5 * 1000 * 1000)
#define MAV_DATA_STREAM_EXTENDED_SYS_STATE (MAV_DATA_STREAM_EXTRA3 + 1)
-#define MAVLINK_STREAM_COUNT (MAV_DATA_STREAM_EXTENDED_SYS_STATE + 1)
+#define MAV_DATA_STREAM_HEARTBEAT (MAV_DATA_STREAM_EXTENDED_SYS_STATE + 1)
+#define MAVLINK_STREAM_COUNT (MAV_DATA_STREAM_HEARTBEAT + 1)
#define ARDUPILOT_VERSION_MAJOR 4
#define ARDUPILOT_VERSION_MINOR 6
#define ARDUPILOT_VERSION_PATCH 3
@@ -128,8 +129,6 @@ typedef struct mavlinkRouteEntry_s {
uint8_t ingressPortIndex;
} mavlinkRouteEntry_t;
-extern const uint8_t mavDefaultRates[MAVLINK_STREAM_COUNT];
-
typedef struct mavlinkPortRuntime_s {
serialPort_t *port;
const serialPortConfig_t *portConfig;
diff --git a/src/main/telemetry/telemetry.c b/src/main/telemetry/telemetry.c
index c77f80a2c57..dba8709e6e9 100644
--- a/src/main/telemetry/telemetry.c
+++ b/src/main/telemetry/telemetry.c
@@ -86,6 +86,7 @@ PG_RESET_TEMPLATE(telemetryConfig_t, telemetryConfig,
.accEventThresholdNegX = SETTING_ACC_EVENT_THRESHOLD_NEG_X_DEFAULT,
#endif
+#if defined(USE_TELEMETRY_MAVLINK)
.mavlink_common = {
.autopilot_type = SETTING_MAVLINK_AUTOPILOT_TYPE_DEFAULT,
.version = SETTING_MAVLINK_VERSION_DEFAULT,
@@ -105,42 +106,43 @@ PG_RESET_TEMPLATE(telemetryConfig_t, telemetryConfig,
.high_latency = SETTING_MAVLINK_PORT1_HIGH_LATENCY_DEFAULT
},
{
- .extended_status_rate = SETTING_MAVLINK_PORT2_EXT_STATUS_RATE_DEFAULT,
- .rc_channels_rate = SETTING_MAVLINK_PORT2_RC_CHAN_RATE_DEFAULT,
- .position_rate = SETTING_MAVLINK_PORT2_POS_RATE_DEFAULT,
- .extra1_rate = SETTING_MAVLINK_PORT2_EXTRA1_RATE_DEFAULT,
- .extra2_rate = SETTING_MAVLINK_PORT2_EXTRA2_RATE_DEFAULT,
- .extra3_rate = SETTING_MAVLINK_PORT2_EXTRA3_RATE_DEFAULT,
+ .extended_status_rate = 0,
+ .rc_channels_rate = 0,
+ .position_rate = 0,
+ .extra1_rate = 0,
+ .extra2_rate = 0,
+ .extra3_rate = 0,
.min_txbuff = SETTING_MAVLINK_PORT2_MIN_TXBUFFER_DEFAULT,
.radio_type = SETTING_MAVLINK_PORT2_RADIO_TYPE_DEFAULT,
.compid = SETTING_MAVLINK_PORT2_COMPID_DEFAULT,
.high_latency = SETTING_MAVLINK_PORT2_HIGH_LATENCY_DEFAULT
},
{
- .extended_status_rate = SETTING_MAVLINK_PORT3_EXT_STATUS_RATE_DEFAULT,
- .rc_channels_rate = SETTING_MAVLINK_PORT3_RC_CHAN_RATE_DEFAULT,
- .position_rate = SETTING_MAVLINK_PORT3_POS_RATE_DEFAULT,
- .extra1_rate = SETTING_MAVLINK_PORT3_EXTRA1_RATE_DEFAULT,
- .extra2_rate = SETTING_MAVLINK_PORT3_EXTRA2_RATE_DEFAULT,
- .extra3_rate = SETTING_MAVLINK_PORT3_EXTRA3_RATE_DEFAULT,
+ .extended_status_rate = 0,
+ .rc_channels_rate = 0,
+ .position_rate = 0,
+ .extra1_rate = 0,
+ .extra2_rate = 0,
+ .extra3_rate = 0,
.min_txbuff = SETTING_MAVLINK_PORT3_MIN_TXBUFFER_DEFAULT,
.radio_type = SETTING_MAVLINK_PORT3_RADIO_TYPE_DEFAULT,
.compid = SETTING_MAVLINK_PORT3_COMPID_DEFAULT,
.high_latency = SETTING_MAVLINK_PORT3_HIGH_LATENCY_DEFAULT
},
{
- .extended_status_rate = SETTING_MAVLINK_PORT4_EXT_STATUS_RATE_DEFAULT,
- .rc_channels_rate = SETTING_MAVLINK_PORT4_RC_CHAN_RATE_DEFAULT,
- .position_rate = SETTING_MAVLINK_PORT4_POS_RATE_DEFAULT,
- .extra1_rate = SETTING_MAVLINK_PORT4_EXTRA1_RATE_DEFAULT,
- .extra2_rate = SETTING_MAVLINK_PORT4_EXTRA2_RATE_DEFAULT,
- .extra3_rate = SETTING_MAVLINK_PORT4_EXTRA3_RATE_DEFAULT,
+ .extended_status_rate = 0,
+ .rc_channels_rate = 0,
+ .position_rate = 0,
+ .extra1_rate = 0,
+ .extra2_rate = 0,
+ .extra3_rate = 0,
.min_txbuff = SETTING_MAVLINK_PORT4_MIN_TXBUFFER_DEFAULT,
.radio_type = SETTING_MAVLINK_PORT4_RADIO_TYPE_DEFAULT,
.compid = SETTING_MAVLINK_PORT4_COMPID_DEFAULT,
.high_latency = SETTING_MAVLINK_PORT4_HIGH_LATENCY_DEFAULT
}
}
+#endif
);
void telemetryInit(void)
diff --git a/src/main/telemetry/telemetry.h b/src/main/telemetry/telemetry.h
index 46937dd7386..f2686c5dcac 100644
--- a/src/main/telemetry/telemetry.h
+++ b/src/main/telemetry/telemetry.h
@@ -46,6 +46,7 @@ typedef enum {
MAVLINK_RADIO_GENERIC,
MAVLINK_RADIO_ELRS,
MAVLINK_RADIO_SIK,
+ MAVLINK_RADIO_NONE // Not a radio
} mavlinkRadio_e;
typedef struct mavlinkTelemetryCommonConfig_s {
diff --git a/src/test/unit/mavlink_unittest.cc b/src/test/unit/mavlink_unittest.cc
index 6e09307247f..57035ad7393 100644
--- a/src/test/unit/mavlink_unittest.cc
+++ b/src/test/unit/mavlink_unittest.cc
@@ -638,6 +638,44 @@ TEST(MavlinkTelemetryTest, RequestDataStreamStopsStream)
EXPECT_EQ(interval.interval_us, -1);
}
+TEST(MavlinkTelemetryTest, HeartbeatIntervalIsIndependentFromExtra2Stream)
+{
+ initMavlinkTestState();
+
+ mavlink_message_t stopExtra2Msg;
+ mavlink_msg_request_data_stream_pack(
+ 42, 200, &stopExtra2Msg,
+ 1, MAV_COMP_ID_MISSIONPLANNER,
+ MAV_DATA_STREAM_EXTRA2, 0, 0);
+
+ pushRxMessage(&stopExtra2Msg);
+ handleMAVLinkTelemetry(1000);
+
+ serialTxLen = 0;
+
+ mavlink_message_t getMsg;
+ mavlink_msg_command_long_pack(
+ 42, 200, &getMsg,
+ 1, MAV_COMP_ID_MISSIONPLANNER,
+ MAV_CMD_GET_MESSAGE_INTERVAL,
+ 0,
+ (float)MAVLINK_MSG_ID_HEARTBEAT,
+ 0, 0, 0, 0, 0, 0);
+
+ pushRxMessage(&getMsg);
+ handleMAVLinkTelemetry(1000);
+
+ mavlink_message_t intervalMsg;
+ ASSERT_TRUE(popTxMessage(&intervalMsg));
+ ASSERT_EQ(intervalMsg.msgid, MAVLINK_MSG_ID_MESSAGE_INTERVAL);
+
+ mavlink_message_interval_t interval;
+ mavlink_msg_message_interval_decode(&intervalMsg, &interval);
+
+ EXPECT_EQ(interval.message_id, MAVLINK_MSG_ID_HEARTBEAT);
+ EXPECT_EQ(interval.interval_us, 1000000);
+}
+
TEST(MavlinkTelemetryTest, RequestProtocolVersionUsesConfiguredVersion)
{
initMavlinkTestState();
diff --git a/src/utils/mavlink_tests/ROUTING_TEST.md b/src/utils/mavlink_tests/ROUTING_TEST.md
index 6a67b31822b..7ed080083d4 100644
--- a/src/utils/mavlink_tests/ROUTING_TEST.md
+++ b/src/utils/mavlink_tests/ROUTING_TEST.md
@@ -1,9 +1,9 @@
# MAVLink Routing Compliance Test
- fc_system_id: `1`
-- links: `['link_camera', 'link_components_a', 'link_gcs', 'link_gimbal']`
-- gcs_link: `link_gcs`
-- components: `[('mav1_elrs_receiver', 1, 68, 'link_components_a'), ('mav2_companion_computer', 1, 191, 'link_components_a'), ('mav3_camera', 1, 100, 'link_camera'), ('mav4_gimbal', 1, 154, 'link_gimbal')]`
+- links: `['link_camera', 'link_companion', 'link_gimbal', 'link_radio']`
+- gcs_link: `link_radio`
+- components: `[('mav2_companion_computer', 1, 191, 'link_companion'), ('mav1_elrs_receiver', 1, 68, 'link_radio'), ('mav3_camera', 1, 100, 'link_camera'), ('mav4_gimbal', 1, 154, 'link_gimbal')]`
## Rule References
@@ -17,16 +17,17 @@
| Case | Source(link) | Target(sys,comp) | Expected Links | Observed Links | Routing | No Ingress Loop | Payload Intact | Pass |
| --- | --- | --- | --- | --- | --- | --- | --- | --- |
-| `gcs_broadcast` | `gcs (link_gcs)` | `(0,0)` | `['link_camera', 'link_components_a', 'link_gimbal']` | `['link_camera', 'link_components_a', 'link_gimbal']` | `True` | `True` | `True` | `True` |
-| `gcs_target_mav1_elrs_receiver` | `gcs (link_gcs)` | `(1,68)` | `['link_components_a']` | `['link_components_a']` | `True` | `True` | `True` | `True` |
-| `gcs_target_mav2_companion_computer` | `gcs (link_gcs)` | `(1,191)` | `['link_components_a']` | `['link_components_a']` | `True` | `True` | `True` | `True` |
-| `gcs_target_mav3_camera` | `gcs (link_gcs)` | `(1,100)` | `['link_camera']` | `['link_camera']` | `True` | `True` | `True` | `True` |
-| `gcs_target_mav4_gimbal` | `gcs (link_gcs)` | `(1,154)` | `['link_gimbal']` | `['link_gimbal']` | `True` | `True` | `True` | `True` |
-| `gcs_target_unknown_component` | `gcs (link_gcs)` | `(1,199)` | `[]` | `[]` | `True` | `True` | `True` | `True` |
-| `gcs_target_unknown_system` | `gcs (link_gcs)` | `(42,1)` | `[]` | `[]` | `True` | `True` | `True` | `True` |
-| `mav1_elrs_receiver_broadcast` | `mav1_elrs_receiver (link_components_a)` | `(0,0)` | `['link_camera', 'link_gcs', 'link_gimbal']` | `['link_camera', 'link_gcs', 'link_gimbal']` | `True` | `True` | `True` | `True` |
-| `mav1_elrs_receiver_to_mav3_camera` | `mav1_elrs_receiver (link_components_a)` | `(1,100)` | `['link_camera']` | `['link_camera']` | `True` | `True` | `True` | `True` |
-| `mav1_elrs_receiver_to_gcs` | `mav1_elrs_receiver (link_components_a)` | `(255,190)` | `['link_gcs']` | `['link_gcs']` | `True` | `True` | `True` | `True` |
+| `gcs_broadcast` | `gcs (link_radio)` | `(0,0)` | `['link_camera', 'link_companion', 'link_gimbal']` | `['link_camera', 'link_companion', 'link_gimbal']` | `True` | `True` | `True` | `True` |
+| `gcs_target_local_system_component_broadcast` | `gcs (link_radio)` | `(1,0)` | `['link_camera', 'link_companion', 'link_gimbal']` | `['link_camera', 'link_companion', 'link_gimbal']` | `True` | `True` | `True` | `True` |
+| `gcs_target_mav2_companion_computer` | `gcs (link_radio)` | `(1,191)` | `['link_companion']` | `['link_companion']` | `True` | `True` | `True` | `True` |
+| `gcs_target_mav1_elrs_receiver` | `gcs (link_radio)` | `(1,68)` | `[]` | `[]` | `True` | `True` | `True` | `True` |
+| `gcs_target_mav3_camera` | `gcs (link_radio)` | `(1,100)` | `['link_camera']` | `['link_camera']` | `True` | `True` | `True` | `True` |
+| `gcs_target_mav4_gimbal` | `gcs (link_radio)` | `(1,154)` | `['link_gimbal']` | `['link_gimbal']` | `True` | `True` | `True` | `True` |
+| `gcs_target_unknown_component` | `gcs (link_radio)` | `(1,199)` | `[]` | `[]` | `True` | `True` | `True` | `True` |
+| `gcs_target_unknown_system` | `gcs (link_radio)` | `(42,1)` | `[]` | `[]` | `True` | `True` | `True` | `True` |
+| `mav2_companion_computer_broadcast` | `mav2_companion_computer (link_companion)` | `(0,0)` | `['link_camera', 'link_gimbal', 'link_radio']` | `['link_camera', 'link_gimbal', 'link_radio']` | `True` | `True` | `True` | `True` |
+| `mav2_companion_computer_to_mav1_elrs_receiver` | `mav2_companion_computer (link_companion)` | `(1,68)` | `['link_radio']` | `['link_radio']` | `True` | `True` | `True` | `True` |
+| `mav2_companion_computer_to_gcs` | `mav2_companion_computer (link_companion)` | `(1,68)` | `['link_radio']` | `['link_radio']` | `True` | `True` | `True` | `True` |
-summary pass_count=10 fail_count=0 total=10
+summary pass_count=11 fail_count=0 total=11
diff --git a/src/utils/mavlink_tests/mav_fix2_singleport_benchmark.py b/src/utils/mavlink_tests/mav_fix2_singleport_benchmark.py
index f510b28b270..33cafc762c1 100644
--- a/src/utils/mavlink_tests/mav_fix2_singleport_benchmark.py
+++ b/src/utils/mavlink_tests/mav_fix2_singleport_benchmark.py
@@ -37,6 +37,8 @@
CHANNELS = [1500, 1500, 900, 1500] + [900] * 14
MAV_CMD_REQUEST_MESSAGE = int(mavutil.mavlink.MAV_CMD_REQUEST_MESSAGE)
+MAV_CMD_SET_MESSAGE_INTERVAL = int(mavutil.mavlink.MAV_CMD_SET_MESSAGE_INTERVAL)
+MAVLINK_MSG_ID_HEARTBEAT = int(mavutil.mavlink.MAVLINK_MSG_ID_HEARTBEAT)
def load_config(config_path: Path) -> Dict[str, Any]:
@@ -93,12 +95,6 @@ def build_cli_commands(config: Dict[str, Any]) -> List[str]:
build_serial_command(2, 0, rc_baud),
build_serial_command(3, 0, rc_baud),
"set mavlink_version = 2",
- f"set mavlink_port1_ext_status_rate = {int(cli_cfg['ext_status_rate_hz'])}",
- f"set mavlink_port1_rc_chan_rate = {int(cli_cfg['rc_chan_rate_hz'])}",
- f"set mavlink_port1_pos_rate = {int(cli_cfg['pos_rate_hz'])}",
- f"set mavlink_port1_extra1_rate = {int(cli_cfg['extra1_rate_hz'])}",
- f"set mavlink_port1_extra2_rate = {int(cli_cfg['extra2_rate_hz'])}",
- f"set mavlink_port1_extra3_rate = {int(cli_cfg['extra3_rate_hz'])}",
"save",
]
return commands
@@ -128,6 +124,7 @@ def run_workload(
command_message_id = int(tests_cfg["stress_command_message_id"])
target_system = int(tests_cfg["rc_target_system"])
target_component = int(tests_cfg["rc_target_component"])
+ stream_cfg = config["cli"]
listener = mavutil.mavlink_connection(
f"tcp:127.0.0.1:{rc_port}",
@@ -158,6 +155,62 @@ def run_workload(
target_component = int(msg.get_srcComponent())
break
+ sender.mav.request_data_stream_send(
+ target_system,
+ target_component,
+ int(mavutil.mavlink.MAV_DATA_STREAM_EXTENDED_STATUS),
+ int(stream_cfg["ext_status_rate_hz"]),
+ 1 if int(stream_cfg["ext_status_rate_hz"]) > 0 else 0,
+ )
+ sender.mav.request_data_stream_send(
+ target_system,
+ target_component,
+ int(mavutil.mavlink.MAV_DATA_STREAM_RC_CHANNELS),
+ int(stream_cfg["rc_chan_rate_hz"]),
+ 1 if int(stream_cfg["rc_chan_rate_hz"]) > 0 else 0,
+ )
+ sender.mav.request_data_stream_send(
+ target_system,
+ target_component,
+ int(mavutil.mavlink.MAV_DATA_STREAM_POSITION),
+ int(stream_cfg["pos_rate_hz"]),
+ 1 if int(stream_cfg["pos_rate_hz"]) > 0 else 0,
+ )
+ sender.mav.request_data_stream_send(
+ target_system,
+ target_component,
+ int(mavutil.mavlink.MAV_DATA_STREAM_EXTRA1),
+ int(stream_cfg["extra1_rate_hz"]),
+ 1 if int(stream_cfg["extra1_rate_hz"]) > 0 else 0,
+ )
+ sender.mav.request_data_stream_send(
+ target_system,
+ target_component,
+ int(mavutil.mavlink.MAV_DATA_STREAM_EXTRA2),
+ int(stream_cfg["extra2_rate_hz"]),
+ 1 if int(stream_cfg["extra2_rate_hz"]) > 0 else 0,
+ )
+ sender.mav.request_data_stream_send(
+ target_system,
+ target_component,
+ int(mavutil.mavlink.MAV_DATA_STREAM_EXTRA3),
+ int(stream_cfg["extra3_rate_hz"]),
+ 1 if int(stream_cfg["extra3_rate_hz"]) > 0 else 0,
+ )
+ sender.mav.command_long_send(
+ target_system,
+ target_component,
+ MAV_CMD_SET_MESSAGE_INTERVAL,
+ 0,
+ float(MAVLINK_MSG_ID_HEARTBEAT),
+ float(int(1_000_000.0 / heartbeat_expected_hz)),
+ 0,
+ 0,
+ 0,
+ 0,
+ 0,
+ )
+
hb_count = 0
hb_est_lost = 0
last_hb_t: float | None = None
@@ -360,6 +413,7 @@ def write_report(config: Dict[str, Any], baseline: Dict[str, Any], stress: Dict[
lines.append(f"- EEPROM: `{config['sitl']['eeprom_path']}`")
lines.append("- MSP kept on UART1 by design (`serial 0 ... functionMask=1`).")
lines.append("- CLI under test sets `receiver_type=SERIAL` and `serialrx_provider=MAVLINK`.")
+ lines.append("- Stream rates are configured at runtime via MAVLink `REQUEST_DATA_STREAM` and `MAV_CMD_SET_MESSAGE_INTERVAL`.")
lines.append(
f"- CLI baud config: `rc_baud={config['cli']['rc_baud']}`, "
f"`telemetry_baud={config['cli'].get('telemetry_baud', config['cli']['rc_baud'])}`."
diff --git a/src/utils/mavlink_tests/mav_multi_benchmark.py b/src/utils/mavlink_tests/mav_multi_benchmark.py
index 6483fa5806e..97ce932a7f6 100644
--- a/src/utils/mavlink_tests/mav_multi_benchmark.py
+++ b/src/utils/mavlink_tests/mav_multi_benchmark.py
@@ -38,6 +38,7 @@
DEFAULT_CONFIG_PATH = Path("mydev/branch/mav_multi/test_config.yaml")
CHANNELS = [1500, 1500, 900, 1500] + [900] * 14
MAV_CMD_REQUEST_MESSAGE = int(mavutil.mavlink.MAV_CMD_REQUEST_MESSAGE)
+MAV_CMD_SET_MESSAGE_INTERVAL = int(mavutil.mavlink.MAV_CMD_SET_MESSAGE_INTERVAL)
MAVLINK_MSG_ID_HEARTBEAT = int(mavutil.mavlink.MAVLINK_MSG_ID_HEARTBEAT)
@@ -131,30 +132,6 @@ def build_cli_config_commands(config: Dict[str, Any], mavlink_port_count: int) -
"set mavlink_port2_high_latency = OFF",
"set mavlink_port3_high_latency = OFF",
"set mavlink_port4_high_latency = OFF",
- f"set mavlink_port1_ext_status_rate = {int(cli_cfg['ext_status_rate_hz'])}",
- f"set mavlink_port1_rc_chan_rate = {int(cli_cfg['rc_chan_rate_hz'])}",
- f"set mavlink_port1_pos_rate = {int(cli_cfg['pos_rate_hz'])}",
- f"set mavlink_port1_extra1_rate = {int(cli_cfg['extra1_rate_hz'])}",
- f"set mavlink_port1_extra2_rate = {int(cli_cfg['extra2_rate_hz'])}",
- f"set mavlink_port1_extra3_rate = {int(cli_cfg['extra3_rate_hz'])}",
- f"set mavlink_port2_ext_status_rate = {int(cli_cfg['ext_status_rate_hz'])}",
- f"set mavlink_port2_rc_chan_rate = {int(cli_cfg['rc_chan_rate_hz'])}",
- f"set mavlink_port2_pos_rate = {int(cli_cfg['pos_rate_hz'])}",
- f"set mavlink_port2_extra1_rate = {int(cli_cfg['extra1_rate_hz'])}",
- f"set mavlink_port2_extra2_rate = {int(cli_cfg['extra2_rate_hz'])}",
- f"set mavlink_port2_extra3_rate = {int(cli_cfg['extra3_rate_hz'])}",
- f"set mavlink_port3_ext_status_rate = {int(cli_cfg['ext_status_rate_hz'])}",
- f"set mavlink_port3_rc_chan_rate = {int(cli_cfg['rc_chan_rate_hz'])}",
- f"set mavlink_port3_pos_rate = {int(cli_cfg['pos_rate_hz'])}",
- f"set mavlink_port3_extra1_rate = {int(cli_cfg['extra1_rate_hz'])}",
- f"set mavlink_port3_extra2_rate = {int(cli_cfg['extra2_rate_hz'])}",
- f"set mavlink_port3_extra3_rate = {int(cli_cfg['extra3_rate_hz'])}",
- f"set mavlink_port4_ext_status_rate = {int(cli_cfg['ext_status_rate_hz'])}",
- f"set mavlink_port4_rc_chan_rate = {int(cli_cfg['rc_chan_rate_hz'])}",
- f"set mavlink_port4_pos_rate = {int(cli_cfg['pos_rate_hz'])}",
- f"set mavlink_port4_extra1_rate = {int(cli_cfg['extra1_rate_hz'])}",
- f"set mavlink_port4_extra2_rate = {int(cli_cfg['extra2_rate_hz'])}",
- f"set mavlink_port4_extra3_rate = {int(cli_cfg['extra3_rate_hz'])}",
"save",
]
return commands
@@ -241,6 +218,8 @@ def run_workload(
command_message_id = int(tests_cfg["stress_command_message_id"])
rc_target_system = int(tests_cfg["rc_target_system"])
rc_target_component = int(tests_cfg["rc_target_component"])
+ heartbeat_expected_hz = float(tests_cfg["heartbeat_expected_hz"])
+ stream_cfg = config["cli"]
port_ready_timeout_s = float(tests_cfg["port_ready_timeout_s"])
warmup_s = float(tests_cfg.get("warmup_s", 3.0))
warmup_heartbeat_count = int(tests_cfg.get("warmup_heartbeat_count", 3))
@@ -376,6 +355,65 @@ def run_workload(
time.sleep(0.001)
+ for port, conn in listeners.items():
+ target_system, target_component = targets[port]
+ conn.mav.request_data_stream_send(
+ target_system,
+ target_component,
+ int(mavutil.mavlink.MAV_DATA_STREAM_EXTENDED_STATUS),
+ int(stream_cfg["ext_status_rate_hz"]),
+ 1 if int(stream_cfg["ext_status_rate_hz"]) > 0 else 0,
+ )
+ conn.mav.request_data_stream_send(
+ target_system,
+ target_component,
+ int(mavutil.mavlink.MAV_DATA_STREAM_RC_CHANNELS),
+ int(stream_cfg["rc_chan_rate_hz"]),
+ 1 if int(stream_cfg["rc_chan_rate_hz"]) > 0 else 0,
+ )
+ conn.mav.request_data_stream_send(
+ target_system,
+ target_component,
+ int(mavutil.mavlink.MAV_DATA_STREAM_POSITION),
+ int(stream_cfg["pos_rate_hz"]),
+ 1 if int(stream_cfg["pos_rate_hz"]) > 0 else 0,
+ )
+ conn.mav.request_data_stream_send(
+ target_system,
+ target_component,
+ int(mavutil.mavlink.MAV_DATA_STREAM_EXTRA1),
+ int(stream_cfg["extra1_rate_hz"]),
+ 1 if int(stream_cfg["extra1_rate_hz"]) > 0 else 0,
+ )
+ conn.mav.request_data_stream_send(
+ target_system,
+ target_component,
+ int(mavutil.mavlink.MAV_DATA_STREAM_EXTRA2),
+ int(stream_cfg["extra2_rate_hz"]),
+ 1 if int(stream_cfg["extra2_rate_hz"]) > 0 else 0,
+ )
+ conn.mav.request_data_stream_send(
+ target_system,
+ target_component,
+ int(mavutil.mavlink.MAV_DATA_STREAM_EXTRA3),
+ int(stream_cfg["extra3_rate_hz"]),
+ 1 if int(stream_cfg["extra3_rate_hz"]) > 0 else 0,
+ )
+ conn.mav.command_long_send(
+ target_system,
+ target_component,
+ MAV_CMD_SET_MESSAGE_INTERVAL,
+ 0,
+ float(MAVLINK_MSG_ID_HEARTBEAT),
+ float(int(1_000_000.0 / heartbeat_expected_hz)),
+ 0,
+ 0,
+ 0,
+ 0,
+ 0,
+ )
+ time.sleep(0.1)
+
for stats in port_stats.values():
stats["heartbeat_count"] = 0
stats["rc_count"] = 0
@@ -617,6 +655,7 @@ def write_testing_report(config: Dict[str, Any], report: Dict[str, Any]) -> None
lines.append(f"- EEPROM: `{config['sitl']['eeprom_path']}`")
lines.append("- MSP kept on UART1 by design (`serial 0 ... functionMask=1`).")
lines.append("- CLI under test sets `receiver_type=SERIAL` and `serialrx_provider=MAVLINK`.")
+ lines.append("- Stream rates are configured at runtime via MAVLink `REQUEST_DATA_STREAM` and `MAV_CMD_SET_MESSAGE_INTERVAL`.")
lines.append("- `RC_CHANNELS` metrics below are MAVLink telemetry stream metrics, not RX input ownership.")
lines.append("")
lines.append("## MAVSDK Probe")
diff --git a/src/utils/mavlink_tests/mavlink_routing_compliance_test.py b/src/utils/mavlink_tests/mavlink_routing_compliance_test.py
index e202e649af8..0ea996ec1b5 100644
--- a/src/utils/mavlink_tests/mavlink_routing_compliance_test.py
+++ b/src/utils/mavlink_tests/mavlink_routing_compliance_test.py
@@ -1,7 +1,7 @@
#!/usr/bin/env python3
"""
Usage:
- conda run -n drone python mydev/branch/mav_multi/mavlink_routing_compliance_test.py --config mydev/branch/mav_multi/routing_test_config.yaml
+ conda run -n drone python src/utils/mavlink_tests/mavlink_routing_compliance_test.py --config src/utils/mavlink_tests/routing_test_config.yaml
"""
from __future__ import annotations
diff --git a/src/utils/mavlink_tests/routing_test_config.yaml b/src/utils/mavlink_tests/routing_test_config.yaml
index e4d17865675..d4677ba4ebf 100644
--- a/src/utils/mavlink_tests/routing_test_config.yaml
+++ b/src/utils/mavlink_tests/routing_test_config.yaml
@@ -7,24 +7,24 @@ timing:
inter_case_pause_s: 0.15
network:
- gcs_link: link_gcs
+ gcs_link: link_radio
links:
- link_gcs:
+ link_radio:
endpoint: tcp:127.0.0.1:5761
- source_system: 255
- source_component: 190
- link_components_a:
+ source_system: 1
+ source_component: 68
+ link_companion:
endpoint: tcp:127.0.0.1:5762
- source_system: 254
- source_component: 200
+ source_system: 1
+ source_component: 191
link_camera:
endpoint: tcp:127.0.0.1:5763
- source_system: 253
- source_component: 201
+ source_system: 1
+ source_component: 100
link_gimbal:
endpoint: tcp:127.0.0.1:5764
- source_system: 252
- source_component: 202
+ source_system: 1
+ source_component: 154
vehicle:
fc_system_id: 1
@@ -33,19 +33,19 @@ tests:
marker_command_base: 31000
unknown_component_id: 199
unknown_system_id: 42
- report_markdown: mydev/branch/mav_multi/ROUTING_TEST.md
+ report_markdown: src/utils/mavlink_tests/ROUTING_TEST.md
components:
- - name: mav1_elrs_receiver
- link: link_components_a
- system_id: 1
- component_id: 68
- mav_type: 49
- name: mav2_companion_computer
- link: link_components_a
+ link: link_companion
system_id: 1
component_id: 191
mav_type: 18
+ - name: mav1_elrs_receiver
+ link: link_radio
+ system_id: 1
+ component_id: 68
+ mav_type: 49
- name: mav3_camera
link: link_camera
system_id: 1
From d2f2866b20e9eb02950a61a975567d2f35afeeeb Mon Sep 17 00:00:00 2001
From: frogmane <7685285+xznhj8129@users.noreply.github.com>
Date: Wed, 4 Mar 2026 16:40:57 -0500
Subject: [PATCH 28/46] .
---
docs/Mavlink.md | 39 ++
docs/development/msp/inav_enums.json | 5 +-
docs/development/msp/inav_enums_ref.md | 3 +-
.../mav_fix2_singleport_benchmark.py | 519 ------------------
src/utils/mavlink_tests/mav_multi_sweep.py | 42 +-
5 files changed, 71 insertions(+), 537 deletions(-)
delete mode 100644 src/utils/mavlink_tests/mav_fix2_singleport_benchmark.py
diff --git a/docs/Mavlink.md b/docs/Mavlink.md
index 98bc3c681ad..1df23459fed 100644
--- a/docs/Mavlink.md
+++ b/docs/Mavlink.md
@@ -20,6 +20,45 @@ INAV has a partial implementation of MAVLink that is intended primarily for simp
- `mavlink_port1_min_txbuffer` – minimum remote TX buffer level before sending when `RADIO_STATUS` provides flow control.
- `mavlink_port1_radio_type` – scales `RADIO_STATUS` RSSI/SNR for **generic**, **ELRS**, or **SiK** links.
+## Multi-port MAVLink
+
+INAV supports up to 4 concurrent MAVLink telemetry ports (`MAX_MAVLINK_PORTS`), one endpoint per serial port configured with `FUNCTION_TELEMETRY_MAVLINK`.
+
+### Configuration model
+
+- Shared across all ports: `mavlink_sysid`, `mavlink_version`, `mavlink_autopilot_type`.
+- Per-port: `mavlink_portN_compid`, `mavlink_portN_min_txbuffer`, `mavlink_portN_radio_type`, `mavlink_portN_high_latency`.
+- Stream defaults at startup:
+- Port 1 uses configured CLI rates (`mavlink_port1_*_rate`).
+- Ports 2..4 start with heartbeat only (1 Hz), all other streams disabled.
+
+### Routing and forwarding behavior
+
+- INAV learns routes from incoming traffic as `(sysid, compid) -> ingress port`.
+- Broadcast messages are forwarded to all other MAVLink ports (except `RADIO_STATUS`, which is not forwarded).
+- Targeted messages are forwarded only to ports with a learned route for that target.
+- Practical caveat: the first targeted message to a never-seen endpoint may not forward until that endpoint has sent at least one MAVLink frame.
+
+### Local message handling behavior
+
+- Local/system broadcasts (`target_system=0` or local system ID with `target_component=0`) are fanned out to all local ports only for:
+- `REQUEST_DATA_STREAM`
+- `MAV_CMD_SET_MESSAGE_INTERVAL`
+- `MAV_CMD_CONTROL_HIGH_LATENCY`
+- Other incoming commands/messages are handled on one resolved local port, based on local target matching.
+
+### High-latency behavior
+
+- High-latency mode is per-port (`mavlink_portN_high_latency` or `MAV_CMD_CONTROL_HIGH_LATENCY` on that port).
+- Requires MAVLink2; MAVLink1 cannot enable it.
+- When enabled, normal stream scheduling for that port is replaced by `HIGH_LATENCY2` at 5-second intervals.
+
+### Usage guidance
+
+- Assign a unique `mavlink_portN_compid` to each INAV MAVLink port to avoid ambiguous local targeting.
+- If a GCS or companion needs telemetry on ports 2..4, explicitly request streams (`REQUEST_DATA_STREAM` or `MAV_CMD_SET_MESSAGE_INTERVAL`) because only heartbeat is enabled by default.
+- If you depend on directed forwarding between links, ensure each remote endpoint transmits at least one frame early so route learning is populated.
+
## Supported Outgoing Messages
Messages are organized into MAVLink datastream groups. Each group sends **one message per trigger** at the configured rate:
diff --git a/docs/development/msp/inav_enums.json b/docs/development/msp/inav_enums.json
index 3844e59cee9..69a74420887 100644
--- a/docs/development/msp/inav_enums.json
+++ b/docs/development/msp/inav_enums.json
@@ -2239,7 +2239,7 @@
"MAG_MAX": "MAG_FAKE"
},
"mavFrameSupportMask_e": {
- "_source": "inav/src/main/telemetry/mavlink.c",
+ "_source": "inav/src/main/telemetry/mavlink.h",
"MAV_FRAME_SUPPORTED_NONE": "0",
"MAV_FRAME_SUPPORTED_GLOBAL": "(1 << 0)",
"MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT": "(1 << 1)",
@@ -2255,7 +2255,8 @@
"_source": "inav/src/main/telemetry/telemetry.h",
"MAVLINK_RADIO_GENERIC": "0",
"MAVLINK_RADIO_ELRS": "1",
- "MAVLINK_RADIO_SIK": "2"
+ "MAVLINK_RADIO_SIK": "2",
+ "MAVLINK_RADIO_NONE": "3"
},
"measurementSteps_e": {
"_source": "inav/src/main/drivers/rangefinder/rangefinder_vl53l0x.c",
diff --git a/docs/development/msp/inav_enums_ref.md b/docs/development/msp/inav_enums_ref.md
index 164ebd9bc14..1fd45d97e91 100644
--- a/docs/development/msp/inav_enums_ref.md
+++ b/docs/development/msp/inav_enums_ref.md
@@ -3378,7 +3378,7 @@
---
## `mavFrameSupportMask_e`
-> Source: ../../../src/main/telemetry/mavlink.c
+> Source: ../../../src/main/telemetry/mavlink.h
| Enumerator | Value | Condition |
|---|---:|---|
@@ -3408,6 +3408,7 @@
| `MAVLINK_RADIO_GENERIC` | 0 | |
| `MAVLINK_RADIO_ELRS` | 1 | |
| `MAVLINK_RADIO_SIK` | 2 | |
+| `MAVLINK_RADIO_NONE` | 3 | |
---
## `measurementSteps_e`
diff --git a/src/utils/mavlink_tests/mav_fix2_singleport_benchmark.py b/src/utils/mavlink_tests/mav_fix2_singleport_benchmark.py
deleted file mode 100644
index 33cafc762c1..00000000000
--- a/src/utils/mavlink_tests/mav_fix2_singleport_benchmark.py
+++ /dev/null
@@ -1,519 +0,0 @@
-#!/usr/bin/env python3
-"""
-Usage:
- /home/anon/miniconda3/envs/drone/bin/python mydev/branch/mav_multi/mav_fix2_singleport_benchmark.py --config mydev/branch/mav_multi/test_config_mav_fix2.yaml
-"""
-
-from __future__ import annotations
-
-import argparse
-import contextlib
-import math
-import socket
-import struct
-import subprocess
-import time
-from datetime import datetime, timezone
-from pathlib import Path
-from typing import Any, Dict, List, Tuple
-
-import yaml
-from pymavlink import mavutil
-from serial.serialutil import SerialException
-
-try:
- from mspapi2.msp_api import MSPApi
- from mspapi2.lib import InavMSP
-except ModuleNotFoundError:
- repo_root_guess = Path(__file__).resolve().parents[3]
- mspapi2_repo = repo_root_guess.parent / "mspapi2"
- if mspapi2_repo.exists():
- import sys
-
- sys.path.insert(0, str(mspapi2_repo))
- from mspapi2.msp_api import MSPApi
- from mspapi2.lib import InavMSP
-
-
-CHANNELS = [1500, 1500, 900, 1500] + [900] * 14
-MAV_CMD_REQUEST_MESSAGE = int(mavutil.mavlink.MAV_CMD_REQUEST_MESSAGE)
-MAV_CMD_SET_MESSAGE_INTERVAL = int(mavutil.mavlink.MAV_CMD_SET_MESSAGE_INTERVAL)
-MAVLINK_MSG_ID_HEARTBEAT = int(mavutil.mavlink.MAVLINK_MSG_ID_HEARTBEAT)
-
-
-def load_config(config_path: Path) -> Dict[str, Any]:
- return yaml.safe_load(config_path.read_text(encoding="utf-8"))
-
-
-def wait_for_tcp_port(host: str, port: int, timeout_s: float) -> None:
- deadline = time.monotonic() + timeout_s
- while time.monotonic() < deadline:
- try:
- with socket.create_connection((host, port), timeout=1.0):
- return
- except (ConnectionRefusedError, socket.timeout, OSError):
- time.sleep(0.2)
- raise TimeoutError(f"TCP port {host}:{port} did not become available within {timeout_s}s")
-
-
-def cli_read_until_prompt(cli_socket: socket.socket) -> str:
- data = b""
- while b"\n# " not in data:
- chunk = cli_socket.recv(65536)
- if not chunk:
- raise ConnectionError("CLI socket closed before prompt")
- data += chunk
- return data.decode("utf-8", errors="replace")
-
-
-def run_cli_commands(host: str, port: int, commands: List[str]) -> None:
- with socket.create_connection((host, port), timeout=5.0) as cli_socket:
- cli_socket.settimeout(3.0)
- cli_socket.sendall(b"#\n")
- cli_read_until_prompt(cli_socket)
- for command in commands:
- cli_socket.sendall(command.encode("utf-8") + b"\n")
- if command == "save":
- break
- cli_read_until_prompt(cli_socket)
- time.sleep(1.0)
-
-
-def build_serial_command(index: int, function_mask: int, baud: int) -> str:
- return f"serial {index} {function_mask} {baud} {baud} 0 {baud}"
-
-
-def build_cli_commands(config: Dict[str, Any]) -> List[str]:
- cli_cfg = config["cli"]
- rc_baud = int(cli_cfg["rc_baud"])
- commands = [
- "feature TELEMETRY",
- "set receiver_type = SERIAL",
- "set serialrx_provider = MAVLINK",
- build_serial_command(0, 1, 115200), # UART1 MSP
- build_serial_command(1, 256, rc_baud), # UART2 MAVLINK single port (RC-capable)
- build_serial_command(2, 0, rc_baud),
- build_serial_command(3, 0, rc_baud),
- "set mavlink_version = 2",
- "save",
- ]
- return commands
-
-
-def run_workload(
- config: Dict[str, Any],
- sitl_pid: int,
- duration_s: float,
- command_rate_hz: float,
- rc_tx_hz_override: float | None = None,
-) -> Dict[str, Any]:
- tests_cfg = config["tests"]
- ports_cfg = config["ports"]
- rc_port = int(ports_cfg["rc"])
- msp_port = int(ports_cfg["msp"])
-
- wait_for_tcp_port("127.0.0.1", rc_port, float(tests_cfg["port_ready_timeout_s"]))
- wait_for_tcp_port("127.0.0.1", msp_port, float(tests_cfg["port_ready_timeout_s"]))
- msp_enabled = msp_port != rc_port
-
- heartbeat_expected_hz = float(tests_cfg["heartbeat_expected_hz"])
- rc_expected_hz = float(tests_cfg["rc_expected_hz"])
- rc_tx_hz = float(tests_cfg["rc_tx_hz"]) if rc_tx_hz_override is None else float(rc_tx_hz_override)
- msp_poll_hz = float(tests_cfg["msp_poll_hz"])
- msp_request_timeout_s = float(tests_cfg["msp_request_timeout_s"])
- command_message_id = int(tests_cfg["stress_command_message_id"])
- target_system = int(tests_cfg["rc_target_system"])
- target_component = int(tests_cfg["rc_target_component"])
- stream_cfg = config["cli"]
-
- listener = mavutil.mavlink_connection(
- f"tcp:127.0.0.1:{rc_port}",
- source_system=170,
- source_component=190,
- autoreconnect=True,
- )
- sender = mavutil.mavlink_connection(
- f"tcp:127.0.0.1:{rc_port}",
- source_system=239,
- source_component=191,
- autoreconnect=True,
- )
-
- # Prime telemetry stream startup from GCS side.
- handshake_deadline = time.monotonic() + 3.0
- while time.monotonic() < handshake_deadline:
- sender.mav.heartbeat_send(
- mavutil.mavlink.MAV_TYPE_GCS,
- mavutil.mavlink.MAV_AUTOPILOT_INVALID,
- 0,
- 0,
- 0,
- )
- msg = listener.recv_match(type="HEARTBEAT", blocking=True, timeout=0.2)
- if msg is not None:
- target_system = int(msg.get_srcSystem())
- target_component = int(msg.get_srcComponent())
- break
-
- sender.mav.request_data_stream_send(
- target_system,
- target_component,
- int(mavutil.mavlink.MAV_DATA_STREAM_EXTENDED_STATUS),
- int(stream_cfg["ext_status_rate_hz"]),
- 1 if int(stream_cfg["ext_status_rate_hz"]) > 0 else 0,
- )
- sender.mav.request_data_stream_send(
- target_system,
- target_component,
- int(mavutil.mavlink.MAV_DATA_STREAM_RC_CHANNELS),
- int(stream_cfg["rc_chan_rate_hz"]),
- 1 if int(stream_cfg["rc_chan_rate_hz"]) > 0 else 0,
- )
- sender.mav.request_data_stream_send(
- target_system,
- target_component,
- int(mavutil.mavlink.MAV_DATA_STREAM_POSITION),
- int(stream_cfg["pos_rate_hz"]),
- 1 if int(stream_cfg["pos_rate_hz"]) > 0 else 0,
- )
- sender.mav.request_data_stream_send(
- target_system,
- target_component,
- int(mavutil.mavlink.MAV_DATA_STREAM_EXTRA1),
- int(stream_cfg["extra1_rate_hz"]),
- 1 if int(stream_cfg["extra1_rate_hz"]) > 0 else 0,
- )
- sender.mav.request_data_stream_send(
- target_system,
- target_component,
- int(mavutil.mavlink.MAV_DATA_STREAM_EXTRA2),
- int(stream_cfg["extra2_rate_hz"]),
- 1 if int(stream_cfg["extra2_rate_hz"]) > 0 else 0,
- )
- sender.mav.request_data_stream_send(
- target_system,
- target_component,
- int(mavutil.mavlink.MAV_DATA_STREAM_EXTRA3),
- int(stream_cfg["extra3_rate_hz"]),
- 1 if int(stream_cfg["extra3_rate_hz"]) > 0 else 0,
- )
- sender.mav.command_long_send(
- target_system,
- target_component,
- MAV_CMD_SET_MESSAGE_INTERVAL,
- 0,
- float(MAVLINK_MSG_ID_HEARTBEAT),
- float(int(1_000_000.0 / heartbeat_expected_hz)),
- 0,
- 0,
- 0,
- 0,
- 0,
- )
-
- hb_count = 0
- hb_est_lost = 0
- last_hb_t: float | None = None
- rc_count = 0
- rc_est_lost = 0
- last_rc_t: float | None = None
- rc_mismatch = 0
- command_sent = 0
- command_ack_total = 0
- command_ack_ok = 0
- msp_success = 0
- msp_fail = 0
- msp_mismatch = 0
- rc_sent = 0
- fc_cpu_load_samples: List[float] = []
- fc_cycle_time_samples: List[float] = []
- fc_status_fail = 0
- fc_status_last_error = ""
-
- rc_period_s = 1.0 / rc_tx_hz
- next_rc_send_t = time.monotonic()
- command_period_s = 0.0 if command_rate_hz <= 0 else (1.0 / command_rate_hz)
- next_command_send_t = next_rc_send_t
- next_heartbeat_send_t = next_rc_send_t
-
- prev_sample_t = time.monotonic()
- next_resource_sample_t = prev_sample_t + 1.0
- next_msp_poll_t = prev_sample_t + (1.0 / msp_poll_hz)
- workload_end_t = prev_sample_t + duration_s
-
- with (MSPApi(tcp_endpoint=f"127.0.0.1:{msp_port}") if msp_enabled else contextlib.nullcontext()) as msp_api:
- if msp_enabled:
- msp_api._serial._max_retries = 1
- msp_api._serial._reconnect_delay = 0.05
- while time.monotonic() < workload_end_t:
- now = time.monotonic()
-
- if now >= next_heartbeat_send_t:
- listener.mav.heartbeat_send(
- mavutil.mavlink.MAV_TYPE_GCS,
- mavutil.mavlink.MAV_AUTOPILOT_INVALID,
- 0,
- 0,
- 0,
- )
- sender.mav.heartbeat_send(
- mavutil.mavlink.MAV_TYPE_GCS,
- mavutil.mavlink.MAV_AUTOPILOT_INVALID,
- 0,
- 0,
- 0,
- )
- next_heartbeat_send_t += 1.0
- if next_heartbeat_send_t < now:
- next_heartbeat_send_t = now + 1.0
-
- if now >= next_rc_send_t:
- sender.mav.rc_channels_override_send(target_system, target_component, *CHANNELS[:8])
- rc_sent += 1
- next_rc_send_t += rc_period_s
- if next_rc_send_t < now:
- next_rc_send_t = now + rc_period_s
-
- if command_period_s > 0 and now >= next_command_send_t:
- sender.mav.command_long_send(
- target_system,
- target_component,
- MAV_CMD_REQUEST_MESSAGE,
- 0,
- float(command_message_id),
- 0,
- 0,
- 0,
- 0,
- 0,
- 0,
- )
- command_sent += 1
- next_command_send_t += command_period_s
- if next_command_send_t < now:
- next_command_send_t = now + command_period_s
-
- while True:
- try:
- msg = listener.recv_match(blocking=False)
- except (ConnectionRefusedError, OSError):
- wait_for_tcp_port("127.0.0.1", rc_port, float(tests_cfg["port_ready_timeout_s"]))
- break
- if msg is None:
- break
- msg_type = msg.get_type()
- if msg_type == "HEARTBEAT":
- target_system = int(msg.get_srcSystem())
- target_component = int(msg.get_srcComponent())
- hb_count += 1
- if last_hb_t is not None:
- dt = now - last_hb_t
- hb_est_lost += max(int(math.floor(dt * heartbeat_expected_hz) - 1), 0)
- last_hb_t = now
- elif msg_type == "RC_CHANNELS":
- rc_count += 1
- if last_rc_t is not None:
- dt = now - last_rc_t
- rc_est_lost += max(int(math.floor(dt * rc_expected_hz) - 1), 0)
- last_rc_t = now
- if (
- abs(int(msg.chan1_raw) - CHANNELS[0]) > 20
- or abs(int(msg.chan2_raw) - CHANNELS[1]) > 20
- or abs(int(msg.chan3_raw) - CHANNELS[2]) > 20
- or abs(int(msg.chan4_raw) - CHANNELS[3]) > 20
- ):
- rc_mismatch += 1
- elif msg_type == "COMMAND_ACK":
- if int(msg.command) == MAV_CMD_REQUEST_MESSAGE:
- command_ack_total += 1
- if int(msg.result) == int(mavutil.mavlink.MAV_RESULT_ACCEPTED):
- command_ack_ok += 1
-
- if msp_enabled and now >= next_msp_poll_t:
- try:
- _, payload = msp_api._request_raw(InavMSP.MSP_RC, timeout=msp_request_timeout_s)
- if len(payload) % 2:
- raise ValueError("MSP RC payload length must be even")
- channel_count = len(payload) // 2
- channels = list(struct.unpack(f"<{channel_count}H", payload))
- msp_success += 1
- if (
- abs(channels[0] - CHANNELS[0]) > 40
- or abs(channels[1] - CHANNELS[1]) > 40
- or abs(channels[2] - CHANNELS[2]) > 40
- or abs(channels[3] - CHANNELS[3]) > 40
- ):
- msp_mismatch += 1
- except (SerialException, RuntimeError, TimeoutError, ConnectionRefusedError):
- msp_fail += 1
- next_msp_poll_t += 1.0 / msp_poll_hz
-
- if now >= next_resource_sample_t:
- if msp_enabled:
- try:
- status = msp_api.get_inav_status()
- fc_cpu_load_samples.append(float(status["cpuLoad"]))
- fc_cycle_time_samples.append(float(status["cycleTime"]))
- except (SerialException, RuntimeError, TimeoutError, ConnectionRefusedError, KeyError, ValueError) as exc:
- fc_status_fail += 1
- fc_status_last_error = str(exc)
- prev_sample_t = now
- next_resource_sample_t += 1.0
-
- time.sleep(0.001)
-
- if msp_enabled and not fc_cpu_load_samples:
- raise RuntimeError(f"No MSP2_INAV_STATUS samples collected; last_error={fc_status_last_error} fail_count={fc_status_fail}")
-
- listener.close()
- sender.close()
-
- hb_total = hb_count + hb_est_lost
- rc_total = rc_count + rc_est_lost
- return {
- "duration_s": duration_s,
- "heartbeat_count": hb_count,
- "heartbeat_est_lost": hb_est_lost,
- "heartbeat_loss_rate": (hb_est_lost / hb_total) if hb_total > 0 else 0.0,
- "rc_count": rc_count,
- "rc_est_lost": rc_est_lost,
- "rc_loss_rate": (rc_est_lost / rc_total) if rc_total > 0 else 0.0,
- "rc_mismatch": rc_mismatch,
- "rc_mismatch_rate": (rc_mismatch / max(rc_count, 1)),
- "msp_success": msp_success,
- "msp_fail": msp_fail,
- "msp_failure_rate": (msp_fail / max(msp_success + msp_fail, 1)),
- "msp_mismatch": msp_mismatch,
- "msp_mismatch_rate": (msp_mismatch / max(msp_success, 1)),
- "command_sent": command_sent,
- "command_ack_total": command_ack_total,
- "command_ack_ok": command_ack_ok,
- "command_ack_failure_rate": ((command_sent - command_ack_total) / command_sent) if command_sent > 0 else 0.0,
- "command_ack_non_ok_rate": ((command_ack_total - command_ack_ok) / command_ack_total) if command_ack_total > 0 else 0.0,
- "rc_sent": rc_sent,
- "rc_sent_hz": (rc_sent / max(duration_s, 1e-6)),
- "fc_cpu_load_avg_pct": (sum(fc_cpu_load_samples) / len(fc_cpu_load_samples)) if fc_cpu_load_samples else 0.0,
- "fc_cpu_load_max_pct": max(fc_cpu_load_samples) if fc_cpu_load_samples else 0.0,
- "fc_cycle_time_avg_us": (sum(fc_cycle_time_samples) / len(fc_cycle_time_samples)) if fc_cycle_time_samples else 0.0,
- "fc_cycle_time_max_us": max(fc_cycle_time_samples) if fc_cycle_time_samples else 0.0,
- "fc_status_samples": len(fc_cpu_load_samples),
- }
-
-
-def write_report(config: Dict[str, Any], baseline: Dict[str, Any], stress: Dict[str, Any]) -> None:
- out_path = Path(config["output"]["testing_md"])
- branch_name = str(config.get("meta", {}).get("branch_name", "unknown"))
- timestamp = datetime.now(timezone.utc).isoformat()
- lines: List[str] = []
- lines.append(f"# MAVLink Single-Port Baseline (`{branch_name}`)")
- lines.append("")
- lines.append(f"- Generated: `{timestamp}`")
- lines.append(f"- Branch: `{branch_name}`")
- lines.append(f"- SITL binary: `{config['sitl']['binary']}`")
- lines.append(f"- EEPROM: `{config['sitl']['eeprom_path']}`")
- lines.append("- MSP kept on UART1 by design (`serial 0 ... functionMask=1`).")
- lines.append("- CLI under test sets `receiver_type=SERIAL` and `serialrx_provider=MAVLINK`.")
- lines.append("- Stream rates are configured at runtime via MAVLink `REQUEST_DATA_STREAM` and `MAV_CMD_SET_MESSAGE_INTERVAL`.")
- lines.append(
- f"- CLI baud config: `rc_baud={config['cli']['rc_baud']}`, "
- f"`telemetry_baud={config['cli'].get('telemetry_baud', config['cli']['rc_baud'])}`."
- )
- lines.append("")
- lines.append("## Baseline: Single MAVLink RC+Telemetry Port")
- lines.append("")
- lines.append(
- f"- Duration: `{baseline['duration_s']}s` | FC cpuLoad avg/max: `{baseline['fc_cpu_load_avg_pct']:.2f}% / {baseline['fc_cpu_load_max_pct']:.2f}%` | "
- f"FC cycleTime avg/max: `{baseline['fc_cycle_time_avg_us']:.1f} / {baseline['fc_cycle_time_max_us']:.1f}` us | "
- f"Status samples: `{baseline['fc_status_samples']}`"
- )
- lines.append(
- f"- MSP success/fail: `{baseline['msp_success']}/{baseline['msp_fail']}` | MSP failure rate: `{baseline['msp_failure_rate']:.4f}` | "
- f"MSP RC mismatch rate: `{baseline['msp_mismatch_rate']:.4f}`"
- )
- lines.append(f"- RC override send rate: `{baseline['rc_sent_hz']:.2f} Hz` (`{baseline['rc_sent']}` packets)")
- lines.append(
- f"- HB count/loss: `{baseline['heartbeat_count']}/{baseline['heartbeat_est_lost']}` | HB loss rate: `{baseline['heartbeat_loss_rate']:.4f}`"
- )
- lines.append(
- f"- RC count/loss: `{baseline['rc_count']}/{baseline['rc_est_lost']}` | RC loss rate: `{baseline['rc_loss_rate']:.4f}` | "
- f"RC mismatch rate: `{baseline['rc_mismatch_rate']:.4f}`"
- )
- lines.append("")
- lines.append("## Stress: Single Port Overload")
- lines.append("")
- lines.append(
- f"- Command load: `{config['tests']['stress_rate_hz']} req/s` for `{stress['duration_s']}s` | "
- f"FC cpuLoad avg/max: `{stress['fc_cpu_load_avg_pct']:.2f}% / {stress['fc_cpu_load_max_pct']:.2f}%` | "
- f"FC cycleTime avg/max: `{stress['fc_cycle_time_avg_us']:.1f} / {stress['fc_cycle_time_max_us']:.1f}` us | "
- f"Status samples: `{stress['fc_status_samples']}`"
- )
- lines.append(
- f"- MSP success/fail: `{stress['msp_success']}/{stress['msp_fail']}` | MSP failure rate: `{stress['msp_failure_rate']:.4f}` | "
- f"MSP RC mismatch rate: `{stress['msp_mismatch_rate']:.4f}`"
- )
- lines.append(f"- RC override send rate: `{stress['rc_sent_hz']:.2f} Hz` (`{stress['rc_sent']}` packets)")
- lines.append(
- f"- HB count/loss: `{stress['heartbeat_count']}/{stress['heartbeat_est_lost']}` | HB loss rate: `{stress['heartbeat_loss_rate']:.4f}`"
- )
- lines.append(
- f"- RC count/loss: `{stress['rc_count']}/{stress['rc_est_lost']}` | RC loss rate: `{stress['rc_loss_rate']:.4f}` | "
- f"RC mismatch rate: `{stress['rc_mismatch_rate']:.4f}`"
- )
- lines.append(
- f"- Command sent/ack: `{stress['command_sent']}/{stress['command_ack_total']}` | "
- f"ack failure rate: `{stress['command_ack_failure_rate']:.4f}` | non-ok ack rate: `{stress['command_ack_non_ok_rate']:.4f}`"
- )
- out_path.parent.mkdir(parents=True, exist_ok=True)
- out_path.write_text("\n".join(lines) + "\n", encoding="utf-8")
-
-
-if __name__ == "__main__":
- parser = argparse.ArgumentParser(description="Run single-port MAVLink benchmark and write a baseline markdown report.")
- parser.add_argument("--config", required=True, help="YAML configuration path")
- args = parser.parse_args()
-
- config = load_config(Path(args.config))
- sitl_bin = Path(config["sitl"]["binary"])
- sitl_workdir = Path(config["sitl"]["workdir"])
- sitl_eeprom = str(config["sitl"]["eeprom_path"])
- sitl_log = Path(config["sitl"]["runtime_log"])
- sitl_log.parent.mkdir(parents=True, exist_ok=True)
-
- log_handle = sitl_log.open("w", encoding="utf-8")
- sitl_proc = subprocess.Popen(
- [str(sitl_bin), f"--path={sitl_eeprom}"],
- cwd=str(sitl_workdir),
- stdout=log_handle,
- stderr=subprocess.STDOUT,
- text=True,
- )
-
- try:
- wait_for_tcp_port("127.0.0.1", int(config["ports"]["msp"]), float(config["tests"]["port_ready_timeout_s"]))
- run_cli_commands("127.0.0.1", int(config["ports"]["msp"]), build_cli_commands(config))
- wait_for_tcp_port("127.0.0.1", int(config["ports"]["msp"]), float(config["tests"]["port_ready_timeout_s"]))
- wait_for_tcp_port("127.0.0.1", int(config["ports"]["rc"]), float(config["tests"]["port_ready_timeout_s"]))
-
- baseline = run_workload(
- config=config,
- sitl_pid=sitl_proc.pid,
- duration_s=float(config["tests"]["baseline_duration_s"]),
- command_rate_hz=0.0,
- )
- stress = run_workload(
- config=config,
- sitl_pid=sitl_proc.pid,
- duration_s=float(config["tests"]["stress_duration_s"]),
- command_rate_hz=float(config["tests"]["stress_rate_hz"]),
- rc_tx_hz_override=float(config["tests"]["rc_tx_hz_max"]),
- )
- write_report(config, baseline, stress)
- print(f"report_written={config['output']['testing_md']}", flush=True)
- finally:
- sitl_proc.terminate()
- try:
- sitl_proc.wait(timeout=5.0)
- except subprocess.TimeoutExpired:
- sitl_proc.kill()
- sitl_proc.wait(timeout=5.0)
- log_handle.close()
diff --git a/src/utils/mavlink_tests/mav_multi_sweep.py b/src/utils/mavlink_tests/mav_multi_sweep.py
index 0915e1a1485..bb7a38b741e 100644
--- a/src/utils/mavlink_tests/mav_multi_sweep.py
+++ b/src/utils/mavlink_tests/mav_multi_sweep.py
@@ -28,7 +28,7 @@
spec.loader.exec_module(benchmark)
-parser = argparse.ArgumentParser(description="Run MAVLink load sweep table for 1..4 ports and [50,100,200,max] req/s")
+parser = argparse.ArgumentParser(description="Run MAVLink total-load sweep table for 1..4 ports and [50,100,200,max] req/s total")
parser.add_argument("--config", default=str(DEFAULT_CONFIG_PATH), help="YAML configuration path")
args = parser.parse_args()
@@ -56,9 +56,9 @@
rate_cache: Dict[float, Dict[int, Dict[str, Any]]] = {}
-for label, rate_hz in rate_labels:
- if rate_hz not in rate_cache:
- rate_cache[rate_hz] = {}
+for label, total_rate_hz in rate_labels:
+ if total_rate_hz not in rate_cache:
+ rate_cache[total_rate_hz] = {}
for port_count in range(1, 5):
scenario_log = sitl_log.with_name(f"{sitl_log.stem}_{label}_{port_count}{sitl_log.suffix}")
log_handle = scenario_log.open("w", encoding="utf-8")
@@ -73,8 +73,12 @@
benchmark.wait_for_tcp_port("127.0.0.1", int(config["ports"]["msp"]), float(config["tests"]["port_ready_timeout_s"]))
benchmark.apply_config_and_wait(config, 4)
active_ports = [rc_port] + telemetry_ports[: max(0, port_count - 1)]
- load_rates_hz = {port: rate_hz for port in active_ports}
- print(f"sweep_run_start label={label} rate={rate_hz} ports={port_count}", flush=True)
+ per_port_rate_hz = total_rate_hz / float(port_count)
+ load_rates_hz = {port: per_port_rate_hz for port in active_ports}
+ print(
+ f"sweep_run_start label={label} total_rate={total_rate_hz} per_port_rate={per_port_rate_hz} ports={port_count}",
+ flush=True,
+ )
result = benchmark.run_workload(
config=config,
sitl_pid=sitl_proc.pid,
@@ -83,8 +87,11 @@
load_rates_hz=load_rates_hz,
duration_s=sweep_duration_s,
)
- rate_cache[rate_hz][port_count] = result
- print(f"sweep_run_done label={label} rate={rate_hz} ports={port_count}", flush=True)
+ rate_cache[total_rate_hz][port_count] = result
+ print(
+ f"sweep_run_done label={label} total_rate={total_rate_hz} per_port_rate={per_port_rate_hz} ports={port_count}",
+ flush=True,
+ )
finally:
sitl_proc.terminate()
try:
@@ -94,7 +101,7 @@
sitl_proc.wait(timeout=5.0)
log_handle.close()
scenario_log.unlink(missing_ok=True)
- results[label] = rate_cache[rate_hz]
+ results[label] = rate_cache[total_rate_hz]
output_path = Path(config["output"]["testing_md"])
lines: List[str] = [
@@ -106,14 +113,15 @@
"- UART1 MSP only.",
"- UART2 is MAVLink RC (460800), RC override target is 100 Hz.",
"- Additional MAVLink telemetry ports are 115200 baud.",
+ "- Total command rate is held constant per load label and split evenly across active MAVLink ports.",
"",
"## Comparison Table",
"",
- "| Load Label | Msg/s per active port | Active MAVLink ports | FC cpuLoad avg/max | FC cycleTime avg/max (us) | MAV seq loss max | Cmd failed total | Cmd failed % | MSP fail % |",
- "| --- | ---: | ---: | --- | --- | ---: | ---: | ---: | ---: |",
+ "| Load Label | Total Msg/s | Active MAVLink ports | Msg/s per active port | FC cpuLoad avg/max | FC cycleTime avg/max (us) | MAV seq loss max | Cmd failed total | Cmd failed % | MSP fail % |",
+ "| --- | ---: | ---: | ---: | --- | --- | ---: | ---: | ---: | ---: |",
]
-for label, rate_hz in rate_labels:
+for label, total_rate_hz in rate_labels:
rate_results = results[label]
for port_count in range(1, 5):
result = rate_results[port_count]
@@ -122,8 +130,9 @@
cmd_sent_total = sum(int(item["command_sent"]) for item in per_port)
cmd_failed_total = sum(int(item["command_failed_total"]) for item in per_port)
cmd_failed_pct = (cmd_failed_total / max(cmd_sent_total, 1)) * 100.0
+ per_port_rate_hz = total_rate_hz / float(port_count)
lines.append(
- f"| {label} | {rate_hz:.1f} | {port_count} | "
+ f"| {label} | {total_rate_hz:.1f} | {port_count} | {per_port_rate_hz:.2f} | "
f"{result['fc_cpu_load_avg_pct']:.2f}% / {result['fc_cpu_load_max_pct']:.2f}% | "
f"{result['fc_cycle_time_avg_us']:.1f} / {result['fc_cycle_time_max_us']:.1f} | "
f"{mav_seq_loss_max_pct:.2f}% | {cmd_failed_total} | {cmd_failed_pct:.2f}% | {(result['msp_failure_rate'] * 100.0):.2f}% |"
@@ -132,13 +141,16 @@
lines.append("")
lines.append("## Raw Scenario Details")
lines.append("")
-for label, rate_hz in rate_labels:
- lines.append(f"### {label} ({rate_hz:.1f} msg/s per active port)")
+for label, total_rate_hz in rate_labels:
+ lines.append(f"### {label} ({total_rate_hz:.1f} total msg/s)")
lines.append("")
for port_count in range(1, 5):
result = results[label][port_count]
+ per_port_rate_hz = total_rate_hz / float(port_count)
lines.append(f"#### {port_count} active MAVLink port(s)")
lines.append("")
+ lines.append(f"- Total command rate: `{total_rate_hz:.1f} msg/s`")
+ lines.append(f"- Per-port command rate: `{per_port_rate_hz:.2f} msg/s`")
lines.append(
f"- FC cpuLoad avg/max: `{result['fc_cpu_load_avg_pct']:.2f}% / {result['fc_cpu_load_max_pct']:.2f}%` | "
f"FC cycleTime avg/max: `{result['fc_cycle_time_avg_us']:.1f} / {result['fc_cycle_time_max_us']:.1f}` us | "
From 13cb589aef26ac68791bd75b771930a20b858c77 Mon Sep 17 00:00:00 2001
From: frogmane <7685285+xznhj8129@users.noreply.github.com>
Date: Thu, 5 Mar 2026 14:15:57 -0500
Subject: [PATCH 29/46] mission upload drop guard, split telemetry messages,
port handling fixes
---
src/main/telemetry/mavlink.c | 217 ++++++++++++++----
src/main/telemetry/mavlink.h | 4 +-
.../mavlink_tests/mav_multi_benchmark.py | 61 ++++-
3 files changed, 229 insertions(+), 53 deletions(-)
diff --git a/src/main/telemetry/mavlink.c b/src/main/telemetry/mavlink.c
index 713c0967f0f..508eaea4062 100644
--- a/src/main/telemetry/mavlink.c
+++ b/src/main/telemetry/mavlink.c
@@ -355,6 +355,8 @@ static void freeMAVLinkTelemetryPortByIndex(uint8_t portIndex)
state->lastMavlinkMessageUs = 0;
state->lastHighLatencyMessageUs = 0;
state->highLatencyEnabled = mavlinkGetPortConfig(portIndex)->high_latency;
+ state->txSeq = 0;
+ state->txDroppedFrames = 0;
memset(&state->mavRecvStatus, 0, sizeof(state->mavRecvStatus));
memset(&state->mavRecvMsg, 0, sizeof(state->mavRecvMsg));
}
@@ -419,6 +421,8 @@ static void configureMAVLinkTelemetryPort(uint8_t portIndex)
state->lastMavlinkMessageUs = 0;
state->lastHighLatencyMessageUs = 0;
state->highLatencyEnabled = mavlinkGetPortConfig(portIndex)->high_latency;
+ state->txSeq = 0;
+ state->txDroppedFrames = 0;
memset(&state->mavRecvStatus, 0, sizeof(state->mavRecvStatus));
memset(&state->mavRecvMsg, 0, sizeof(state->mavRecvMsg));
}
@@ -452,8 +456,10 @@ void checkMAVLinkTelemetryState(void)
static void mavlinkSendMessage(void)
{
- uint8_t mavBuffer[MAVLINK_MAX_PACKET_LEN];
- int msgLength = mavlink_msg_to_send_buffer(mavBuffer, &mavSendMsg);
+ const mavlink_msg_entry_t *msgEntry = mavlink_get_msg_entry(mavSendMsg.msgid);
+ if (!msgEntry) {
+ return;
+ }
for (uint8_t portIndex = 0; portIndex < mavPortCount; portIndex++) {
if ((mavSendMask & MAVLINK_PORT_MASK(portIndex)) == 0) {
@@ -465,9 +471,39 @@ static void mavlinkSendMessage(void)
continue;
}
- for (int i = 0; i < msgLength; i++) {
- serialWrite(state->port, mavBuffer[i]);
+ mavlink_status_t txStatus = { 0 };
+ txStatus.current_tx_seq = state->txSeq;
+ if (mavlinkGetProtocolVersion() == 1) {
+ txStatus.flags |= MAVLINK_STATUS_FLAG_OUT_MAVLINK1;
+ }
+
+ mavlink_message_t txMsg = mavSendMsg;
+ mavlink_finalize_message_buffer(
+ &txMsg,
+ txMsg.sysid,
+ txMsg.compid,
+ &txStatus,
+ msgEntry->min_msg_len,
+ txMsg.len,
+ msgEntry->crc_extra
+ );
+ state->txSeq = txStatus.current_tx_seq;
+
+ uint8_t mavBuffer[MAVLINK_MAX_PACKET_LEN];
+ const int msgLength = mavlink_msg_to_send_buffer(mavBuffer, &txMsg);
+ if (msgLength <= 0) {
+ continue;
+ }
+
+ // Drop the frame on this port if there is no room; do not block telemetry task.
+ if (serialTxBytesFree(state->port) < (uint32_t)msgLength) {
+ state->txDroppedFrames++;
+ continue;
}
+
+ serialBeginWrite(state->port);
+ serialWriteBuf(state->port, mavBuffer, msgLength);
+ serialEndWrite(state->port);
}
}
@@ -1181,6 +1217,8 @@ void mavlinkSendVfrHud(void)
mavlinkSendMessage();
}
+static uint8_t mavlinkGetAutopilotEnum(void);
+
void mavlinkSendHeartbeat(void)
{
uint8_t mavModes = MAV_MODE_FLAG_CUSTOM_MODE_ENABLED;
@@ -1230,18 +1268,11 @@ void mavlinkSendHeartbeat(void)
mavSystemState = MAV_STATE_STANDBY;
}
- uint8_t mavType;
- if (mavAutopilotType == MAVLINK_AUTOPILOT_ARDUPILOT) {
- mavType = MAV_AUTOPILOT_ARDUPILOTMEGA;
- } else {
- mavType = MAV_AUTOPILOT_GENERIC;
- }
-
mavlink_msg_heartbeat_pack(mavSystemId, mavComponentId, &mavSendMsg,
// type Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
mavSystemType,
// autopilot Autopilot type / class. defined in MAV_AUTOPILOT ENUM
- mavType,
+ mavlinkGetAutopilotEnum(),
// base_mode System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h
mavModes,
// custom_mode A bitfield for use for autopilot-specific flags.
@@ -1252,7 +1283,7 @@ void mavlinkSendHeartbeat(void)
mavlinkSendMessage();
}
-void mavlinkSendBatteryTemperatureStatusText(void)
+static void mavlinkSendBatteryStatus(void)
{
uint16_t batteryVoltages[MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_LEN];
uint16_t batteryVoltagesExt[MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_EXT_LEN];
@@ -1308,8 +1339,10 @@ void mavlinkSendBatteryTemperatureStatusText(void)
0);
mavlinkSendMessage();
+}
-
+static void mavlinkSendScaledPressure(void)
+{
int16_t temperature;
sensors(SENSOR_BARO) ? getBaroTemperature(&temperature) : getIMUTemperature(&temperature);
mavlink_msg_scaled_pressure_pack(mavSystemId, mavComponentId, &mavSendMsg,
@@ -1320,7 +1353,10 @@ void mavlinkSendBatteryTemperatureStatusText(void)
0);
mavlinkSendMessage();
+}
+static bool mavlinkSendStatusText(void)
+{
// FIXME - Status text is limited to boards with USE_OSD
#ifdef USE_OSD
char buff[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN] = {" "};
@@ -1340,10 +1376,17 @@ void mavlinkSendBatteryTemperatureStatusText(void)
0);
mavlinkSendMessage();
+ return true;
}
#endif
+ return false;
+}
-
+void mavlinkSendBatteryTemperatureStatusText(void)
+{
+ mavlinkSendBatteryStatus();
+ mavlinkSendScaledPressure();
+ mavlinkSendStatusText();
}
static uint8_t mavlinkGetAutopilotEnum(void)
@@ -1577,6 +1620,8 @@ void processMAVLinkTelemetry(timeUs_t currentTimeUs)
}
+static void mavlinkResetIncomingMissionTransaction(void);
+
static bool handleIncoming_MISSION_CLEAR_ALL(void)
{
mavlink_mission_clear_all_t msg;
@@ -1585,6 +1630,7 @@ static bool handleIncoming_MISSION_CLEAR_ALL(void)
// Check if this message is for us
if (msg.target_system == mavSystemId) {
resetWaypointList();
+ mavlinkResetIncomingMissionTransaction();
mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, MAV_MISSION_ACCEPTED, MAV_MISSION_TYPE_MISSION, 0);
mavlinkSendMessage();
return true;
@@ -1594,11 +1640,66 @@ static bool handleIncoming_MISSION_CLEAR_ALL(void)
}
// Static state for MISSION UPLOAD transaction (starting with MISSION_COUNT)
+#define MAVLINK_MISSION_UPLOAD_TIMEOUT_MS 10000
static int incomingMissionWpCount = 0;
static int incomingMissionWpSequence = 0;
+static uint8_t incomingMissionSourceSystem = 0;
+static uint8_t incomingMissionSourceComponent = 0;
+static timeMs_t incomingMissionLastActivityMs = 0;
+
+static void mavlinkResetIncomingMissionTransaction(void)
+{
+ incomingMissionWpCount = 0;
+ incomingMissionWpSequence = 0;
+ incomingMissionSourceSystem = 0;
+ incomingMissionSourceComponent = 0;
+ incomingMissionLastActivityMs = 0;
+}
+
+static void mavlinkStartIncomingMissionTransaction(int missionCount)
+{
+ incomingMissionWpCount = missionCount;
+ incomingMissionWpSequence = 0;
+ incomingMissionSourceSystem = mavRecvMsg.sysid;
+ incomingMissionSourceComponent = mavRecvMsg.compid;
+ incomingMissionLastActivityMs = millis();
+}
+
+static void mavlinkTouchIncomingMissionTransaction(void)
+{
+ incomingMissionLastActivityMs = millis();
+}
+
+static bool mavlinkIsIncomingMissionTransactionActive(void)
+{
+ if (incomingMissionWpCount <= 0) {
+ return false;
+ }
+
+ if ((timeMs_t)(millis() - incomingMissionLastActivityMs) > MAVLINK_MISSION_UPLOAD_TIMEOUT_MS) {
+ mavlinkResetIncomingMissionTransaction();
+ return false;
+ }
+
+ return true;
+}
+
+static bool mavlinkIsIncomingMissionTransactionOwner(void)
+{
+ return mavRecvMsg.sysid == incomingMissionSourceSystem &&
+ mavRecvMsg.compid == incomingMissionSourceComponent;
+}
static bool mavlinkHandleMissionItemCommon(bool useIntMessages, uint8_t frame, uint16_t command, uint8_t autocontinue, uint16_t seq, float param1, float param2, float param3, float param4, int32_t lat, int32_t lon, float altMeters)
{
+ if (!mavlinkIsIncomingMissionTransactionActive() || !mavlinkIsIncomingMissionTransactionOwner()) {
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, MAV_MISSION_INVALID_SEQUENCE, MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
+ return true;
+ }
+
+ mavlinkTouchIncomingMissionTransaction();
+
if (autocontinue == 0) {
mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, MAV_MISSION_UNSUPPORTED, MAV_MISSION_TYPE_MISSION, 0);
mavlinkSendMessage();
@@ -1773,6 +1874,7 @@ static bool mavlinkHandleMissionItemCommon(bool useIntMessages, uint8_t frame, u
mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, MAV_MISSION_INVALID, MAV_MISSION_TYPE_MISSION, 0);
mavlinkSendMessage();
}
+ mavlinkResetIncomingMissionTransaction();
}
else {
if (useIntMessages) {
@@ -1786,6 +1888,7 @@ static bool mavlinkHandleMissionItemCommon(bool useIntMessages, uint8_t frame, u
else {
// If we get a duplicate of the last accepted item, re-request the next one instead of aborting.
if (seq + 1 == incomingMissionWpSequence) {
+ mavlinkTouchIncomingMissionTransaction();
if (useIntMessages) {
mavlink_msg_mission_request_int_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, incomingMissionWpSequence, MAV_MISSION_TYPE_MISSION);
} else {
@@ -1808,14 +1911,20 @@ static bool handleIncoming_MISSION_COUNT(void)
// Check if this message is for us
if (msg.target_system == mavSystemId) {
+ mavlinkResetIncomingMissionTransaction();
if (ARMING_FLAG(ARMED)) {
mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, MAV_MISSION_ERROR, MAV_MISSION_TYPE_MISSION, 0);
mavlinkSendMessage();
return true;
}
+ if (msg.count == 0) {
+ resetWaypointList();
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, MAV_MISSION_ACCEPTED, MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
+ return true;
+ }
if (msg.count <= NAV_MAX_WAYPOINTS) {
- incomingMissionWpCount = msg.count; // We need to know how many items to request
- incomingMissionWpSequence = 0;
+ mavlinkStartIncomingMissionTransaction(msg.count);
mavlink_msg_mission_request_int_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, incomingMissionWpSequence, MAV_MISSION_TYPE_MISSION);
mavlinkSendMessage();
return true;
@@ -2256,10 +2365,16 @@ static bool handleIncoming_COMMAND(uint8_t targetSystem, uint8_t targetComponent
#endif
break;
case MAVLINK_MSG_ID_BATTERY_STATUS:
+ mavlinkSendBatteryStatus();
+ sent = true;
+ break;
case MAVLINK_MSG_ID_SCALED_PRESSURE:
- mavlinkSendBatteryTemperatureStatusText();
+ mavlinkSendScaledPressure();
sent = true;
break;
+ case MAVLINK_MSG_ID_STATUSTEXT:
+ sent = mavlinkSendStatusText();
+ break;
case MAVLINK_MSG_ID_HOME_POSITION:
#ifdef USE_GPS
if (STATE(GPS_FIX_HOME)) {
@@ -2651,20 +2766,48 @@ static void mavlinkExtractTargets(const mavlink_message_t *msg, int16_t *targetS
}
}
-static bool mavlinkRouteMatchesTargetOnPort(uint8_t portIndex, int16_t targetSystem, int16_t targetComponent)
+static uint8_t mavlinkComputeForwardMask(uint8_t ingressPortIndex, int16_t targetSystem, int16_t targetComponent)
{
+ uint8_t mask = 0;
+
+ if (targetSystem <= 0) {
+ for (uint8_t portIndex = 0; portIndex < mavPortCount; portIndex++) {
+ if (portIndex == ingressPortIndex) {
+ continue;
+ }
+
+ const mavlinkPortRuntime_t *state = &mavPortStates[portIndex];
+ if (!state->telemetryEnabled || !state->port) {
+ continue;
+ }
+
+ mask |= MAVLINK_PORT_MASK(portIndex);
+ }
+ return mask;
+ }
+
for (uint8_t routeIndex = 0; routeIndex < mavRouteCount; routeIndex++) {
const mavlinkRouteEntry_t *route = &mavRouteTable[routeIndex];
- if (route->ingressPortIndex != portIndex || route->sysid != targetSystem) {
+
+ if (route->sysid != targetSystem) {
+ continue;
+ }
+ if (targetComponent > 0 && route->compid != targetComponent) {
+ continue;
+ }
+ if (route->ingressPortIndex == ingressPortIndex || route->ingressPortIndex >= mavPortCount) {
continue;
}
- if (targetComponent <= 0 || route->compid == targetComponent) {
- return true;
+ const mavlinkPortRuntime_t *state = &mavPortStates[route->ingressPortIndex];
+ if (!state->telemetryEnabled || !state->port) {
+ continue;
}
+
+ mask |= MAVLINK_PORT_MASK(route->ingressPortIndex);
}
- return false;
+ return mask;
}
static void mavlinkForwardMessage(uint8_t ingressPortIndex, int16_t targetSystem, int16_t targetComponent)
@@ -2675,31 +2818,25 @@ static void mavlinkForwardMessage(uint8_t ingressPortIndex, int16_t targetSystem
uint8_t mavBuffer[MAVLINK_MAX_PACKET_LEN];
const int msgLength = mavlink_msg_to_send_buffer(mavBuffer, &mavRecvMsg);
+ if (msgLength <= 0) {
+ return;
+ }
+ const uint8_t forwardMask = mavlinkComputeForwardMask(ingressPortIndex, targetSystem, targetComponent);
for (uint8_t portIndex = 0; portIndex < mavPortCount; portIndex++) {
- if (portIndex == ingressPortIndex) {
+ if ((forwardMask & MAVLINK_PORT_MASK(portIndex)) == 0) {
continue;
}
- const mavlinkPortRuntime_t *state = &mavPortStates[portIndex];
- if (!state->telemetryEnabled || !state->port) {
- continue;
- }
-
- bool shouldForward = false;
- if (targetSystem <= 0) {
- shouldForward = true;
- } else if (mavlinkRouteMatchesTargetOnPort(portIndex, targetSystem, targetComponent)) {
- shouldForward = true;
- }
-
- if (!shouldForward) {
+ mavlinkPortRuntime_t *state = &mavPortStates[portIndex];
+ if (serialTxBytesFree(state->port) < (uint32_t)msgLength) {
+ state->txDroppedFrames++;
continue;
}
- for (int i = 0; i < msgLength; i++) {
- serialWrite(state->port, mavBuffer[i]);
- }
+ serialBeginWrite(state->port);
+ serialWriteBuf(state->port, mavBuffer, msgLength);
+ serialEndWrite(state->port);
}
}
diff --git a/src/main/telemetry/mavlink.h b/src/main/telemetry/mavlink.h
index d774e6cb07b..60b77237d0a 100755
--- a/src/main/telemetry/mavlink.h
+++ b/src/main/telemetry/mavlink.h
@@ -57,7 +57,7 @@ typedef enum {
* MAVLink requires angles to be in the range -Pi..Pi.
* This converts angles from a range of 0..Pi to -Pi..Pi
*/
-#define RADIANS_TO_MAVLINK_RANGE(angle) (angle > M_PIf) ? angle - (2 * M_PIf) : angle
+#define RADIANS_TO_MAVLINK_RANGE(angle) (((angle) > M_PIf) ? ((angle) - (2 * M_PIf)) : (angle))
/** @brief A mapping of plane flight modes for custom_mode field of heartbeat. */
typedef enum APM_PLANE_MODE
@@ -142,6 +142,8 @@ typedef struct mavlinkPortRuntime_s {
uint8_t mavRates[MAVLINK_STREAM_COUNT];
uint8_t mavRatesConfigured[MAVLINK_STREAM_COUNT];
uint8_t mavTicks[MAVLINK_STREAM_COUNT];
+ uint8_t txSeq;
+ uint32_t txDroppedFrames;
mavlink_message_t mavRecvMsg;
mavlink_status_t mavRecvStatus;
} mavlinkPortRuntime_t;
diff --git a/src/utils/mavlink_tests/mav_multi_benchmark.py b/src/utils/mavlink_tests/mav_multi_benchmark.py
index 97ce932a7f6..bb74da85779 100644
--- a/src/utils/mavlink_tests/mav_multi_benchmark.py
+++ b/src/utils/mavlink_tests/mav_multi_benchmark.py
@@ -40,6 +40,8 @@
MAV_CMD_REQUEST_MESSAGE = int(mavutil.mavlink.MAV_CMD_REQUEST_MESSAGE)
MAV_CMD_SET_MESSAGE_INTERVAL = int(mavutil.mavlink.MAV_CMD_SET_MESSAGE_INTERVAL)
MAVLINK_MSG_ID_HEARTBEAT = int(mavutil.mavlink.MAVLINK_MSG_ID_HEARTBEAT)
+MAV_AUTOPILOT_INVALID = int(mavutil.mavlink.MAV_AUTOPILOT_INVALID)
+MAV_TYPE_GCS = int(mavutil.mavlink.MAV_TYPE_GCS)
def load_config(config_path: Path) -> Dict[str, Any]:
@@ -61,6 +63,25 @@ def wait_for_tcp_port(host: str, port: int, timeout_s: float) -> None:
raise TimeoutError(f"TCP port {host}:{port} did not become available within {timeout_s}s")
+def wait_for_tcp_port_cycle(host: str, port: int, timeout_s: float) -> None:
+ deadline = time.monotonic() + timeout_s
+ saw_closed = False
+ while time.monotonic() < deadline:
+ try:
+ with socket.create_connection((host, port), timeout=1.0):
+ if saw_closed:
+ return
+ except (ConnectionRefusedError, socket.timeout, OSError):
+ saw_closed = True
+ time.sleep(0.2)
+
+ if saw_closed:
+ raise TimeoutError(f"TCP port {host}:{port} did not return after reboot within {timeout_s}s")
+
+ # If no close window was observed, treat it as already rebooted and just ensure the port is reachable.
+ wait_for_tcp_port(host, port, timeout_s)
+
+
def cli_read_until_prompt(cli_socket: socket.socket) -> str:
data = b""
while b"\n# " not in data:
@@ -85,7 +106,7 @@ def wait_for_cli_ready(host: str, port: int, timeout_s: float) -> None:
raise TimeoutError(f"CLI prompt did not become available on {host}:{port} within {timeout_s}s")
-def run_cli_commands(host: str, port: int, commands: List[str], reboot_timeout_s: float) -> None:
+def run_cli_commands(host: str, port: int, commands: List[str], reboot_timeout_s: float) -> bool:
sent_save = False
with socket.create_connection((host, port), timeout=5.0) as cli_socket:
cli_socket.settimeout(3.0)
@@ -100,6 +121,7 @@ def run_cli_commands(host: str, port: int, commands: List[str], reboot_timeout_s
if sent_save:
# Save triggers reboot; do not send '#' again because that re-enters CLI mode.
time.sleep(min(reboot_timeout_s, 1.0))
+ return sent_save
def build_serial_command(index: int, function_mask: int, baud: int) -> str:
@@ -140,12 +162,14 @@ def build_cli_config_commands(config: Dict[str, Any], mavlink_port_count: int) -
def apply_config_and_wait(config: Dict[str, Any], mavlink_port_count: int) -> None:
ports = config["ports"]
commands = build_cli_config_commands(config, mavlink_port_count)
- run_cli_commands(
+ sent_save = run_cli_commands(
"127.0.0.1",
int(ports["msp"]),
commands,
reboot_timeout_s=float(config["tests"]["save_reboot_timeout_s"]),
)
+ if sent_save:
+ wait_for_tcp_port_cycle("127.0.0.1", int(ports["msp"]), float(config["tests"]["save_reboot_timeout_s"]))
wait_for_tcp_port("127.0.0.1", int(ports["msp"]), float(config["tests"]["port_ready_timeout_s"]))
wait_for_tcp_port("127.0.0.1", int(ports["rc"]), float(config["tests"]["port_ready_timeout_s"]))
if mavlink_port_count >= 2:
@@ -196,6 +220,10 @@ def open_mavlink_tcp_connection(port: int, source_system: int, source_component:
time.sleep(0.2)
+def is_fc_heartbeat(msg: Any) -> bool:
+ return int(msg.autopilot) != MAV_AUTOPILOT_INVALID and int(msg.type) != MAV_TYPE_GCS
+
+
def run_workload(
config: Dict[str, Any],
sitl_pid: int,
@@ -263,6 +291,7 @@ def run_workload(
"mav_msg_count": 0,
"mav_seq_lost": 0,
"last_seq_by_source": {},
+ "seq_track_source": None,
}
for idx, port in enumerate(sorted(load_rates_hz.keys())):
@@ -341,8 +370,11 @@ def run_workload(
break
msg_type = msg.get_type()
if msg_type == "HEARTBEAT":
- targets[port] = (int(msg.get_srcSystem()), int(msg.get_srcComponent()))
- warmup_hb_seen[port] += 1
+ src_system = int(msg.get_srcSystem())
+ src_component = int(msg.get_srcComponent())
+ if is_fc_heartbeat(msg):
+ targets[port] = (src_system, src_component)
+ warmup_hb_seen[port] += 1
if telemetry_ports and all(count >= warmup_heartbeat_count for count in warmup_hb_seen.values()) and (now - warmup_start_t) >= warmup_s:
break
@@ -357,6 +389,7 @@ def run_workload(
for port, conn in listeners.items():
target_system, target_component = targets[port]
+ port_stats[port]["seq_track_source"] = (target_system, target_component)
conn.mav.request_data_stream_send(
target_system,
target_component,
@@ -510,16 +543,20 @@ def run_workload(
seq = int(header.seq)
if seq is not None:
src_key = (int(msg.get_srcSystem()), int(msg.get_srcComponent()))
- last_seq = stats["last_seq_by_source"].get(src_key)
- if last_seq is not None:
- seq_delta = (seq - int(last_seq)) & 0xFF
- if seq_delta > 0:
- stats["mav_seq_lost"] += max(seq_delta - 1, 0)
- stats["last_seq_by_source"][src_key] = seq
- stats["mav_msg_count"] += 1
+ if src_key == stats["seq_track_source"]:
+ last_seq = stats["last_seq_by_source"].get(src_key)
+ if last_seq is not None:
+ seq_delta = (seq - int(last_seq)) & 0xFF
+ if seq_delta > 0:
+ stats["mav_seq_lost"] += max(seq_delta - 1, 0)
+ stats["last_seq_by_source"][src_key] = seq
+ stats["mav_msg_count"] += 1
if msg_type == "HEARTBEAT":
- targets[port] = (int(msg.get_srcSystem()), int(msg.get_srcComponent()))
+ src_system = int(msg.get_srcSystem())
+ src_component = int(msg.get_srcComponent())
+ if is_fc_heartbeat(msg):
+ targets[port] = (src_system, src_component)
stats["heartbeat_count"] += 1
elif msg_type == "RC_CHANNELS":
stats["rc_count"] += 1
From 5c3b2eb146d5ac8e621a90fc7ed5e8f3907d0446 Mon Sep 17 00:00:00 2001
From: frogmane <7685285+xznhj8129@users.noreply.github.com>
Date: Sat, 7 Mar 2026 23:46:15 -0500
Subject: [PATCH 30/46] update mav_fix2 changes
---
docs/Mavlink.md | 5 +-
docs/development/msp/inav_enums.json | 5 +-
docs/development/msp/inav_enums_ref.md | 5 +-
src/main/fc/fc_msp.c | 4 +-
src/main/navigation/navigation.c | 6 +-
src/main/telemetry/mavlink.c | 277 ++++++++++-----
src/main/telemetry/mavlink.h | 2 +-
src/test/unit/mavlink_unittest.cc | 469 ++++++++++++++++++++++---
src/test/unit/platform.h | 1 +
9 files changed, 628 insertions(+), 146 deletions(-)
diff --git a/docs/Mavlink.md b/docs/Mavlink.md
index 1df23459fed..78c89e0d648 100644
--- a/docs/Mavlink.md
+++ b/docs/Mavlink.md
@@ -86,7 +86,8 @@ Messages are organized into MAVLink datastream groups. Each group sends **one me
- `MISSION_CLEAR_ALL`: clears stored mission.
- `COMMAND_LONG` / `COMMAND_INT`: command transport for supported `MAV_CMD_*` handlers.
- `REQUEST_DATA_STREAM`: legacy stream-rate control per stream group.
-- `SET_POSITION_TARGET_GLOBAL_INT`: writes the GCS-guided waypoint when the frame is supported.
+- `SET_POSITION_TARGET_GLOBAL_INT`: writes the GCS-guided waypoint when the frame is supported; altitude-only requests are also accepted when X/Y are masked out and GCS navigation is valid.
+- `SET_POSITION_TARGET_LOCAL_NED`: accepts altitude-only requests in `MAV_FRAME_LOCAL_OFFSET_NED` when X/Y are zero or ignored and GCS navigation is valid.
- `RC_CHANNELS_OVERRIDE` passes channel values to the MAVLink serial receiver backend.
- `RADIO_STATUS` updates remote TX buffer level and scales RSSI/SNR according to `mavlink_port1_radio_type` (also feeds link stats for MAVLink RX receivers).
- `ADSB_VEHICLE` populates the internal traffic list when ADS‑B is enabled.
@@ -101,7 +102,7 @@ Limited implementation of the Command protocol.
- `MAV_CMD_SET_MESSAGE_INTERVAL` / `MAV_CMD_GET_MESSAGE_INTERVAL`: adjust or query telemetry stream output for supported message IDs (streamed messages only; intervals slower than 1 Hz are not accepted).
- `MAV_CMD_GET_HOME_POSITION`: replies with `HOME_POSITION` when home fix exists.
- `MAV_CMD_REQUEST_MESSAGE`: emits one selected message (`HEARTBEAT`, `SYS_STATUS`, `ATTITUDE`, `VFR_HUD`, `AVAILABLE_MODES`, `CURRENT_MODE`, `EXTENDED_SYS_STATE`, RC channels, GPS/global/origin, battery/pressure, and `HOME_POSITION` when available) or `UNSUPPORTED`.
-- `MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES`: returns stub `AUTOPILOT_VERSION` (v2 only; v1 returns `UNSUPPORTED`).
+- `MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES`: returns stub `AUTOPILOT_VERSION` (v2 only; v1 returns `UNSUPPORTED`) advertising `SET_POSITION_TARGET_GLOBAL_INT` and `SET_POSITION_TARGET_LOCAL_NED`.
- `MAV_CMD_REQUEST_PROTOCOL_VERSION`: returns stub `PROTOCOL_VERSION` (v2 only; v1 returns `UNSUPPORTED`).
## Mode mappings (INAV → MAVLink/ArduPilot)
diff --git a/docs/development/msp/inav_enums.json b/docs/development/msp/inav_enums.json
index 69a74420887..63121588b83 100644
--- a/docs/development/msp/inav_enums.json
+++ b/docs/development/msp/inav_enums.json
@@ -3302,9 +3302,8 @@
"_source": "inav/src/main/io/displayport_msp_osd.c",
"SD_3016": "0",
"HD_5018": "1",
- "HD_3016": "2",
- "HD_6022": "3",
- "HD_5320": "4"
+ "HD_6022": "2",
+ "HD_5320": "3"
},
"resourceOwner_e": {
"_source": "inav/src/main/drivers/resource.h",
diff --git a/docs/development/msp/inav_enums_ref.md b/docs/development/msp/inav_enums_ref.md
index 1fd45d97e91..a12fd374756 100644
--- a/docs/development/msp/inav_enums_ref.md
+++ b/docs/development/msp/inav_enums_ref.md
@@ -4836,9 +4836,8 @@
|---|---:|---|
| `SD_3016` | 0 | |
| `HD_5018` | 1 | |
-| `HD_3016` | 2 | |
-| `HD_6022` | 3 | |
-| `HD_5320` | 4 | |
+| `HD_6022` | 2 | |
+| `HD_5320` | 3 | |
---
## `resourceOwner_e`
diff --git a/src/main/fc/fc_msp.c b/src/main/fc/fc_msp.c
index 0939ab521b9..b06bf1f07f3 100644
--- a/src/main/fc/fc_msp.c
+++ b/src/main/fc/fc_msp.c
@@ -4224,7 +4224,9 @@ bool mspFCProcessInOutCommand(uint16_t cmdMSP, sbuf_t *dst, sbuf_t *src, mspResu
break;
}
- if (navigationSetAltitudeTargetWithDatum((geoAltitudeDatumFlag_e)sbufReadU8(src), (int32_t)sbufReadU32(src))) {
+ uint8_t setAltDatum = (geoAltitudeDatumFlag_e)sbufReadU8(src);
+ int32_t setNewAlt = sbufReadU32(src);
+ if (navigationSetAltitudeTargetWithDatum(setAltDatum, setNewAlt)) {
*ret = MSP_RESULT_ACK;
break;
}
diff --git a/src/main/navigation/navigation.c b/src/main/navigation/navigation.c
index a3752233149..55d6ccb8af7 100644
--- a/src/main/navigation/navigation.c
+++ b/src/main/navigation/navigation.c
@@ -1298,9 +1298,11 @@ static navigationFSMEvent_t navOnEnteringState_NAV_STATE_ALTHOLD_INITIALIZE(navi
if (!(prevFlags & NAV_CTL_ALT) || (prevFlags & NAV_AUTO_RTH) || (prevFlags & NAV_AUTO_WP) || terrainFollowingToggled) {
resetAltitudeController(navTerrainFollowingRequested());
setupAltitudeController();
- setDesiredPosition(&navGetCurrentActualPositionAndVelocity()->pos, posControl.actualState.yaw, NAV_POS_UPDATE_Z); // This will reset surface offset
}
+ // POSHOLD is a 3D hold mode: always capture current altitude setpoint when entering.
+ setDesiredPosition(&navGetCurrentActualPositionAndVelocity()->pos, posControl.actualState.yaw, NAV_POS_UPDATE_Z); // This will reset surface offset
+
return NAV_FSM_EVENT_SUCCESS;
}
@@ -3896,7 +3898,7 @@ void setWaypoint(uint8_t wpNumber, const navWaypoint_t * wpData)
// Only valid when armed and in poshold mode
else if ((wpNumber == 255) && (wpData->action == NAV_WP_ACTION_WAYPOINT) && isGCSValid()) {
// Convert to local coordinates
- geoConvertGeodeticToLocal(&wpPos.pos, &posControl.gpsOrigin, &wpLLH, GEO_ALT_RELATIVE);
+ geoConvertGeodeticToLocal(&wpPos.pos, &posControl.gpsOrigin, &wpLLH, waypointMissionAltConvMode(wpData->p3));
navSetWaypointFlags_t waypointUpdateFlags = NAV_POS_UPDATE_XY;
diff --git a/src/main/telemetry/mavlink.c b/src/main/telemetry/mavlink.c
index 508eaea4062..e155e4594b4 100644
--- a/src/main/telemetry/mavlink.c
+++ b/src/main/telemetry/mavlink.c
@@ -267,29 +267,32 @@ static void mavlinkSetActivePortContext(uint8_t portIndex)
mavlinkApplyActivePortOutputVersion();
}
-static int mavlinkStreamTrigger(enum MAV_DATA_STREAM streamNum)
+static uint8_t mavlinkClampStreamRate(uint8_t rate)
+{
+ if (rate > TELEMETRY_MAVLINK_MAXRATE) {
+ return TELEMETRY_MAVLINK_MAXRATE;
+ }
+
+ return rate;
+}
+
+static int mavlinkStreamTrigger(enum MAV_DATA_STREAM streamNum, timeUs_t currentTimeUs)
{
if (!mavActivePort || streamNum >= MAXSTREAMS) {
return 0;
}
- uint8_t rate = mavActivePort->mavRates[streamNum];
+ const uint8_t rate = mavlinkClampStreamRate(mavActivePort->mavRates[streamNum]);
if (rate == 0) {
return 0;
}
- if (mavActivePort->mavTicks[streamNum] == 0) {
- // we're triggering now, setup the next trigger point
- if (rate > TELEMETRY_MAVLINK_MAXRATE) {
- rate = TELEMETRY_MAVLINK_MAXRATE;
- }
-
- mavActivePort->mavTicks[streamNum] = (TELEMETRY_MAVLINK_MAXRATE / rate);
+ const timeUs_t intervalUs = 1000000UL / rate;
+ if ((mavActivePort->mavStreamNextDue[streamNum] == 0) || (cmpTimeUs(currentTimeUs, mavActivePort->mavStreamNextDue[streamNum]) >= 0)) {
+ mavActivePort->mavStreamNextDue[streamNum] = currentTimeUs + intervalUs;
return 1;
}
- // count down at TASK_RATE_HZ
- mavActivePort->mavTicks[streamNum]--;
return 0;
}
@@ -298,8 +301,8 @@ static void mavlinkSetStreamRate(uint8_t streamNum, uint8_t rate)
if (!mavActivePort || streamNum >= MAXSTREAMS) {
return;
}
- mavActivePort->mavRates[streamNum] = rate;
- mavActivePort->mavTicks[streamNum] = 0;
+ mavActivePort->mavRates[streamNum] = mavlinkClampStreamRate(rate);
+ mavActivePort->mavStreamNextDue[streamNum] = 0;
}
static int32_t mavlinkStreamIntervalUs(uint8_t streamNum)
@@ -308,7 +311,7 @@ static int32_t mavlinkStreamIntervalUs(uint8_t streamNum)
return -1;
}
- uint8_t rate = mavActivePort->mavRates[streamNum];
+ uint8_t rate = mavlinkClampStreamRate(mavActivePort->mavRates[streamNum]);
if (rate == 0) {
return -1;
}
@@ -336,7 +339,7 @@ static void configureMAVLinkStreamRates(uint8_t portIndex)
for (uint8_t stream = 0; stream < MAVLINK_STREAM_COUNT; stream++) {
state->mavRates[stream] = selectedRates[stream];
state->mavRatesConfigured[stream] = selectedRates[stream];
- state->mavTicks[stream] = 0;
+ state->mavStreamNextDue[stream] = 0;
}
}
@@ -357,6 +360,7 @@ static void freeMAVLinkTelemetryPortByIndex(uint8_t portIndex)
state->highLatencyEnabled = mavlinkGetPortConfig(portIndex)->high_latency;
state->txSeq = 0;
state->txDroppedFrames = 0;
+ memset(state->mavStreamNextDue, 0, sizeof(state->mavStreamNextDue));
memset(&state->mavRecvStatus, 0, sizeof(state->mavRecvStatus));
memset(&state->mavRecvMsg, 0, sizeof(state->mavRecvMsg));
}
@@ -423,6 +427,7 @@ static void configureMAVLinkTelemetryPort(uint8_t portIndex)
state->highLatencyEnabled = mavlinkGetPortConfig(portIndex)->high_latency;
state->txSeq = 0;
state->txDroppedFrames = 0;
+ memset(state->mavStreamNextDue, 0, sizeof(state->mavStreamNextDue));
memset(&state->mavRecvStatus, 0, sizeof(state->mavRecvStatus));
memset(&state->mavRecvMsg, 0, sizeof(state->mavRecvMsg));
}
@@ -461,8 +466,22 @@ static void mavlinkSendMessage(void)
return;
}
+ uint8_t sendMask = mavSendMask;
+ if (sendMask == 0) {
+ if (mavActivePort) {
+ for (uint8_t portIndex = 0; portIndex < mavPortCount; portIndex++) {
+ if (&mavPortStates[portIndex] == mavActivePort) {
+ sendMask = MAVLINK_PORT_MASK(portIndex);
+ break;
+ }
+ }
+ } else if (mavPortCount == 1 && mavPortStates[0].telemetryEnabled && mavPortStates[0].port) {
+ sendMask = MAVLINK_PORT_MASK(0);
+ }
+ }
+
for (uint8_t portIndex = 0; portIndex < mavPortCount; portIndex++) {
- if ((mavSendMask & MAVLINK_PORT_MASK(portIndex)) == 0) {
+ if ((sendMask & MAVLINK_PORT_MASK(portIndex)) == 0) {
continue;
}
@@ -517,15 +536,21 @@ static void mavlinkSendAutopilotVersion(void)
capabilities |= MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT;
capabilities |= MAV_PROTOCOL_CAPABILITY_MISSION_INT;
capabilities |= MAV_PROTOCOL_CAPABILITY_COMMAND_INT;
+ capabilities |= MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_LOCAL_NED;
capabilities |= MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_GLOBAL_INT;
+ const uint32_t flightSwVersion =
+ ((uint32_t)ARDUPILOT_VERSION_MAJOR << 24) |
+ ((uint32_t)ARDUPILOT_VERSION_MINOR << 16) |
+ ((uint32_t)ARDUPILOT_VERSION_PATCH << 8);
+
// Bare minimum: caps + IDs. Everything else 0 is fine.
mavlink_msg_autopilot_version_pack(
mavSystemId,
mavComponentId,
&mavSendMsg,
capabilities, // capabilities
- 0, // flight_sw_version. Setting this to actual Ardupilot version makes QGC not display modes anymore but "Unknown", except Guided is "GUIDED". Why?
+ flightSwVersion, // flight_sw_version
0, // middleware_sw_version
0, // os_sw_version
0, // board_version
@@ -609,6 +634,69 @@ static MAV_RESULT mavlinkSetAltitudeTargetFromFrame(uint8_t frame, float altitud
#endif
}
+static MAV_MISSION_RESULT mavlinkMissionResultFromCommandResult(MAV_RESULT result)
+{
+ switch (result) {
+ case MAV_RESULT_ACCEPTED:
+ return MAV_MISSION_ACCEPTED;
+ case MAV_RESULT_UNSUPPORTED:
+ return MAV_MISSION_UNSUPPORTED;
+ default:
+ return MAV_MISSION_ERROR;
+ }
+}
+
+static bool mavlinkHandleArmedGuidedMissionItem(uint8_t current, uint8_t frame, mavFrameSupportMask_e allowedFrames, int32_t latitudeE7, int32_t longitudeE7, float altitudeMeters)
+{
+ if (!isGCSValid()) {
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg,
+ mavRecvMsg.sysid, mavRecvMsg.compid,
+ MAV_MISSION_ERROR, MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
+ return true;
+ }
+
+ if (!mavlinkFrameIsSupported(frame, allowedFrames)) {
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg,
+ mavRecvMsg.sysid, mavRecvMsg.compid,
+ MAV_MISSION_UNSUPPORTED_FRAME, MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
+ return true;
+ }
+
+ if (current == 2) {
+ navWaypoint_t wp = {0};
+ wp.action = NAV_WP_ACTION_WAYPOINT;
+ wp.lat = latitudeE7;
+ wp.lon = longitudeE7;
+ wp.alt = (int32_t)lrintf(altitudeMeters * 100.0f);
+ wp.p3 = mavlinkFrameUsesAbsoluteAltitude(frame) ? NAV_WP_ALTMODE : 0;
+
+ setWaypoint(255, &wp);
+
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg,
+ mavRecvMsg.sysid, mavRecvMsg.compid,
+ MAV_MISSION_ACCEPTED, MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
+ return true;
+ }
+
+ if (current == 3) {
+ const MAV_RESULT result = mavlinkSetAltitudeTargetFromFrame(frame, altitudeMeters);
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg,
+ mavRecvMsg.sysid, mavRecvMsg.compid,
+ mavlinkMissionResultFromCommandResult(result), MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
+ return true;
+ }
+
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg,
+ mavRecvMsg.sysid, mavRecvMsg.compid,
+ MAV_MISSION_ERROR, MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
+ return true;
+}
+
static uint8_t navWaypointFrame(const navWaypoint_t *wp, bool useIntMessages)
{
switch (wp->action) {
@@ -1128,7 +1216,7 @@ void mavlinkSendPosition(timeUs_t currentTimeUs)
// [cm/s] Ground Y Speed (Longitude, positive east)
getEstimatedActualVelocity(Y),
// [cm/s] Ground Z Speed (Altitude, positive down)
- getEstimatedActualVelocity(Z),
+ -getEstimatedActualVelocity(Z),
// [cdeg] Vehicle heading (yaw angle) (0.0..359.99 degrees, 0=north)
DECIDEGREES_TO_CENTIDEGREES(attitude.values.yaw)
);
@@ -1239,7 +1327,7 @@ void mavlinkSendHeartbeat(void)
if (manualInputAllowed) {
mavModes |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED;
}
- if (flm == FLM_POSITION_HOLD) {
+ if (flm == FLM_POSITION_HOLD && isGCSValid()) {
mavModes |= MAV_MODE_FLAG_GUIDED_ENABLED;
}
else if (flm == FLM_MISSION || flm == FLM_RTH ) {
@@ -1584,37 +1672,37 @@ void processMAVLinkTelemetry(timeUs_t currentTimeUs)
}
// is executed @ TELEMETRY_MAVLINK_MAXRATE rate
- if (mavlinkStreamTrigger(MAV_DATA_STREAM_EXTENDED_STATUS)) {
+ if (mavlinkStreamTrigger(MAV_DATA_STREAM_EXTENDED_STATUS, currentTimeUs)) {
mavlinkSendSystemStatus();
}
- if (mavlinkStreamTrigger(MAV_DATA_STREAM_RC_CHANNELS)) {
+ if (mavlinkStreamTrigger(MAV_DATA_STREAM_RC_CHANNELS, currentTimeUs)) {
mavlinkSendRCChannelsAndRSSI();
}
#ifdef USE_GPS
- if (mavlinkStreamTrigger(MAV_DATA_STREAM_POSITION)) {
+ if (mavlinkStreamTrigger(MAV_DATA_STREAM_POSITION, currentTimeUs)) {
mavlinkSendPosition(currentTimeUs);
}
#endif
- if (mavlinkStreamTrigger(MAV_DATA_STREAM_EXTRA1)) {
+ if (mavlinkStreamTrigger(MAV_DATA_STREAM_EXTRA1, currentTimeUs)) {
mavlinkSendAttitude();
}
- if (mavlinkStreamTrigger(MAV_DATA_STREAM_EXTRA2)) {
+ if (mavlinkStreamTrigger(MAV_DATA_STREAM_EXTRA2, currentTimeUs)) {
mavlinkSendVfrHud();
}
- if (mavlinkStreamTrigger(MAV_DATA_STREAM_HEARTBEAT)) {
+ if (mavlinkStreamTrigger(MAV_DATA_STREAM_HEARTBEAT, currentTimeUs)) {
mavlinkSendHeartbeat();
}
- if (mavlinkStreamTrigger(MAV_DATA_STREAM_EXTENDED_SYS_STATE)) {
+ if (mavlinkStreamTrigger(MAV_DATA_STREAM_EXTENDED_SYS_STATE, currentTimeUs)) {
mavlinkSendExtendedSysState();
}
- if (mavlinkStreamTrigger(MAV_DATA_STREAM_EXTRA3)) {
+ if (mavlinkStreamTrigger(MAV_DATA_STREAM_EXTRA3, currentTimeUs)) {
mavlinkSendBatteryTemperatureStatusText();
}
@@ -1700,7 +1788,9 @@ static bool mavlinkHandleMissionItemCommon(bool useIntMessages, uint8_t frame, u
mavlinkTouchIncomingMissionTransaction();
- if (autocontinue == 0) {
+ const bool lastMissionItem = incomingMissionWpCount > 0 && ((int)seq + 1 >= incomingMissionWpCount);
+
+ if (autocontinue == 0 && !lastMissionItem) {
mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, MAV_MISSION_UNSUPPORTED, MAV_MISSION_TYPE_MISSION, 0);
mavlinkSendMessage();
return true;
@@ -1948,36 +2038,15 @@ static bool handleIncoming_MISSION_ITEM(void)
}
if (ARMING_FLAG(ARMED)) {
- // Legacy Mission Planner GUIDED
- if (isGCSValid() && (msg.command == MAV_CMD_NAV_WAYPOINT) && (msg.current == 2)) {
- if (!(msg.frame == MAV_FRAME_GLOBAL)) {
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg,
- mavRecvMsg.sysid, mavRecvMsg.compid,
- MAV_MISSION_UNSUPPORTED_FRAME, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
- return true;
- }
-
- navWaypoint_t wp;
- wp.action = NAV_WP_ACTION_WAYPOINT;
- wp.lat = (int32_t)(msg.x * 1e7f);
- wp.lon = (int32_t)(msg.y * 1e7f);
- wp.alt = (int32_t)(msg.z * 100.0f);
- wp.p1 = 0;
- wp.p2 = 0;
- wp.p3 = mavlinkFrameUsesAbsoluteAltitude(msg.frame) ? NAV_WP_ALTMODE : 0;
- setWaypoint(255, &wp);
-
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg,
- mavRecvMsg.sysid, mavRecvMsg.compid,
- MAV_MISSION_ACCEPTED, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
- return true;
- } else {
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, MAV_MISSION_ERROR, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
- return true;
+ if (msg.command == MAV_CMD_NAV_WAYPOINT) {
+ return mavlinkHandleArmedGuidedMissionItem(msg.current, msg.frame,
+ MAV_FRAME_SUPPORTED_GLOBAL | MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT,
+ (int32_t)lrintf(msg.x * 1e7f), (int32_t)lrintf(msg.y * 1e7f), msg.z);
}
+
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, MAV_MISSION_ERROR, MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
+ return true;
}
return mavlinkHandleMissionItemCommon(false, msg.frame, msg.command, msg.autocontinue, msg.seq, msg.param1, msg.param2, msg.param3, msg.param4, (int32_t)(msg.x * 1e7f), (int32_t)(msg.y * 1e7f), msg.z);
@@ -2177,7 +2246,7 @@ static bool handleIncoming_COMMAND(uint8_t targetSystem, uint8_t targetComponent
}
if (isGCSValid()) {
- navWaypoint_t wp;
+ navWaypoint_t wp = {0};
wp.action = NAV_WP_ACTION_WAYPOINT;
wp.lat = (int32_t)(latitudeDeg * 1e7f);
wp.lon = (int32_t)(longitudeDeg * 1e7f);
@@ -2200,7 +2269,7 @@ static bool handleIncoming_COMMAND(uint8_t targetSystem, uint8_t targetComponent
return true;
case MAV_CMD_DO_CHANGE_ALTITUDE:
{
- const MAV_RESULT result = mavlinkSetAltitudeTargetFromFrame(frame, param1);
+ const MAV_RESULT result = mavlinkSetAltitudeTargetFromFrame((uint8_t)lrintf(param2), param1);
mavlinkSendCommandAck(command, result, ackTargetSystem, ackTargetComponent);
return true;
}
@@ -2433,35 +2502,15 @@ static bool handleIncoming_MISSION_ITEM_INT(void)
}
if (ARMING_FLAG(ARMED)) {
- if (isGCSValid() && (msg.command == MAV_CMD_NAV_WAYPOINT) && (msg.current == 2)) {
- if (!(msg.frame == MAV_FRAME_GLOBAL_INT || msg.frame == MAV_FRAME_GLOBAL_RELATIVE_ALT_INT)) {
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg,
- mavRecvMsg.sysid, mavRecvMsg.compid,
- MAV_MISSION_UNSUPPORTED_FRAME, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
- return true;
- }
-
- navWaypoint_t wp;
- wp.action = NAV_WP_ACTION_WAYPOINT;
- wp.lat = msg.x;
- wp.lon = msg.y;
- wp.alt = (int32_t)(msg.z * 100.0f);
- wp.p1 = 0;
- wp.p2 = 0;
- wp.p3 = mavlinkFrameUsesAbsoluteAltitude(msg.frame) ? NAV_WP_ALTMODE : 0;
- setWaypoint(255, &wp);
-
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg,
- mavRecvMsg.sysid, mavRecvMsg.compid,
- MAV_MISSION_ACCEPTED, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
- return true;
- } else {
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, MAV_MISSION_ERROR, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
- return true;
+ if (msg.command == MAV_CMD_NAV_WAYPOINT) {
+ return mavlinkHandleArmedGuidedMissionItem(msg.current, msg.frame,
+ MAV_FRAME_SUPPORTED_GLOBAL_INT | MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT_INT,
+ msg.x, msg.y, msg.z);
}
+
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, MAV_MISSION_ERROR, MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
+ return true;
}
return mavlinkHandleMissionItemCommon(true, msg.frame, msg.command, msg.autocontinue, msg.seq, msg.param1, msg.param2, msg.param3, msg.param4, msg.x, msg.y, msg.z);
@@ -2572,7 +2621,9 @@ static bool handleIncoming_SET_POSITION_TARGET_GLOBAL_INT(void)
// Altitude-only SET_POSITION_TARGET_GLOBAL_INT mirrors MAV_CMD_DO_CHANGE_ALTITUDE semantics.
if (xIgnored && yIgnored && !zIgnored) {
- mavlinkSetAltitudeTargetFromFrame(frame, msg.alt);
+ if (isGCSValid()) {
+ mavlinkSetAltitudeTargetFromFrame(frame, msg.alt);
+ }
return true;
}
@@ -2581,7 +2632,7 @@ static bool handleIncoming_SET_POSITION_TARGET_GLOBAL_INT(void)
}
if (isGCSValid()) {
- navWaypoint_t wp;
+ navWaypoint_t wp = {0};
wp.action = NAV_WP_ACTION_WAYPOINT;
wp.lat = msg.lat_int;
wp.lon = msg.lon_int;
@@ -2597,13 +2648,45 @@ static bool handleIncoming_SET_POSITION_TARGET_GLOBAL_INT(void)
return true;
}
+static bool handleIncoming_SET_POSITION_TARGET_LOCAL_NED(void)
+{
+ mavlink_set_position_target_local_ned_t msg;
+ mavlink_msg_set_position_target_local_ned_decode(&mavRecvMsg, &msg);
-static bool handleIncoming_RC_CHANNELS_OVERRIDE(void) {
- mavlink_rc_channels_override_t msg;
- mavlink_msg_rc_channels_override_decode(&mavRecvMsg, &msg);
if (msg.target_system != mavSystemId) {
return false;
}
+ if (msg.target_component != 0 && msg.target_component != mavComponentId) {
+ return false;
+ }
+
+ if (msg.coordinate_frame != MAV_FRAME_LOCAL_OFFSET_NED) {
+ return true;
+ }
+
+ const uint16_t typeMask = msg.type_mask;
+ const bool xIgnored = (typeMask & POSITION_TARGET_TYPEMASK_X_IGNORE) != 0;
+ const bool yIgnored = (typeMask & POSITION_TARGET_TYPEMASK_Y_IGNORE) != 0;
+ const bool zIgnored = (typeMask & POSITION_TARGET_TYPEMASK_Z_IGNORE) != 0;
+
+ if (!isGCSValid() || zIgnored) {
+ return true;
+ }
+
+ if ((!xIgnored && fabsf(msg.x) > 0.01f) || (!yIgnored && fabsf(msg.y) > 0.01f)) {
+ return true;
+ }
+
+ const int32_t targetAltitudeCm = (int32_t)lrintf((float)getEstimatedActualPosition(Z) - (msg.z * 100.0f));
+ navigationSetAltitudeTargetWithDatum(NAV_WP_TAKEOFF_DATUM, targetAltitudeCm);
+
+ return true;
+}
+
+
+static bool handleIncoming_RC_CHANNELS_OVERRIDE(void) {
+ mavlink_rc_channels_override_t msg;
+ mavlink_msg_rc_channels_override_decode(&mavRecvMsg, &msg);
mavlinkRxHandleMessage(&msg);
return true;
}
@@ -2904,6 +2987,13 @@ static bool processMAVLinkIncomingTelemetry(uint8_t ingressPortIndex)
mavlinkExtractTargets(&mavRecvMsg, &targetSystem, &targetComponent);
mavlinkForwardMessage(ingressPortIndex, targetSystem, targetComponent);
+ if (mavRecvMsg.msgid == MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE) {
+ mavlinkSetActivePortContext(ingressPortIndex);
+ mavSendMask = MAVLINK_PORT_MASK(ingressPortIndex);
+ handleIncoming_RC_CHANNELS_OVERRIDE();
+ return false;
+ }
+
const int8_t localPortIndex = mavlinkResolveLocalPortForTarget(targetSystem, targetComponent, ingressPortIndex);
if (localPortIndex < 0) {
return false;
@@ -2970,6 +3060,9 @@ static bool processMAVLinkIncomingTelemetry(uint8_t ingressPortIndex)
// Don't set that we handled a message, otherwise RC channel packets will block telemetry messages
localHandled = false;
break;
+ case MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED:
+ localHandled = handleIncoming_SET_POSITION_TARGET_LOCAL_NED();
+ break;
case MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT:
localHandled = handleIncoming_SET_POSITION_TARGET_GLOBAL_INT();
break;
diff --git a/src/main/telemetry/mavlink.h b/src/main/telemetry/mavlink.h
index 60b77237d0a..38aface2d5f 100755
--- a/src/main/telemetry/mavlink.h
+++ b/src/main/telemetry/mavlink.h
@@ -141,7 +141,7 @@ typedef struct mavlinkPortRuntime_s {
bool highLatencyEnabled;
uint8_t mavRates[MAVLINK_STREAM_COUNT];
uint8_t mavRatesConfigured[MAVLINK_STREAM_COUNT];
- uint8_t mavTicks[MAVLINK_STREAM_COUNT];
+ timeUs_t mavStreamNextDue[MAVLINK_STREAM_COUNT];
uint8_t txSeq;
uint32_t txDroppedFrames;
mavlink_message_t mavRecvMsg;
diff --git a/src/test/unit/mavlink_unittest.cc b/src/test/unit/mavlink_unittest.cc
index 57035ad7393..641f31432d2 100644
--- a/src/test/unit/mavlink_unittest.cc
+++ b/src/test/unit/mavlink_unittest.cc
@@ -52,6 +52,13 @@ extern "C" {
#include "io/osd.h"
#include "navigation/navigation.h"
+#ifdef __cplusplus
+ #define _Static_assert static_assert
+#endif
+ #include "navigation/navigation_private.h"
+#ifdef __cplusplus
+ #undef _Static_assert
+#endif
#include "rx/rx.h"
@@ -60,19 +67,16 @@ extern "C" {
#include "sensors/diagnostics.h"
#include "sensors/gyro.h"
#include "sensors/pitotmeter.h"
+ #include "sensors/sensors.h"
#include "sensors/temperature.h"
#include "telemetry/mavlink.h"
#include "telemetry/telemetry.h"
-#pragma GCC diagnostic push
-#pragma GCC diagnostic ignored "-Wunused-function"
- #define MAVLINK_COMM_NUM_BUFFERS 1
- #include "common/mavlink.h"
-#pragma GCC diagnostic pop
-
void mavlinkSendAttitude(void);
+ void mavlinkSendHeartbeat(void);
void mavlinkSendBatteryTemperatureStatusText(void);
+ void mavlinkSendPosition(timeUs_t currentTimeUs);
PG_REGISTER(telemetryConfig_t, telemetryConfig, PG_TELEMETRY_CONFIG, 0);
PG_REGISTER(rxConfig_t, rxConfig, PG_RX_CONFIG, 0);
@@ -90,6 +94,7 @@ static uint8_t serialTxBuffer[2048];
static size_t serialRxLen;
static size_t serialRxPos;
static size_t serialTxLen;
+static const uint8_t testTargetComponent = MAV_COMP_ID_AUTOPILOT1;
const uint32_t baudRates[] = {
0, 1200, 2400, 4800, 9600, 19200, 38400, 57600, 115200, 230400, 250000,
@@ -103,6 +108,14 @@ static int mavlinkRxHandleCalls;
static bool gcsValid;
static int waypointCount;
static navWaypoint_t waypointStore[4];
+static float estimatedPosition[XYZ_AXIS_COUNT];
+static float estimatedVelocity[XYZ_AXIS_COUNT];
+static int altitudeTargetSetCalls;
+static bool altitudeTargetSetResult;
+static geoAltitudeDatumFlag_e lastAltitudeTargetDatum;
+static int32_t lastAltitudeTargetCm;
+static flightModeForTelemetry_e testFlightMode;
+static uint32_t testSensorsMask;
static void resetSerialBuffers(void)
{
@@ -139,13 +152,24 @@ static void initMavlinkTestState(void)
mavlinkRxHandleCalls = 0;
gcsValid = true;
waypointCount = 0;
+ memset(estimatedPosition, 0, sizeof(estimatedPosition));
+ memset(estimatedVelocity, 0, sizeof(estimatedVelocity));
+ altitudeTargetSetCalls = 0;
+ altitudeTargetSetResult = true;
+ lastAltitudeTargetDatum = NAV_WP_TAKEOFF_DATUM;
+ lastAltitudeTargetCm = 0;
+ testFlightMode = FLM_MANUAL;
+ testSensorsMask = 0;
+ memset(&gpsSol, 0, sizeof(gpsSol));
+ memset(&GPS_home, 0, sizeof(GPS_home));
memset(waypointStore, 0, sizeof(waypointStore));
memset(&rxLinkStatistics, 0, sizeof(rxLinkStatistics));
- telemetryConfigMutable()->mavlink.sysid = 1;
- telemetryConfigMutable()->mavlink.autopilot_type = MAVLINK_AUTOPILOT_ARDUPILOT;
- telemetryConfigMutable()->mavlink.version = 2;
- telemetryConfigMutable()->mavlink.min_txbuff = 0;
+ telemetryConfigMutable()->mavlink_common.sysid = 1;
+ telemetryConfigMutable()->mavlink_common.autopilot_type = MAVLINK_AUTOPILOT_ARDUPILOT;
+ telemetryConfigMutable()->mavlink_common.version = 2;
+ telemetryConfigMutable()->mavlink[0].min_txbuff = 0;
+ telemetryConfigMutable()->mavlink[0].compid = MAV_COMP_ID_AUTOPILOT1;
telemetryConfigMutable()->halfDuplex = 0;
rxConfigMutable()->receiverType = RX_TYPE_NONE;
@@ -158,7 +182,7 @@ static void initMavlinkTestState(void)
rxRuntimeConfig.channelCount = 8;
initMAVLinkTelemetry();
- configureMAVLinkTelemetryPort();
+ checkMAVLinkTelemetryState();
}
TEST(MavlinkTelemetryTest, AttitudeUsesRadiansPerSecond)
@@ -193,7 +217,7 @@ TEST(MavlinkTelemetryTest, CommandLongRepositionUsesGlobalFrameAndParams)
mavlink_message_t cmd;
mavlink_msg_command_long_pack(
42, 200, &cmd,
- 1, MAV_COMP_ID_MISSIONPLANNER,
+ 1, testTargetComponent,
MAV_CMD_DO_REPOSITION,
0,
0, 0, 0, 123.4f,
@@ -226,7 +250,7 @@ TEST(MavlinkTelemetryTest, CommandIntUnsupportedFrameIsRejected)
mavlink_message_t cmd;
mavlink_msg_command_int_pack(
42, 200, &cmd,
- 1, MAV_COMP_ID_MISSIONPLANNER,
+ 1, testTargetComponent,
MAV_FRAME_BODY_NED,
MAV_CMD_DO_REPOSITION,
0, 0,
@@ -255,7 +279,7 @@ TEST(MavlinkTelemetryTest, CommandIntRepositionScalesCoordinates)
mavlink_message_t cmd;
mavlink_msg_command_int_pack(
42, 200, &cmd,
- 1, MAV_COMP_ID_MISSIONPLANNER,
+ 1, testTargetComponent,
MAV_FRAME_GLOBAL_RELATIVE_ALT_INT,
MAV_CMD_DO_REPOSITION,
0, 0,
@@ -289,7 +313,7 @@ TEST(MavlinkTelemetryTest, MissionClearAllAcksAndResets)
mavlink_message_t msg;
mavlink_msg_mission_clear_all_pack(
42, 200, &msg,
- 1, MAV_COMP_ID_MISSIONPLANNER, MAV_MISSION_TYPE_MISSION);
+ 1, testTargetComponent, MAV_MISSION_TYPE_MISSION);
pushRxMessage(&msg);
handleMAVLinkTelemetry(1000);
@@ -314,7 +338,7 @@ TEST(MavlinkTelemetryTest, MissionCountRequestsFirstItem)
mavlink_message_t msg;
mavlink_msg_mission_count_pack(
42, 200, &msg,
- 1, MAV_COMP_ID_MISSIONPLANNER, 1, MAV_MISSION_TYPE_MISSION, 0);
+ 1, testTargetComponent, 1, MAV_MISSION_TYPE_MISSION, 0);
pushRxMessage(&msg);
handleMAVLinkTelemetry(1000);
@@ -338,7 +362,7 @@ TEST(MavlinkTelemetryTest, MissionCountWhileArmedIsRejected)
mavlink_message_t msg;
mavlink_msg_mission_count_pack(
42, 200, &msg,
- 1, MAV_COMP_ID_MISSIONPLANNER, 1, MAV_MISSION_TYPE_MISSION, 0);
+ 1, testTargetComponent, 1, MAV_MISSION_TYPE_MISSION, 0);
pushRxMessage(&msg);
handleMAVLinkTelemetry(1000);
@@ -374,7 +398,7 @@ TEST(MavlinkTelemetryTest, MissionItemIntSingleItemAcksAccepted)
mavlink_message_t countMsg;
mavlink_msg_mission_count_pack(
42, 200, &countMsg,
- 1, MAV_COMP_ID_MISSIONPLANNER, 1, MAV_MISSION_TYPE_MISSION, 0);
+ 1, testTargetComponent, 1, MAV_MISSION_TYPE_MISSION, 0);
pushRxMessage(&countMsg);
handleMAVLinkTelemetry(1000);
@@ -384,7 +408,7 @@ TEST(MavlinkTelemetryTest, MissionItemIntSingleItemAcksAccepted)
mavlink_message_t itemMsg;
mavlink_msg_mission_item_int_pack(
42, 200, &itemMsg,
- 1, MAV_COMP_ID_MISSIONPLANNER, 0,
+ 1, testTargetComponent, 0,
MAV_FRAME_GLOBAL_RELATIVE_ALT_INT,
MAV_CMD_NAV_WAYPOINT, 0, 1,
0, 0, 0, 0,
@@ -408,6 +432,80 @@ TEST(MavlinkTelemetryTest, MissionItemIntSingleItemAcksAccepted)
EXPECT_EQ(lastWaypoint.alt, (int32_t)(12.3f * 100.0f));
}
+TEST(MavlinkTelemetryTest, MissionItemIntSingleFinalItemAllowsAutocontinueZero)
+{
+ initMavlinkTestState();
+
+ mavlink_message_t countMsg;
+ mavlink_msg_mission_count_pack(
+ 42, 200, &countMsg,
+ 1, testTargetComponent, 1, MAV_MISSION_TYPE_MISSION, 0);
+
+ pushRxMessage(&countMsg);
+ handleMAVLinkTelemetry(1000);
+
+ serialTxLen = 0;
+
+ mavlink_message_t itemMsg;
+ mavlink_msg_mission_item_int_pack(
+ 42, 200, &itemMsg,
+ 1, testTargetComponent, 0,
+ MAV_FRAME_GLOBAL_RELATIVE_ALT_INT,
+ MAV_CMD_NAV_WAYPOINT, 0, 0,
+ 0, 0, 0, 0,
+ 375000000, -1222500000, 12.3f,
+ MAV_MISSION_TYPE_MISSION);
+
+ pushRxMessage(&itemMsg);
+ handleMAVLinkTelemetry(1000);
+
+ mavlink_message_t ackMsg;
+ ASSERT_TRUE(popTxMessage(&ackMsg));
+ ASSERT_EQ(ackMsg.msgid, MAVLINK_MSG_ID_MISSION_ACK);
+
+ mavlink_mission_ack_t ack;
+ mavlink_msg_mission_ack_decode(&ackMsg, &ack);
+
+ EXPECT_EQ(ack.type, MAV_MISSION_ACCEPTED);
+}
+
+TEST(MavlinkTelemetryTest, MissionItemIntNonFinalAutocontinueZeroIsRejected)
+{
+ initMavlinkTestState();
+
+ mavlink_message_t countMsg;
+ mavlink_msg_mission_count_pack(
+ 42, 200, &countMsg,
+ 1, testTargetComponent, 2, MAV_MISSION_TYPE_MISSION, 0);
+
+ pushRxMessage(&countMsg);
+ handleMAVLinkTelemetry(1000);
+
+ serialTxLen = 0;
+
+ mavlink_message_t itemMsg;
+ mavlink_msg_mission_item_int_pack(
+ 42, 200, &itemMsg,
+ 1, testTargetComponent, 0,
+ MAV_FRAME_GLOBAL_RELATIVE_ALT_INT,
+ MAV_CMD_NAV_WAYPOINT, 0, 0,
+ 0, 0, 0, 0,
+ 375000000, -1222500000, 12.3f,
+ MAV_MISSION_TYPE_MISSION);
+
+ pushRxMessage(&itemMsg);
+ handleMAVLinkTelemetry(1000);
+
+ mavlink_message_t ackMsg;
+ ASSERT_TRUE(popTxMessage(&ackMsg));
+ ASSERT_EQ(ackMsg.msgid, MAVLINK_MSG_ID_MISSION_ACK);
+
+ mavlink_mission_ack_t ack;
+ mavlink_msg_mission_ack_decode(&ackMsg, &ack);
+
+ EXPECT_EQ(ack.type, MAV_MISSION_UNSUPPORTED);
+}
+
TEST(MavlinkTelemetryTest, MissionItemIntGuidedWhileArmedUpdatesWaypoint)
{
initMavlinkTestState();
@@ -416,7 +514,7 @@ TEST(MavlinkTelemetryTest, MissionItemIntGuidedWhileArmedUpdatesWaypoint)
mavlink_message_t msg;
mavlink_msg_mission_item_int_pack(
42, 200, &msg,
- 1, MAV_COMP_ID_MISSIONPLANNER, 0,
+ 1, testTargetComponent, 0,
MAV_FRAME_GLOBAL_RELATIVE_ALT_INT,
MAV_CMD_NAV_WAYPOINT, 2, 1,
0, 0, 0, 0,
@@ -433,6 +531,37 @@ TEST(MavlinkTelemetryTest, MissionItemIntGuidedWhileArmedUpdatesWaypoint)
EXPECT_EQ(lastWaypoint.p3, 0);
}
+TEST(MavlinkTelemetryTest, MissionItemIntGuidedWhileArmedCurrentThreeChangesAltitude)
+{
+ initMavlinkTestState();
+ ENABLE_ARMING_FLAG(ARMED);
+
+ mavlink_message_t msg;
+ mavlink_msg_mission_item_int_pack(
+ 42, 200, &msg,
+ 1, testTargetComponent, 0,
+ MAV_FRAME_GLOBAL_RELATIVE_ALT_INT,
+ MAV_CMD_NAV_WAYPOINT, 3, 1,
+ 0, 0, 0, 0,
+ 375000000, -1222500000, 12.3f,
+ MAV_MISSION_TYPE_MISSION);
+
+ pushRxMessage(&msg);
+ handleMAVLinkTelemetry(1000);
+
+ mavlink_message_t ackMsg;
+ ASSERT_TRUE(popTxMessage(&ackMsg));
+ ASSERT_EQ(ackMsg.msgid, MAVLINK_MSG_ID_MISSION_ACK);
+
+ mavlink_mission_ack_t ack;
+ mavlink_msg_mission_ack_decode(&ackMsg, &ack);
+
+ EXPECT_EQ(ack.type, MAV_MISSION_ACCEPTED);
+ EXPECT_EQ(altitudeTargetSetCalls, 1);
+ EXPECT_EQ(lastAltitudeTargetDatum, NAV_WP_TAKEOFF_DATUM);
+ EXPECT_EQ(lastAltitudeTargetCm, 1230);
+}
+
TEST(MavlinkTelemetryTest, MissionRequestListSendsCount)
{
initMavlinkTestState();
@@ -441,7 +570,7 @@ TEST(MavlinkTelemetryTest, MissionRequestListSendsCount)
mavlink_message_t msg;
mavlink_msg_mission_request_list_pack(
42, 200, &msg,
- 1, MAV_COMP_ID_MISSIONPLANNER, MAV_MISSION_TYPE_MISSION);
+ 1, testTargetComponent, MAV_MISSION_TYPE_MISSION);
pushRxMessage(&msg);
handleMAVLinkTelemetry(1000);
@@ -470,7 +599,7 @@ TEST(MavlinkTelemetryTest, MissionRequestSendsWaypoint)
mavlink_message_t msg;
mavlink_msg_mission_request_pack(
42, 200, &msg,
- 1, MAV_COMP_ID_MISSIONPLANNER, 0, MAV_MISSION_TYPE_MISSION);
+ 1, testTargetComponent, 0, MAV_MISSION_TYPE_MISSION);
pushRxMessage(&msg);
handleMAVLinkTelemetry(1000);
@@ -498,7 +627,7 @@ TEST(MavlinkTelemetryTest, LegacyGuidedMissionItemUsesAbsoluteAltitude)
mavlink_message_t msg;
mavlink_msg_mission_item_pack(
42, 200, &msg,
- 1, MAV_COMP_ID_MISSIONPLANNER, 0,
+ 1, testTargetComponent, 0,
MAV_FRAME_GLOBAL,
MAV_CMD_NAV_WAYPOINT, 2, 1,
0, 0, 0, 0,
@@ -519,7 +648,7 @@ TEST(MavlinkTelemetryTest, ParamRequestListRespondsWithEmptyParam)
mavlink_message_t msg;
mavlink_msg_param_request_list_pack(
42, 200, &msg,
- 1, MAV_COMP_ID_MISSIONPLANNER);
+ 1, testTargetComponent);
pushRxMessage(&msg);
handleMAVLinkTelemetry(1000);
@@ -542,7 +671,7 @@ TEST(MavlinkTelemetryTest, SetPositionTargetGlobalIntSetsWaypoint)
mavlink_message_t msg;
mavlink_msg_set_position_target_global_int_pack(
42, 200, &msg,
- 0, 1, MAV_COMP_ID_MISSIONPLANNER,
+ 0, 1, testTargetComponent,
MAV_FRAME_GLOBAL_RELATIVE_ALT_INT, 0,
375000000, -1222500000, 12.3f,
0, 0, 0, 0, 0, 0, 0, 0);
@@ -564,7 +693,7 @@ TEST(MavlinkTelemetryTest, SetPositionTargetGlobalIntUsesAbsoluteAltitude)
mavlink_message_t msg;
mavlink_msg_set_position_target_global_int_pack(
42, 200, &msg,
- 0, 1, MAV_COMP_ID_MISSIONPLANNER,
+ 0, 1, testTargetComponent,
MAV_FRAME_GLOBAL_INT, 0,
375000000, -1222500000, 12.3f,
0, 0, 0, 0, 0, 0, 0, 0);
@@ -576,6 +705,93 @@ TEST(MavlinkTelemetryTest, SetPositionTargetGlobalIntUsesAbsoluteAltitude)
EXPECT_EQ(lastWaypoint.p3, NAV_WP_ALTMODE);
}
+TEST(MavlinkTelemetryTest, SetPositionTargetGlobalIntAltitudeOnlyRequiresValidGcs)
+{
+ initMavlinkTestState();
+ gcsValid = false;
+
+ mavlink_message_t msg;
+ mavlink_msg_set_position_target_global_int_pack(
+ 42, 200, &msg,
+ 0, 1, testTargetComponent,
+ MAV_FRAME_GLOBAL_RELATIVE_ALT_INT,
+ POSITION_TARGET_TYPEMASK_X_IGNORE |
+ POSITION_TARGET_TYPEMASK_Y_IGNORE |
+ POSITION_TARGET_TYPEMASK_VX_IGNORE |
+ POSITION_TARGET_TYPEMASK_VY_IGNORE |
+ POSITION_TARGET_TYPEMASK_VZ_IGNORE |
+ POSITION_TARGET_TYPEMASK_AX_IGNORE |
+ POSITION_TARGET_TYPEMASK_AY_IGNORE |
+ POSITION_TARGET_TYPEMASK_AZ_IGNORE |
+ POSITION_TARGET_TYPEMASK_YAW_IGNORE |
+ POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE,
+ 0, 0, 12.3f,
+ 0, 0, 0, 0, 0, 0, 0, 0);
+
+ pushRxMessage(&msg);
+ handleMAVLinkTelemetry(1000);
+
+ EXPECT_EQ(altitudeTargetSetCalls, 0);
+}
+
+TEST(MavlinkTelemetryTest, SetPositionTargetLocalNedAltitudeOnlySetsAltitudeTarget)
+{
+ initMavlinkTestState();
+ estimatedPosition[Z] = 1000.0f;
+
+ mavlink_message_t msg;
+ mavlink_msg_set_position_target_local_ned_pack(
+ 42, 200, &msg,
+ 0, 1, testTargetComponent,
+ MAV_FRAME_LOCAL_OFFSET_NED,
+ POSITION_TARGET_TYPEMASK_X_IGNORE |
+ POSITION_TARGET_TYPEMASK_Y_IGNORE |
+ POSITION_TARGET_TYPEMASK_VX_IGNORE |
+ POSITION_TARGET_TYPEMASK_VY_IGNORE |
+ POSITION_TARGET_TYPEMASK_VZ_IGNORE |
+ POSITION_TARGET_TYPEMASK_AX_IGNORE |
+ POSITION_TARGET_TYPEMASK_AY_IGNORE |
+ POSITION_TARGET_TYPEMASK_AZ_IGNORE |
+ POSITION_TARGET_TYPEMASK_YAW_IGNORE |
+ POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE,
+ 0.0f, 0.0f, -2.5f,
+ 0, 0, 0, 0, 0, 0, 0, 0);
+
+ pushRxMessage(&msg);
+ handleMAVLinkTelemetry(1000);
+
+ EXPECT_EQ(altitudeTargetSetCalls, 1);
+ EXPECT_EQ(lastAltitudeTargetDatum, NAV_WP_TAKEOFF_DATUM);
+ EXPECT_EQ(lastAltitudeTargetCm, 1250);
+}
+
+TEST(MavlinkTelemetryTest, SetPositionTargetLocalNedIgnoresXyMotionRequests)
+{
+ initMavlinkTestState();
+ estimatedPosition[Z] = 1000.0f;
+
+ mavlink_message_t msg;
+ mavlink_msg_set_position_target_local_ned_pack(
+ 42, 200, &msg,
+ 0, 1, testTargetComponent,
+ MAV_FRAME_LOCAL_OFFSET_NED,
+ POSITION_TARGET_TYPEMASK_VX_IGNORE |
+ POSITION_TARGET_TYPEMASK_VY_IGNORE |
+ POSITION_TARGET_TYPEMASK_VZ_IGNORE |
+ POSITION_TARGET_TYPEMASK_AX_IGNORE |
+ POSITION_TARGET_TYPEMASK_AY_IGNORE |
+ POSITION_TARGET_TYPEMASK_AZ_IGNORE |
+ POSITION_TARGET_TYPEMASK_YAW_IGNORE |
+ POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE,
+ 1.0f, 0.0f, -2.5f,
+ 0, 0, 0, 0, 0, 0, 0, 0);
+
+ pushRxMessage(&msg);
+ handleMAVLinkTelemetry(1000);
+
+ EXPECT_EQ(altitudeTargetSetCalls, 0);
+}
+
TEST(MavlinkTelemetryTest, RequestDataStreamStopsStream)
{
initMavlinkTestState();
@@ -583,7 +799,7 @@ TEST(MavlinkTelemetryTest, RequestDataStreamStopsStream)
mavlink_message_t setMsg;
mavlink_msg_request_data_stream_pack(
42, 200, &setMsg,
- 1, MAV_COMP_ID_MISSIONPLANNER,
+ 1, testTargetComponent,
MAV_DATA_STREAM_RC_CHANNELS, 10, 1);
pushRxMessage(&setMsg);
@@ -594,7 +810,7 @@ TEST(MavlinkTelemetryTest, RequestDataStreamStopsStream)
mavlink_message_t getMsg;
mavlink_msg_command_long_pack(
42, 200, &getMsg,
- 1, MAV_COMP_ID_MISSIONPLANNER,
+ 1, testTargetComponent,
MAV_CMD_GET_MESSAGE_INTERVAL,
0,
(float)MAVLINK_MSG_ID_RC_CHANNELS,
@@ -618,7 +834,7 @@ TEST(MavlinkTelemetryTest, RequestDataStreamStopsStream)
mavlink_message_t stopMsg;
mavlink_msg_request_data_stream_pack(
42, 200, &stopMsg,
- 1, MAV_COMP_ID_MISSIONPLANNER,
+ 1, testTargetComponent,
MAV_DATA_STREAM_RC_CHANNELS, 0, 0);
pushRxMessage(&stopMsg);
@@ -645,7 +861,7 @@ TEST(MavlinkTelemetryTest, HeartbeatIntervalIsIndependentFromExtra2Stream)
mavlink_message_t stopExtra2Msg;
mavlink_msg_request_data_stream_pack(
42, 200, &stopExtra2Msg,
- 1, MAV_COMP_ID_MISSIONPLANNER,
+ 1, testTargetComponent,
MAV_DATA_STREAM_EXTRA2, 0, 0);
pushRxMessage(&stopExtra2Msg);
@@ -656,7 +872,7 @@ TEST(MavlinkTelemetryTest, HeartbeatIntervalIsIndependentFromExtra2Stream)
mavlink_message_t getMsg;
mavlink_msg_command_long_pack(
42, 200, &getMsg,
- 1, MAV_COMP_ID_MISSIONPLANNER,
+ 1, testTargetComponent,
MAV_CMD_GET_MESSAGE_INTERVAL,
0,
(float)MAVLINK_MSG_ID_HEARTBEAT,
@@ -683,7 +899,7 @@ TEST(MavlinkTelemetryTest, RequestProtocolVersionUsesConfiguredVersion)
mavlink_message_t msg;
mavlink_msg_command_long_pack(
42, 200, &msg,
- 1, MAV_COMP_ID_MISSIONPLANNER,
+ 1, testTargetComponent,
MAV_CMD_REQUEST_PROTOCOL_VERSION,
0,
0, 0, 0, 0, 0, 0, 0);
@@ -703,6 +919,105 @@ TEST(MavlinkTelemetryTest, RequestProtocolVersionUsesConfiguredVersion)
EXPECT_EQ(version.max_version, 200);
}
+TEST(MavlinkTelemetryTest, RequestAutopilotCapabilitiesReportsLocalNedCapabilityAndPackedVersion)
+{
+ initMavlinkTestState();
+
+ mavlink_message_t msg;
+ mavlink_msg_command_long_pack(
+ 42, 200, &msg,
+ 1, testTargetComponent,
+ MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES,
+ 0,
+ 1, 0, 0, 0, 0, 0, 0);
+
+ pushRxMessage(&msg);
+ handleMAVLinkTelemetry(1000);
+
+ mavlink_status_t status;
+ memset(&status, 0, sizeof(status));
+ mavlink_message_t outMsg;
+ bool sawAutopilotVersion = false;
+
+ for (size_t i = 0; i < serialTxLen; i++) {
+ if (mavlink_parse_char(0, serialTxBuffer[i], &outMsg, &status) == MAVLINK_FRAMING_OK) {
+ if (outMsg.msgid == MAVLINK_MSG_ID_AUTOPILOT_VERSION) {
+ mavlink_autopilot_version_t version;
+ mavlink_msg_autopilot_version_decode(&outMsg, &version);
+ EXPECT_NE((version.capabilities & MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_LOCAL_NED), 0U);
+ EXPECT_EQ(version.flight_sw_version,
+ ((uint32_t)ARDUPILOT_VERSION_MAJOR << 24) |
+ ((uint32_t)ARDUPILOT_VERSION_MINOR << 16) |
+ ((uint32_t)ARDUPILOT_VERSION_PATCH << 8));
+ EXPECT_EQ(version.middleware_sw_version, 0U);
+ EXPECT_EQ(version.os_sw_version, 0U);
+ sawAutopilotVersion = true;
+ }
+ }
+ }
+
+ EXPECT_TRUE(sawAutopilotVersion);
+}
+
+TEST(MavlinkTelemetryTest, HeartbeatGuidedFlagRequiresValidGcsInPoshold)
+{
+ initMavlinkTestState();
+ testFlightMode = FLM_POSITION_HOLD;
+ gcsValid = false;
+
+ mavlinkSendHeartbeat();
+
+ mavlink_message_t msg;
+ ASSERT_TRUE(popTxMessage(&msg));
+ ASSERT_EQ(msg.msgid, MAVLINK_MSG_ID_HEARTBEAT);
+
+ mavlink_heartbeat_t heartbeat;
+ mavlink_msg_heartbeat_decode(&msg, &heartbeat);
+ EXPECT_EQ((heartbeat.base_mode & MAV_MODE_FLAG_GUIDED_ENABLED), 0);
+
+ serialTxLen = 0;
+ gcsValid = true;
+
+ mavlinkSendHeartbeat();
+
+ ASSERT_TRUE(popTxMessage(&msg));
+ ASSERT_EQ(msg.msgid, MAVLINK_MSG_ID_HEARTBEAT);
+
+ mavlink_msg_heartbeat_decode(&msg, &heartbeat);
+ EXPECT_NE((heartbeat.base_mode & MAV_MODE_FLAG_GUIDED_ENABLED), 0);
+}
+
+TEST(MavlinkTelemetryTest, PositionReportsPositiveDownVelocity)
+{
+ initMavlinkTestState();
+ testSensorsMask = SENSOR_GPS;
+ gpsSol.fixType = GPS_FIX_3D;
+ gpsSol.llh.lat = 375000000;
+ gpsSol.llh.lon = -1222500000;
+ gpsSol.llh.alt = 12345;
+ estimatedVelocity[Z] = 321.0f;
+
+ mavlinkSendPosition(1000);
+
+ mavlink_status_t status;
+ memset(&status, 0, sizeof(status));
+ mavlink_message_t msg;
+ bool sawGlobalPosition = false;
+
+ for (size_t i = 0; i < serialTxLen; i++) {
+ if (mavlink_parse_char(0, serialTxBuffer[i], &msg, &status) == MAVLINK_FRAMING_OK) {
+ if (msg.msgid == MAVLINK_MSG_ID_GLOBAL_POSITION_INT) {
+ mavlink_global_position_int_t position;
+ mavlink_msg_global_position_int_decode(&msg, &position);
+ EXPECT_EQ(position.vz, -321);
+ sawGlobalPosition = true;
+ }
+ }
+ }
+
+ EXPECT_TRUE(sawGlobalPosition);
+}
+
TEST(MavlinkTelemetryTest, BatteryStatusDoesNotSendExtendedSysState)
{
initMavlinkTestState();
@@ -731,7 +1046,7 @@ TEST(MavlinkTelemetryTest, RadioStatusUpdatesRxLinkStats)
initMavlinkTestState();
rxConfigMutable()->receiverType = RX_TYPE_SERIAL;
rxConfigMutable()->serialrx_provider = SERIALRX_MAVLINK;
- telemetryConfigMutable()->mavlink.radio_type = MAVLINK_RADIO_ELRS;
+ telemetryConfigMutable()->mavlink[0].radio_type = MAVLINK_RADIO_ELRS;
mavlink_message_t msg;
mavlink_msg_radio_status_pack(
@@ -753,7 +1068,24 @@ TEST(MavlinkTelemetryTest, RcChannelsOverrideIsForwarded)
mavlink_message_t msg;
mavlink_msg_rc_channels_override_pack(
42, 200, &msg,
- 1, MAV_COMP_ID_MISSIONPLANNER,
+ 1, testTargetComponent,
+ 1500, 1500, 1500, 1500, 1500, 1500, 1500, 1500,
+ 0, 0, 0, 0, 0, 0, 0, 0, 0, 0);
+
+ pushRxMessage(&msg);
+ handleMAVLinkTelemetry(1000);
+
+ EXPECT_EQ(mavlinkRxHandleCalls, 1);
+}
+
+TEST(MavlinkTelemetryTest, RcChannelsOverrideIgnoresTargetSystemMismatch)
+{
+ initMavlinkTestState();
+
+ mavlink_message_t msg;
+ mavlink_msg_rc_channels_override_pack(
+ 42, 200, &msg,
+ 99, testTargetComponent,
1500, 1500, 1500, 1500, 1500, 1500, 1500, 1500,
0, 0, 0, 0, 0, 0, 0, 0, 0, 0);
@@ -775,11 +1107,12 @@ gyro_t gyro;
gpsSolutionData_t gpsSol;
gpsLocation_t GPS_home;
navSystemStatus_t NAV_Status;
+navigationPosControl_t posControl;
rxRuntimeConfig_t rxRuntimeConfig;
rxLinkStatistics_t rxLinkStatistics;
uint16_t averageSystemLoadPercent;
-uint32_t micros(void)
+timeUs_t micros(void)
{
return 0;
}
@@ -792,11 +1125,18 @@ uint32_t millis(void)
serialPortConfig_t *findSerialPortConfig(serialPortFunction_e function)
{
UNUSED(function);
+ testPortConfig.functionMask = FUNCTION_TELEMETRY_MAVLINK;
testPortConfig.identifier = SERIAL_PORT_USART1;
testPortConfig.telemetry_baudrateIndex = BAUD_115200;
return &testPortConfig;
}
+serialPortConfig_t *findNextSerialPortConfig(serialPortFunction_e function)
+{
+ UNUSED(function);
+ return NULL;
+}
+
portSharing_e determinePortSharing(const serialPortConfig_t *portConfig, serialPortFunction_e function)
{
UNUSED(portConfig);
@@ -847,6 +1187,23 @@ void serialWrite(serialPort_t *instance, uint8_t ch)
serialTxBuffer[serialTxLen++] = ch;
}
+void serialWriteBuf(serialPort_t *instance, const uint8_t *data, int count)
+{
+ UNUSED(instance);
+ memcpy(&serialTxBuffer[serialTxLen], data, (size_t)count);
+ serialTxLen += (size_t)count;
+}
+
+void serialBeginWrite(serialPort_t *instance)
+{
+ UNUSED(instance);
+}
+
+void serialEndWrite(serialPort_t *instance)
+{
+ UNUSED(instance);
+}
+
void serialSetMode(serialPort_t *instance, portMode_t mode)
{
UNUSED(instance);
@@ -861,8 +1218,7 @@ bool telemetryDetermineEnabledState(portSharing_e portSharing)
bool sensors(uint32_t mask)
{
- UNUSED(mask);
- return false;
+ return (testSensorsMask & mask) != 0;
}
bool isAmperageConfigured(void)
@@ -870,6 +1226,11 @@ bool isAmperageConfigured(void)
return false;
}
+bool isBlackboxDeviceFull(void)
+{
+ return false;
+}
+
bool feature(uint32_t mask)
{
UNUSED(mask);
@@ -896,6 +1257,24 @@ uint8_t getBatteryCellCount(void)
return 0;
}
+batteryState_e getBatteryState(void)
+{
+ return BATTERY_OK;
+}
+
+bool isEstimatedWindSpeedValid(void)
+{
+ return false;
+}
+
+float getEstimatedHorizontalWindSpeed(uint16_t *angle)
+{
+ if (angle) {
+ *angle = 0;
+ }
+ return 0;
+}
+
uint16_t getBatteryAverageCellVoltage(void)
{
return 0;
@@ -919,14 +1298,12 @@ bool osdUsingScaledThrottle(void)
float getEstimatedActualPosition(int axis)
{
- UNUSED(axis);
- return 0.0f;
+ return estimatedPosition[axis];
}
float getEstimatedActualVelocity(int axis)
{
- UNUSED(axis);
- return 0.0f;
+ return estimatedVelocity[axis];
}
float getAirspeedEstimate(void)
@@ -1001,6 +1378,14 @@ int isGCSValid(void)
return gcsValid;
}
+bool navigationSetAltitudeTargetWithDatum(geoAltitudeDatumFlag_e datumFlag, int32_t targetAltitudeCm)
+{
+ altitudeTargetSetCalls++;
+ lastAltitudeTargetDatum = datumFlag;
+ lastAltitudeTargetCm = targetAltitudeCm;
+ return altitudeTargetSetResult;
+}
+
void setWaypoint(uint8_t wpNumber, const navWaypoint_t *wp)
{
UNUSED(wpNumber);
@@ -1036,7 +1421,7 @@ void resetWaypointList(void)
flightModeForTelemetry_e getFlightModeForTelemetry(void)
{
- return FLM_MANUAL;
+ return testFlightMode;
}
bool isModeActivationConditionPresent(boxId_e modeId)
diff --git a/src/test/unit/platform.h b/src/test/unit/platform.h
index 4f921e9612e..12b2671167b 100644
--- a/src/test/unit/platform.h
+++ b/src/test/unit/platform.h
@@ -79,6 +79,7 @@ extern SysTick_Type *SysTick;
#define WS2811_DMA_TC_FLAG 1
#define WS2811_DMA_HANDLER_IDENTIFER 0
+#include "target/common.h"
#include "target.h"
#define FAST_CODE
From c0c6fab1f3c08e962847a1514dd79a71c1d8d22e Mon Sep 17 00:00:00 2001
From: frogmane <7685285+xznhj8129@users.noreply.github.com>
Date: Wed, 1 Apr 2026 13:07:40 -0400
Subject: [PATCH 31/46] add mav yaw, fix missing cli yaml
---
docs/Mavlink.md | 1 +
src/main/fc/settings.yaml | 2 +-
src/main/telemetry/mavlink.c | 35 +++++++++++++++++++++++++++++++++++
3 files changed, 37 insertions(+), 1 deletion(-)
diff --git a/docs/Mavlink.md b/docs/Mavlink.md
index 78c89e0d648..0474a4a46a6 100644
--- a/docs/Mavlink.md
+++ b/docs/Mavlink.md
@@ -99,6 +99,7 @@ Messages are organized into MAVLink datastream groups. Each group sends **one me
Limited implementation of the Command protocol.
- `MAV_CMD_DO_REPOSITION`: sets the Follow Me/GCS Nav waypoint when GCS NAV is valid. Accepts `MAV_FRAME_GLOBAL`, `MAV_FRAME_GLOBAL_INT`, `MAV_FRAME_GLOBAL_RELATIVE_ALT`, `MAV_FRAME_GLOBAL_RELATIVE_ALT_INT`; otherwise `UNSUPPORTED`.
+- `MAV_CMD_CONDITION_YAW`: changes the current heading target when the active navigation state has yaw control. Accepts absolute heading (`param4=0`) and relative turns (`param4!=0`); turn-rate is ignored.
- `MAV_CMD_SET_MESSAGE_INTERVAL` / `MAV_CMD_GET_MESSAGE_INTERVAL`: adjust or query telemetry stream output for supported message IDs (streamed messages only; intervals slower than 1 Hz are not accepted).
- `MAV_CMD_GET_HOME_POSITION`: replies with `HOME_POSITION` when home fix exists.
- `MAV_CMD_REQUEST_MESSAGE`: emits one selected message (`HEARTBEAT`, `SYS_STATUS`, `ATTITUDE`, `VFR_HUD`, `AVAILABLE_MODES`, `CURRENT_MODE`, `EXTENDED_SYS_STATE`, RC channels, GPS/global/origin, battery/pressure, and `HOME_POSITION` when available) or `UNSUPPORTED`.
diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml
index 18fda6bc4e6..b9d09980455 100644
--- a/src/main/fc/settings.yaml
+++ b/src/main/fc/settings.yaml
@@ -199,7 +199,7 @@ tables:
values: ["NONE", "SERIAL", "MSP"]
enum: headTrackerDevType_e
- name: mavlink_radio_type
- values: ["GENERIC", "ELRS", "SIK"]
+ values: ["GENERIC", "ELRS", "SIK", "NONE"]
enum: mavlinkRadio_e
- name: mavlink_autopilot_type
values: ["GENERIC", "ARDUPILOT"]
diff --git a/src/main/telemetry/mavlink.c b/src/main/telemetry/mavlink.c
index e155e4594b4..aa0a290d06e 100644
--- a/src/main/telemetry/mavlink.c
+++ b/src/main/telemetry/mavlink.c
@@ -2273,6 +2273,34 @@ static bool handleIncoming_COMMAND(uint8_t targetSystem, uint8_t targetComponent
mavlinkSendCommandAck(command, result, ackTargetSystem, ackTargetComponent);
return true;
}
+ case MAV_CMD_CONDITION_YAW:
+ {
+ if (!(navGetCurrentStateFlags() & NAV_CTL_YAW)) {
+ mavlinkSendCommandAck(command, MAV_RESULT_DENIED, ackTargetSystem, ackTargetComponent);
+ return true;
+ }
+
+ int32_t targetHeadingCd = wrap_36000((int32_t)lrintf(param1 * 100.0f));
+
+ if (param4 != 0.0f) {
+ const int32_t currentHeadingCd = STATE(AIRPLANE) ? posControl.actualState.cog : posControl.actualState.yaw;
+ const int32_t headingChangeCd = (int32_t)lrintf(fabsf(param1) * 100.0f);
+
+ if (param3 < 0.0f) {
+ targetHeadingCd = wrap_36000(currentHeadingCd - headingChangeCd);
+ } else {
+ targetHeadingCd = wrap_36000(currentHeadingCd + headingChangeCd);
+ }
+ }
+
+ updateHeadingHoldTarget(CENTIDEGREES_TO_DEGREES(targetHeadingCd));
+ posControl.desiredState.yaw = targetHeadingCd;
+ posControl.cruise.course = targetHeadingCd;
+ posControl.cruise.previousCourse = targetHeadingCd;
+
+ mavlinkSendCommandAck(command, MAV_RESULT_ACCEPTED, ackTargetSystem, ackTargetComponent);
+ return true;
+ }
case MAV_CMD_SET_MESSAGE_INTERVAL:
{
uint8_t stream;
@@ -2933,6 +2961,13 @@ static int8_t mavlinkResolveLocalPortForTarget(int16_t targetSystem, int16_t tar
return -1;
}
+ if (ingressPortIndex < mavPortCount) {
+ const mavlinkTelemetryPortConfig_t *ingressCfg = mavlinkGetPortConfig(ingressPortIndex);
+ if (targetComponent <= 0 || ingressCfg->compid == targetComponent) {
+ return ingressPortIndex;
+ }
+ }
+
for (uint8_t portIndex = 0; portIndex < mavPortCount; portIndex++) {
const mavlinkTelemetryPortConfig_t *cfg = mavlinkGetPortConfig(portIndex);
if (targetComponent <= 0 || cfg->compid == targetComponent) {
From f2dacc1887cc0b97476760ecf4060766c770a702 Mon Sep 17 00:00:00 2001
From: frogmane <7685285+xznhj8129@users.noreply.github.com>
Date: Thu, 2 Apr 2026 14:39:05 -0400
Subject: [PATCH 32/46] Add MSP tunnel over MAVLink
---
docs/Mavlink.md | 125 +--
src/main/msp/msp_serial.c | 111 +++
src/main/msp/msp_serial.h | 3 +
src/main/telemetry/mavlink.c | 159 ++++
src/test/unit/CMakeLists.txt | 2 +-
src/test/unit/mavlink_unittest.cc | 283 +++++-
src/utils/mavlink_tests/ROUTING_TEST.md | 33 -
.../mavlink_tests/mav_multi_benchmark.py | 880 ------------------
src/utils/mavlink_tests/mav_multi_sweep.py | 164 ----
.../mavlink_routing_compliance_test.py | 499 ----------
src/utils/mavlink_tests/mavlink_test_rc.py | 141 ---
src/utils/mavlink_tests/msp_test_rc.py | 145 ---
.../mavlink_tests/routing_test_config.yaml | 58 --
..._multiport4_sweep_rc460800_tele115200.yaml | 51 -
14 files changed, 624 insertions(+), 2030 deletions(-)
delete mode 100644 src/utils/mavlink_tests/ROUTING_TEST.md
delete mode 100644 src/utils/mavlink_tests/mav_multi_benchmark.py
delete mode 100644 src/utils/mavlink_tests/mav_multi_sweep.py
delete mode 100644 src/utils/mavlink_tests/mavlink_routing_compliance_test.py
delete mode 100644 src/utils/mavlink_tests/mavlink_test_rc.py
delete mode 100644 src/utils/mavlink_tests/msp_test_rc.py
delete mode 100644 src/utils/mavlink_tests/routing_test_config.yaml
delete mode 100644 src/utils/mavlink_tests/test_config_multiport4_sweep_rc460800_tele115200.yaml
diff --git a/docs/Mavlink.md b/docs/Mavlink.md
index 0474a4a46a6..c42310a30ab 100644
--- a/docs/Mavlink.md
+++ b/docs/Mavlink.md
@@ -2,6 +2,8 @@
INAV has a partial implementation of MAVLink that is intended primarily for simple telemetry and operation. It supports RC, missions, telemetry and some features such as Guided mode; but it is very different from a compliant MAVLink spec vehicle such as Pixhawk or Ardupilot and important differences exist, as such it is not 100% compatible and cannot be expected to work the same way. The standard MAVLink header library is used in compilation.
+INAV supports up to 4 concurrent MAVLink telemetry ports (`MAX_MAVLINK_PORTS`), one endpoint per serial port configured with `FUNCTION_TELEMETRY_MAVLINK`.
+
## Fundamental differences from ArduPilot/PX4
- **No MAVLink parameter API**: INAV sends a single stub parameter and otherwise ignores parameter traffic. Configure the aircraft through the INAV Configurator or CLI instead.
@@ -11,54 +13,62 @@ INAV has a partial implementation of MAVLink that is intended primarily for simp
- **Flow control expectations**: INAV honours `RADIO_STATUS.txbuf` to avoid overrunning radios; without it, packets are simply paced at 20 ms intervals.
- **Half‑duplex etiquette**: when half‑duplex is enabled, INAV waits one telemetry tick after any received frame before transmitting to reduce collisions.
-### Relevant CLI options
-- `mavlink_sysid` – system ID used in every outbound packet (default 1); most inbound handlers only act on packets targeted to this system ID.
-- `mavlink_autopilot_type` – heartbeat autopilot ID (`GENERIC` or `ARDUPILOT`).
-- `mavlink_version` – force MAVLink v1 when set to 1.
-- Stream rates (Hz): `mavlink_port1_ext_status_rate`, `mavlink_port1_rc_chan_rate`, `mavlink_port1_pos_rate`, `mavlink_port1_extra1_rate`, `mavlink_port1_extra2_rate`, `mavlink_port1_extra3_rate`. Each group is polled up to 50 Hz; a rate of 0 disables the group.
-- `mavlink_port1_min_txbuffer` – minimum remote TX buffer level before sending when `RADIO_STATUS` provides flow control.
-- `mavlink_port1_radio_type` – scales `RADIO_STATUS` RSSI/SNR for **generic**, **ELRS**, or **SiK** links.
+### Usage guidance
+- If you rely on RC via MAVLink, ensure the serial receiver type is set to `SERIALRX_MAVLINK` and consider enabling `telemetry_halfduplex` when RX shares the port.
+- To reduce bandwidth, lower the stream rates for groups you do not need, or disable them entirely by setting the rate to 0.
+- Assign a unique `mavlink_port{1-4}_compid` to each INAV MAVLink port to avoid ambiguous local targeting.
+- If a GCS or companion needs telemetry on ports 2..4, explicitly request streams (`REQUEST_DATA_STREAM` or `MAV_CMD_SET_MESSAGE_INTERVAL`) because only heartbeat is enabled by default.
+- If you depend on directed forwarding between links, ensure each remote endpoint transmits at least one frame early so route learning is populated.
-## Multi-port MAVLink
+### Relevant CLI settings
+
+- `mavlink_sysid` - system ID used in every outbound packet (default 1); most inbound handlers only act on packets targeted to this system ID.
+- `mavlink_autopilot_type` - heartbeat autopilot ID (`GENERIC` or `ARDUPILOT`).
+- `mavlink_version` - force MAVLink v1 when set to 1.
+- Stream rates (Hz): Each group is polled up to 50 Hz; a rate of 0 disables the group.
+ - `mavlink_port{1-4}_ext_status_rate`
+ - `mavlink_port{1-4}_rc_chan_rate`
+ - `mavlink_port{1-4}_pos_rate`
+ - `mavlink_port{1-4}_extra1_rate`
+ - `mavlink_port{1-4}_extra2_rate`
+ - `mavlink_port{1-4}_extra3_rate`.
+- Port 1 uses configured CLI rates (`mavlink_port1_*_rate`).
+- Ports 2..4 start with heartbeat only (1 Hz), all other streams disabled.
+- `mavlink_port{1-4}_compid` - MAV_COMPONENT ID of port. Ensure these are different.
+- `mavlink_port{1-4}_min_txbuffer` - minimum remote TX buffer level before sending when `RADIO_STATUS` provides flow control.
+- `mavlink_port{1-4}_radio_type`- scales `RADIO_STATUS` RSSI/SNR for **generic**, **ELRS**, or **SiK** links.
+- `mavlink_port{1-4}_high_latency`- turns on Mavlink HIGH_LATENCY2 mode on this port
-INAV supports up to 4 concurrent MAVLink telemetry ports (`MAX_MAVLINK_PORTS`), one endpoint per serial port configured with `FUNCTION_TELEMETRY_MAVLINK`.
-### Configuration model
+## Datastream groups and defaults
-- Shared across all ports: `mavlink_sysid`, `mavlink_version`, `mavlink_autopilot_type`.
-- Per-port: `mavlink_portN_compid`, `mavlink_portN_min_txbuffer`, `mavlink_portN_radio_type`, `mavlink_portN_high_latency`.
-- Stream defaults at startup:
-- Port 1 uses configured CLI rates (`mavlink_port1_*_rate`).
-- Ports 2..4 start with heartbeat only (1 Hz), all other streams disabled.
+Default rates (Hz) are shown; adjust with the CLI keys above for port 1.
+Ports 2..N use a secondary startup profile (heartbeat at 1 Hz, other streams disabled).
-### Routing and forwarding behavior
+| Datastream group | Messages | Default rate |
+| --- | --- | --- |
+| `EXTENDED_STATUS` | `SYS_STATUS` | 2 Hz |
+| `RC_CHANNELS` | `RC_CHANNELS_RAW` (v1) / `RC_CHANNELS` (v2) | 1 Hz |
+| `POSITION` | `GPS_RAW_INT`, `GLOBAL_POSITION_INT`, `GPS_GLOBAL_ORIGIN` | 2 Hz |
+| `EXTRA1` | `ATTITUDE` | 3 Hz |
+| `EXTRA2` | `VFR_HUD` | 2 Hz |
+| `HEARTBEAT` | `HEARTBEAT` | 1 Hz (independent of stream groups) |
+| `EXT_SYS_STATE` | `EXTENDED_SYS_STATE` | 1 Hz (defaults to `mavlink_port1_extra3_rate`) |
+| `EXTRA3` | `BATTERY_STATUS`, `SCALED_PRESSURE`, `STATUSTEXT` (when present) | 1 Hz |
+
+### Routing, forwarding and local handling
- INAV learns routes from incoming traffic as `(sysid, compid) -> ingress port`.
- Broadcast messages are forwarded to all other MAVLink ports (except `RADIO_STATUS`, which is not forwarded).
- Targeted messages are forwarded only to ports with a learned route for that target.
- Practical caveat: the first targeted message to a never-seen endpoint may not forward until that endpoint has sent at least one MAVLink frame.
-
-### Local message handling behavior
-
- Local/system broadcasts (`target_system=0` or local system ID with `target_component=0`) are fanned out to all local ports only for:
-- `REQUEST_DATA_STREAM`
-- `MAV_CMD_SET_MESSAGE_INTERVAL`
-- `MAV_CMD_CONTROL_HIGH_LATENCY`
+ - `REQUEST_DATA_STREAM`
+ - `MAV_CMD_SET_MESSAGE_INTERVAL`
+ - `MAV_CMD_CONTROL_HIGH_LATENCY`
- Other incoming commands/messages are handled on one resolved local port, based on local target matching.
-### High-latency behavior
-
-- High-latency mode is per-port (`mavlink_portN_high_latency` or `MAV_CMD_CONTROL_HIGH_LATENCY` on that port).
-- Requires MAVLink2; MAVLink1 cannot enable it.
-- When enabled, normal stream scheduling for that port is replaced by `HIGH_LATENCY2` at 5-second intervals.
-
-### Usage guidance
-
-- Assign a unique `mavlink_portN_compid` to each INAV MAVLink port to avoid ambiguous local targeting.
-- If a GCS or companion needs telemetry on ports 2..4, explicitly request streams (`REQUEST_DATA_STREAM` or `MAV_CMD_SET_MESSAGE_INTERVAL`) because only heartbeat is enabled by default.
-- If you depend on directed forwarding between links, ensure each remote endpoint transmits at least one frame early so route learning is populated.
-
## Supported Outgoing Messages
Messages are organized into MAVLink datastream groups. Each group sends **one message per trigger** at the configured rate:
@@ -89,9 +99,10 @@ Messages are organized into MAVLink datastream groups. Each group sends **one me
- `SET_POSITION_TARGET_GLOBAL_INT`: writes the GCS-guided waypoint when the frame is supported; altitude-only requests are also accepted when X/Y are masked out and GCS navigation is valid.
- `SET_POSITION_TARGET_LOCAL_NED`: accepts altitude-only requests in `MAV_FRAME_LOCAL_OFFSET_NED` when X/Y are zero or ignored and GCS navigation is valid.
- `RC_CHANNELS_OVERRIDE` passes channel values to the MAVLink serial receiver backend.
-- `RADIO_STATUS` updates remote TX buffer level and scales RSSI/SNR according to `mavlink_port1_radio_type` (also feeds link stats for MAVLink RX receivers).
+- `RADIO_STATUS` updates remote TX buffer level and scales RSSI/SNR according to `mavlink_port{1-4}_radio_type` (also feeds link stats for MAVLink RX receivers).
- `ADSB_VEHICLE` populates the internal traffic list when ADS‑B is enabled.
- `PARAM_REQUEST_LIST` elicits a stub `PARAM_VALUE` response so ground stations stop requesting parameters (INAV does not expose parameters over MAVLink).
+- `TUNNEL` accepts private payload type `0x8001` for MSP-over-MAVLink on MAVLink2 links.
## Supported Commands
@@ -134,28 +145,6 @@ Limited implementation of the Command protocol.
- FAILSAFE → **RTL** (RTH/other phases) or **AUTOLAND** (landing phase)
- Any other unmapped mode falls back to **MANUAL**
-## Datastream groups and defaults
-
-Default rates (Hz) are shown; adjust with the CLI keys above for port 1.
-Ports 2..N use a secondary startup profile (heartbeat at 1 Hz, other streams disabled).
-
-| Datastream group | Messages | Default rate |
-| --- | --- | --- |
-| `EXTENDED_STATUS` | `SYS_STATUS` | 2 Hz |
-| `RC_CHANNELS` | `RC_CHANNELS_RAW` (v1) / `RC_CHANNELS` (v2) | 1 Hz |
-| `POSITION` | `GPS_RAW_INT`, `GLOBAL_POSITION_INT`, `GPS_GLOBAL_ORIGIN` | 2 Hz |
-| `EXTRA1` | `ATTITUDE` | 3 Hz |
-| `EXTRA2` | `VFR_HUD` | 2 Hz |
-| `HEARTBEAT` | `HEARTBEAT` | 1 Hz (independent of stream groups) |
-| `EXT_SYS_STATE` | `EXTENDED_SYS_STATE` | 1 Hz (defaults to `mavlink_port1_extra3_rate`) |
-| `EXTRA3` | `BATTERY_STATUS`, `SCALED_PRESSURE`, `STATUSTEXT` (when present) | 1 Hz |
-
-## Operating tips
-
-- Set `mavlink_port1_radio_type` to **ELRS** or **SiK** if you use those links to get accurate link quality scaling in `RADIO_STATUS`.
-- If you rely on RC override via MAVLink, ensure the serial receiver type is set to `SERIALRX_MAVLINK` and consider enabling `telemetry_halfduplex` when RX shares the port.
-- To reduce bandwidth, lower the stream rates for groups you do not need, or disable them entirely by setting the rate to 0.
-
## MAVLink Missions
@@ -171,3 +160,25 @@ Partial compatibility with MAVLink mission planners such as QGC is implemented,
- SET_POI: lat/lon/alt OK; `param1` is fixed to `MAV_ROI_LOCATION`; user-action bits in `p3` are dropped (alt-mode bit respected on upload).
- SET_HEAD: heading `p1` OK; user-action bits in `p3` are not represented.
- Net effect: actions and positions OK, but MSP-specific fields (leg speed, LAND elevation adjustment, RTH land flag, user-action bits in `p3`) are lost, so MAVLink missions cannot fully conform to `MSP_navigation_messages.md`.
+
+
+## MSP over MAVLink tunnel
+This feature uses the MAVLink [Tunnel service](https://mavlink.io/en/services/tunnel.html) to let the INAV Configurator use MSP over an existing MAVLink telemetry link, typically a radio link where there is no separate wireless MSP device.
+**It is not intended as a general-purpose serial tunnel, and it is not a replacement for normal MAVLink control/telemetry traffic.**
+CLI mode is unavailable in MSP-over-MAVLink.
+
+- INAV accepts `TUNNEL` messages with private payload type `0x8001` as an MSP byte stream carried over MAVLink2.
+- `target_system` must match `mavlink_sysid`.
+- `target_component` may be `0` or the local port `mavlink_port{1-4}_compid`.
+- `target_component=0` is handled on the ingress MAVLink port only; it is not fanned out to other local MAVLink ports.
+- MSP replies are sent back to the requester as one or more `TUNNEL` messages on that same ingress port.
+- MSP framing is preserved end-to-end: MSPv1 requests get MSPv1 replies, and MSPv2 requests get MSPv2 replies.
+- Reboot (`MSP_REBOOT`) is supported over the tunnel. Serial passthrough and ESC 4way passthrough are rejected before execution.
+
+## High latency mode
+High-latency mode uses the MAVLink [High Latency service](https://mavlink.io/en/services/high_latency.html) to replace normal scheduled telemetry on one port with periodic `HIGH_LATENCY2` summaries for very low-bandwidth or intermittent links.
+
+- High latency mode is per-port, controlled by `mavlink_port{1-4}_high_latency` or by `MAV_CMD_CONTROL_HIGH_LATENCY` received on that port.
+- It requires MAVLink2. MAVLink1 cannot enable or carry `HIGH_LATENCY2`.
+- When enabled on a port, normal stream scheduling on that port is replaced by `HIGH_LATENCY2` at 5 second intervals.
+- This is intended for slow and high latency telemetry such as cellular, satellite or LoRa, not for normal rich telemetry, mission planning, or configurator use.
diff --git a/src/main/msp/msp_serial.c b/src/main/msp/msp_serial.c
index 32aac7a7bd5..02e36004c89 100644
--- a/src/main/msp/msp_serial.c
+++ b/src/main/msp/msp_serial.c
@@ -259,6 +259,11 @@ static bool mspSerialProcessReceivedData(mspPort_t *mspPort, uint8_t c)
return true;
}
+bool mspSerialProcessReceivedByte(mspPort_t *mspPort, uint8_t c)
+{
+ return mspSerialProcessReceivedData(mspPort, c);
+}
+
static uint8_t mspSerialChecksumBuf(uint8_t checksum, const uint8_t *data, int len)
{
while (len-- > 0) {
@@ -391,6 +396,98 @@ static int mspSerialEncode(mspPort_t *msp, mspPacket_t *packet, mspVersion_e msp
return mspSerialSendFrame(msp, hdrBuf, hdrLen, sbufPtr(&packet->buf), dataLen, crcBuf, crcLen);
}
+int mspSerialEncodePacket(mspPacket_t *packet, mspVersion_e mspVersion, uint8_t *frameBuf, int frameBufSize)
+{
+ static const uint8_t mspMagic[MSP_VERSION_COUNT] = MSP_VERSION_MAGIC_INITIALIZER;
+ const int dataLen = sbufBytesRemaining(&packet->buf);
+ uint8_t hdrBuf[16] = { '$', mspMagic[mspVersion], packet->result == MSP_RESULT_ERROR ? '!' : '>'};
+ uint8_t crcBuf[2];
+ int hdrLen = 3;
+ int crcLen = 0;
+
+ if (mspVersion == MSP_V1) {
+ mspHeaderV1_t * hdrV1 = (mspHeaderV1_t *)&hdrBuf[hdrLen];
+ hdrLen += sizeof(mspHeaderV1_t);
+ hdrV1->cmd = packet->cmd;
+
+ if (dataLen >= JUMBO_FRAME_SIZE_LIMIT) {
+ mspHeaderJUMBO_t * hdrJUMBO = (mspHeaderJUMBO_t *)&hdrBuf[hdrLen];
+ hdrLen += sizeof(mspHeaderJUMBO_t);
+
+ hdrV1->size = JUMBO_FRAME_SIZE_LIMIT;
+ hdrJUMBO->size = dataLen;
+ }
+ else {
+ hdrV1->size = dataLen;
+ }
+
+ crcBuf[crcLen] = mspSerialChecksumBuf(0, hdrBuf + V1_CHECKSUM_STARTPOS, hdrLen - V1_CHECKSUM_STARTPOS);
+ crcBuf[crcLen] = mspSerialChecksumBuf(crcBuf[crcLen], sbufPtr(&packet->buf), dataLen);
+ crcLen++;
+ }
+ else if (mspVersion == MSP_V2_OVER_V1) {
+ mspHeaderV1_t * hdrV1 = (mspHeaderV1_t *)&hdrBuf[hdrLen];
+
+ hdrLen += sizeof(mspHeaderV1_t);
+
+ mspHeaderV2_t * hdrV2 = (mspHeaderV2_t *)&hdrBuf[hdrLen];
+ hdrLen += sizeof(mspHeaderV2_t);
+
+ const int v1PayloadSize = sizeof(mspHeaderV2_t) + dataLen + 1;
+ hdrV1->cmd = MSP_V2_FRAME_ID;
+
+ if (v1PayloadSize >= JUMBO_FRAME_SIZE_LIMIT) {
+ mspHeaderJUMBO_t * hdrJUMBO = (mspHeaderJUMBO_t *)&hdrBuf[hdrLen];
+ hdrLen += sizeof(mspHeaderJUMBO_t);
+
+ hdrV1->size = JUMBO_FRAME_SIZE_LIMIT;
+ hdrJUMBO->size = v1PayloadSize;
+ }
+ else {
+ hdrV1->size = v1PayloadSize;
+ }
+
+ hdrV2->flags = packet->flags;
+ hdrV2->cmd = packet->cmd;
+ hdrV2->size = dataLen;
+
+ crcBuf[crcLen] = crc8_dvb_s2_update(0, (uint8_t *)hdrV2, sizeof(mspHeaderV2_t));
+ crcBuf[crcLen] = crc8_dvb_s2_update(crcBuf[crcLen], sbufPtr(&packet->buf), dataLen);
+ crcLen++;
+
+ crcBuf[crcLen] = mspSerialChecksumBuf(0, hdrBuf + V1_CHECKSUM_STARTPOS, hdrLen - V1_CHECKSUM_STARTPOS);
+ crcBuf[crcLen] = mspSerialChecksumBuf(crcBuf[crcLen], sbufPtr(&packet->buf), dataLen);
+ crcBuf[crcLen] = mspSerialChecksumBuf(crcBuf[crcLen], crcBuf, crcLen);
+ crcLen++;
+ }
+ else if (mspVersion == MSP_V2_NATIVE) {
+ mspHeaderV2_t * hdrV2 = (mspHeaderV2_t *)&hdrBuf[hdrLen];
+ hdrLen += sizeof(mspHeaderV2_t);
+
+ hdrV2->flags = packet->flags;
+ hdrV2->cmd = packet->cmd;
+ hdrV2->size = dataLen;
+
+ crcBuf[crcLen] = crc8_dvb_s2_update(0, (uint8_t *)hdrV2, sizeof(mspHeaderV2_t));
+ crcBuf[crcLen] = crc8_dvb_s2_update(crcBuf[crcLen], sbufPtr(&packet->buf), dataLen);
+ crcLen++;
+ }
+ else {
+ return 0;
+ }
+
+ const int totalFrameLength = hdrLen + dataLen + crcLen;
+ if (frameBufSize < totalFrameLength) {
+ return 0;
+ }
+
+ memcpy(frameBuf, hdrBuf, hdrLen);
+ memcpy(frameBuf + hdrLen, sbufPtr(&packet->buf), dataLen);
+ memcpy(frameBuf + hdrLen + dataLen, crcBuf, crcLen);
+
+ return totalFrameLength;
+}
+
static mspPostProcessFnPtr mspSerialProcessReceivedCommand(mspPort_t *msp, mspProcessCommandFnPtr mspProcessCommandFn)
{
uint8_t outBuf[MSP_PORT_OUTBUF_SIZE];
@@ -422,6 +519,20 @@ static mspPostProcessFnPtr mspSerialProcessReceivedCommand(mspPort_t *msp, mspPr
return mspPostProcessFn;
}
+mspResult_e mspSerialProcessCommand(mspPort_t *msp, mspProcessCommandFnPtr mspProcessCommandFn, mspPacket_t *reply, mspPostProcessFnPtr *mspPostProcessFn)
+{
+ mspPacket_t command = {
+ .buf = { .ptr = msp->inBuf, .end = msp->inBuf + msp->dataSize, },
+ .cmd = msp->cmdMSP,
+ .flags = msp->cmdFlags,
+ .result = 0,
+ };
+
+ const mspResult_e status = mspProcessCommandFn(&command, reply, mspPostProcessFn);
+ msp->c_state = MSP_IDLE;
+ return status;
+}
+
static void mspEvaluateNonMspData(mspPort_t * mspPort, uint8_t receivedChar)
{
if (receivedChar == '#') {
diff --git a/src/main/msp/msp_serial.h b/src/main/msp/msp_serial.h
index 67487606da0..86fa6461217 100644
--- a/src/main/msp/msp_serial.h
+++ b/src/main/msp/msp_serial.h
@@ -101,6 +101,9 @@ typedef struct mspPort_s {
void mspSerialInit(void);
void resetMspPort(mspPort_t *mspPortToReset, serialPort_t *serialPort);
+bool mspSerialProcessReceivedByte(mspPort_t *mspPort, uint8_t c);
+int mspSerialEncodePacket(mspPacket_t *packet, mspVersion_e mspVersion, uint8_t *frameBuf, int frameBufSize);
+mspResult_e mspSerialProcessCommand(mspPort_t *msp, mspProcessCommandFnPtr mspProcessCommandFn, mspPacket_t *reply, mspPostProcessFnPtr *mspPostProcessFn);
void mspSerialProcess(mspEvaluateNonMspData_e evaluateNonMspData, mspProcessCommandFnPtr mspProcessCommandFn);
void mspSerialProcessOnePort(mspPort_t * const mspPort, mspEvaluateNonMspData_e evaluateNonMspData, mspProcessCommandFnPtr mspProcessCommandFn);
void mspSerialAllocatePorts(void);
diff --git a/src/main/telemetry/mavlink.c b/src/main/telemetry/mavlink.c
index aa0a290d06e..6b7e5496475 100644
--- a/src/main/telemetry/mavlink.c
+++ b/src/main/telemetry/mavlink.c
@@ -48,6 +48,7 @@
#include "fc/config.h"
#include "fc/fc_core.h"
+#include "fc/fc_msp.h"
#include "fc/rc_controls.h"
#include "fc/rc_modes.h"
#include "fc/runtime_config.h"
@@ -66,6 +67,9 @@
#include "io/serial.h"
#include "io/osd.h"
+#include "msp/msp_protocol.h"
+#include "msp/msp_serial.h"
+
#include "navigation/navigation.h"
#include "navigation/navigation_private.h"
@@ -106,6 +110,9 @@ static mavlinkPortRuntime_t mavPortStates[MAX_MAVLINK_PORTS];
static uint8_t mavPortCount = 0;
static mavlinkRouteEntry_t mavRouteTable[MAVLINK_MAX_ROUTES];
static uint8_t mavRouteCount = 0;
+static mspPort_t mavTunnelMspPorts[MAX_MAVLINK_PORTS];
+static uint8_t mavTunnelRemoteSystemIds[MAX_MAVLINK_PORTS];
+static uint8_t mavTunnelRemoteComponentIds[MAX_MAVLINK_PORTS];
static uint8_t mavSendMask = 0;
static mavlinkPortRuntime_t *mavActivePort = NULL;
static const mavlinkTelemetryPortConfig_t *mavActiveConfig = NULL;
@@ -117,6 +124,13 @@ static uint8_t mavSystemId = 1;
static uint8_t mavAutopilotType;
static uint8_t mavComponentId = MAV_COMP_ID_AUTOPILOT1;
+#define MAVLINK_TUNNEL_PAYLOAD_TYPE_INAV_MSP 0x8001
+#define MAVLINK_TUNNEL_MSP_TIMEOUT_MS 1000
+#define MAVLINK_TUNNEL_MSP_FRAMEBUF_SIZE (MSP_PORT_OUTBUF_SIZE + 16)
+
+static uint8_t mavTunnelReplyPayloadBuf[MSP_PORT_OUTBUF_SIZE];
+static uint8_t mavTunnelFrameBuf[MAVLINK_TUNNEL_MSP_FRAMEBUF_SIZE];
+
static uint8_t mavlinkGetVehicleType(void)
{
switch (mixerConfig()->platformType)
@@ -363,6 +377,9 @@ static void freeMAVLinkTelemetryPortByIndex(uint8_t portIndex)
memset(state->mavStreamNextDue, 0, sizeof(state->mavStreamNextDue));
memset(&state->mavRecvStatus, 0, sizeof(state->mavRecvStatus));
memset(&state->mavRecvMsg, 0, sizeof(state->mavRecvMsg));
+ resetMspPort(&mavTunnelMspPorts[portIndex], NULL);
+ mavTunnelRemoteSystemIds[portIndex] = 0;
+ mavTunnelRemoteComponentIds[portIndex] = 0;
}
void freeMAVLinkTelemetryPort(void)
@@ -379,6 +396,9 @@ void initMAVLinkTelemetry(void)
{
memset(mavPortStates, 0, sizeof(mavPortStates));
memset(mavRouteTable, 0, sizeof(mavRouteTable));
+ memset(mavTunnelMspPorts, 0, sizeof(mavTunnelMspPorts));
+ memset(mavTunnelRemoteSystemIds, 0, sizeof(mavTunnelRemoteSystemIds));
+ memset(mavTunnelRemoteComponentIds, 0, sizeof(mavTunnelRemoteComponentIds));
mavPortCount = 0;
mavRouteCount = 0;
mavSendMask = 0;
@@ -430,6 +450,9 @@ static void configureMAVLinkTelemetryPort(uint8_t portIndex)
memset(state->mavStreamNextDue, 0, sizeof(state->mavStreamNextDue));
memset(&state->mavRecvStatus, 0, sizeof(state->mavRecvStatus));
memset(&state->mavRecvMsg, 0, sizeof(state->mavRecvMsg));
+ resetMspPort(&mavTunnelMspPorts[portIndex], NULL);
+ mavTunnelRemoteSystemIds[portIndex] = 0;
+ mavTunnelRemoteComponentIds[portIndex] = 0;
}
void checkMAVLinkTelemetryState(void)
@@ -526,6 +549,139 @@ static void mavlinkSendMessage(void)
}
}
+static void mavlinkResetTunnelState(uint8_t ingressPortIndex)
+{
+ resetMspPort(&mavTunnelMspPorts[ingressPortIndex], NULL);
+ mavTunnelRemoteSystemIds[ingressPortIndex] = 0;
+ mavTunnelRemoteComponentIds[ingressPortIndex] = 0;
+}
+
+static void mavlinkSendTunnelReply(uint8_t targetSystem, uint8_t targetComponent, const uint8_t *payload, uint8_t payloadLength)
+{
+ uint8_t tunnelPayload[MAVLINK_MSG_TUNNEL_FIELD_PAYLOAD_LEN] = { 0 };
+ memcpy(tunnelPayload, payload, payloadLength);
+
+ mavlink_msg_tunnel_pack(
+ mavSystemId,
+ mavComponentId,
+ &mavSendMsg,
+ targetSystem,
+ targetComponent,
+ MAVLINK_TUNNEL_PAYLOAD_TYPE_INAV_MSP,
+ payloadLength,
+ tunnelPayload);
+ mavlinkSendMessage();
+}
+
+static void mavlinkSendTunnelMspReply(uint8_t targetSystem, uint8_t targetComponent, mspPacket_t *reply, uint8_t *replyPayloadHead, mspVersion_e mspVersion)
+{
+ sbufSwitchToReader(&reply->buf, replyPayloadHead);
+
+ const int frameLength = mspSerialEncodePacket(reply, mspVersion, mavTunnelFrameBuf, sizeof(mavTunnelFrameBuf));
+ for (int offset = 0; offset < frameLength; offset += MAVLINK_MSG_TUNNEL_FIELD_PAYLOAD_LEN) {
+ const uint8_t chunkLength = MIN(MAVLINK_MSG_TUNNEL_FIELD_PAYLOAD_LEN, frameLength - offset);
+ mavlinkSendTunnelReply(
+ targetSystem,
+ targetComponent,
+ mavTunnelFrameBuf + offset,
+ chunkLength);
+ }
+}
+
+static bool handleIncoming_TUNNEL(uint8_t ingressPortIndex)
+{
+ if (mavlinkGetProtocolVersion() == 1) {
+ return false;
+ }
+
+ mavlink_tunnel_t msg;
+ mavlink_msg_tunnel_decode(&mavRecvMsg, &msg);
+
+ if (msg.payload_type != MAVLINK_TUNNEL_PAYLOAD_TYPE_INAV_MSP) {
+ return false;
+ }
+
+ if (msg.target_system != mavSystemId) {
+ return false;
+ }
+
+ if (msg.target_component != 0 && msg.target_component != mavComponentId) {
+ return false;
+ }
+
+ mspPort_t *mspPort = &mavTunnelMspPorts[ingressPortIndex];
+ const timeMs_t now = millis();
+ if (msg.payload_length > MAVLINK_MSG_TUNNEL_FIELD_PAYLOAD_LEN) {
+ mavlinkResetTunnelState(ingressPortIndex);
+ return false;
+ }
+
+ if (mspPort->c_state != MSP_IDLE &&
+ ((now - mspPort->lastActivityMs) > MAVLINK_TUNNEL_MSP_TIMEOUT_MS ||
+ mavTunnelRemoteSystemIds[ingressPortIndex] != mavRecvMsg.sysid ||
+ mavTunnelRemoteComponentIds[ingressPortIndex] != mavRecvMsg.compid)) {
+ mavlinkResetTunnelState(ingressPortIndex);
+ }
+
+ mavTunnelRemoteSystemIds[ingressPortIndex] = mavRecvMsg.sysid;
+ mavTunnelRemoteComponentIds[ingressPortIndex] = mavRecvMsg.compid;
+ mspPort->lastActivityMs = now;
+
+ bool handled = false;
+ for (uint8_t payloadIndex = 0; payloadIndex < msg.payload_length; payloadIndex++) {
+ if (!mspSerialProcessReceivedByte(mspPort, msg.payload[payloadIndex])) {
+ continue;
+ }
+
+ handled = true;
+ if (mspPort->c_state != MSP_COMMAND_RECEIVED) {
+ continue;
+ }
+
+ mspPacket_t reply = {
+ .buf = { .ptr = mavTunnelReplyPayloadBuf, .end = ARRAYEND(mavTunnelReplyPayloadBuf), },
+ .cmd = -1,
+ .flags = 0,
+ .result = 0,
+ };
+ uint8_t *replyPayloadHead = reply.buf.ptr;
+
+ if (mspPort->cmdMSP == MSP_SET_PASSTHROUGH) {
+ reply.cmd = MSP_SET_PASSTHROUGH;
+ reply.result = MSP_RESULT_ERROR;
+ mavlinkSendTunnelMspReply(mavRecvMsg.sysid, mavRecvMsg.compid, &reply, replyPayloadHead, mspPort->mspVersion);
+ mavlinkResetTunnelState(ingressPortIndex);
+ break;
+ }
+
+ mspPostProcessFnPtr mspPostProcessFn = NULL;
+ const uint16_t command = mspPort->cmdMSP;
+ mspResult_e status = mspSerialProcessCommand(mspPort, mspFcProcessCommand, &reply, &mspPostProcessFn);
+
+ if (mspPostProcessFn && command != MSP_REBOOT) {
+ sbufInit(&reply.buf, mavTunnelReplyPayloadBuf, ARRAYEND(mavTunnelReplyPayloadBuf));
+ reply.result = MSP_RESULT_ERROR;
+ mspPostProcessFn = NULL;
+ status = MSP_RESULT_ERROR;
+ }
+
+ if (status != MSP_RESULT_NO_REPLY) {
+ mavlinkSendTunnelMspReply(mavRecvMsg.sysid, mavRecvMsg.compid, &reply, replyPayloadHead, mspPort->mspVersion);
+ }
+
+ mavlinkResetTunnelState(ingressPortIndex);
+
+ if (mspPostProcessFn) {
+ waitForSerialPortToFinishTransmitting(mavPortStates[ingressPortIndex].port);
+ mspPostProcessFn(mavPortStates[ingressPortIndex].port);
+ }
+
+ break;
+ }
+
+ return handled;
+}
+
static void mavlinkSendAutopilotVersion(void)
{
if (mavlinkGetProtocolVersion() == 1) return;
@@ -3111,6 +3267,9 @@ static bool processMAVLinkIncomingTelemetry(uint8_t ingressPortIndex)
// Don't set that we handled a message, otherwise radio status packets will block telemetry messages.
localHandled = false;
break;
+ case MAVLINK_MSG_ID_TUNNEL:
+ localHandled = handleIncoming_TUNNEL(ingressPortIndex);
+ break;
default:
localHandled = false;
break;
diff --git a/src/test/unit/CMakeLists.txt b/src/test/unit/CMakeLists.txt
index f377b24a80e..7debcc97758 100644
--- a/src/test/unit/CMakeLists.txt
+++ b/src/test/unit/CMakeLists.txt
@@ -44,7 +44,7 @@ set_property(SOURCE gimbal_serial_unittest.cc PROPERTY depends "io/gimbal_serial
set_property(SOURCE gimbal_serial_unittest.cc PROPERTY definitions USE_SERIAL_GIMBAL GIMBAL_UNIT_TEST USE_HEADTRACKER)
set_property(SOURCE mavlink_unittest.cc PROPERTY depends
- "telemetry/mavlink.c" "common/maths.c")
+ "telemetry/mavlink.c" "common/crc.c" "common/maths.c" "common/streambuf.c" "msp/msp_serial.c")
set_property(SOURCE mavlink_unittest.cc PROPERTY definitions USE_TELEMETRY USE_TELEMETRY_MAVLINK)
set_property(SOURCE mavlink_unittest.cc PROPERTY includes
"${CMAKE_CURRENT_SOURCE_DIR}/../../../lib/main/MAVLink")
diff --git a/src/test/unit/mavlink_unittest.cc b/src/test/unit/mavlink_unittest.cc
index 641f31432d2..a60b72357b2 100644
--- a/src/test/unit/mavlink_unittest.cc
+++ b/src/test/unit/mavlink_unittest.cc
@@ -20,6 +20,7 @@
#include
#include
+#include
extern "C" {
#include "platform.h"
@@ -28,6 +29,7 @@ extern "C" {
#include "common/axis.h"
#include "common/maths.h"
+ #include "common/streambuf.h"
#include "common/time.h"
#include "config/parameter_group.h"
@@ -51,6 +53,10 @@ extern "C" {
#include "io/gps.h"
#include "io/osd.h"
+ #include "msp/msp.h"
+ #include "msp/msp_protocol.h"
+ #include "msp/msp_serial.h"
+
#include "navigation/navigation.h"
#ifdef __cplusplus
#define _Static_assert static_assert
@@ -95,6 +101,17 @@ static size_t serialRxLen;
static size_t serialRxPos;
static size_t serialTxLen;
static const uint8_t testTargetComponent = MAV_COMP_ID_AUTOPILOT1;
+static const uint8_t testTunnelSourceSystem = 42;
+static const uint8_t testTunnelSourceComponent = 200;
+static const uint8_t testSimpleMspCommand = 90;
+static const uint8_t testLargeReplyMspCommand = 91;
+static const size_t testMspFrameBufSize = MSP_PORT_OUTBUF_SIZE + 16;
+static timeMs_t fakeMillis;
+static int mspCommandCallCount;
+static int mspPassthroughDispatchCount;
+static int mspRebootPostProcessCount;
+static int waitForSerialPortToFinishTransmittingCalls;
+static serialPort_t *lastPostProcessPort;
const uint32_t baudRates[] = {
0, 1200, 2400, 4800, 9600, 19200, 38400, 57600, 115200, 230400, 250000,
@@ -124,6 +141,42 @@ static void resetSerialBuffers(void)
serialTxLen = 0;
}
+static std::vector makeMspV1Request(uint8_t cmd, const std::vector &payload = {})
+{
+ std::vector frame = {
+ '$', 'M', '<',
+ static_cast(payload.size()),
+ cmd
+ };
+ uint8_t checksum = frame[3] ^ frame[4];
+ for (const uint8_t byte : payload) {
+ frame.push_back(byte);
+ checksum ^= byte;
+ }
+ frame.push_back(checksum);
+ return frame;
+}
+
+static std::vector encodeMspV1Reply(uint8_t cmd, int16_t result, const std::vector &payload = {})
+{
+ uint8_t payloadBuf[MSP_PORT_OUTBUF_SIZE];
+ mspPacket_t reply = {
+ .buf = { .ptr = payloadBuf, .end = ARRAYEND(payloadBuf), },
+ .cmd = cmd,
+ .flags = 0,
+ .result = result,
+ };
+ uint8_t *payloadHead = reply.buf.ptr;
+ if (!payload.empty()) {
+ sbufWriteData(&reply.buf, payload.data(), (int)payload.size());
+ }
+ sbufSwitchToReader(&reply.buf, payloadHead);
+
+ uint8_t frameBuf[testMspFrameBufSize];
+ const int frameLength = mspSerialEncodePacket(&reply, MSP_V1, frameBuf, sizeof(frameBuf));
+ return std::vector(frameBuf, frameBuf + frameLength);
+}
+
static void pushRxMessage(const mavlink_message_t *msg)
{
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
@@ -132,6 +185,30 @@ static void pushRxMessage(const mavlink_message_t *msg)
serialRxLen += (size_t)length;
}
+static void pushTunnelPayload(uint8_t payloadLength, const std::vector &payload, uint8_t targetComponent = testTargetComponent)
+{
+ uint8_t tunnelPayload[MAVLINK_MSG_TUNNEL_FIELD_PAYLOAD_LEN] = { 0 };
+ size_t copyLength = payload.size();
+ if (copyLength > MAVLINK_MSG_TUNNEL_FIELD_PAYLOAD_LEN) {
+ copyLength = MAVLINK_MSG_TUNNEL_FIELD_PAYLOAD_LEN;
+ }
+ if (copyLength > 0) {
+ memcpy(tunnelPayload, payload.data(), copyLength);
+ }
+
+ mavlink_message_t msg;
+ mavlink_msg_tunnel_pack(
+ testTunnelSourceSystem,
+ testTunnelSourceComponent,
+ &msg,
+ telemetryConfig()->mavlink_common.sysid,
+ targetComponent,
+ 0x8001,
+ payloadLength,
+ tunnelPayload);
+ pushRxMessage(&msg);
+}
+
static bool popTxMessage(mavlink_message_t *msg)
{
mavlink_status_t status;
@@ -144,12 +221,54 @@ static bool popTxMessage(mavlink_message_t *msg)
return false;
}
+static std::vector parseTxMessages(void)
+{
+ std::vector messages;
+ mavlink_status_t status;
+ memset(&status, 0, sizeof(status));
+
+ mavlink_message_t msg;
+ for (size_t i = 0; i < serialTxLen; i++) {
+ if (mavlink_parse_char(0, serialTxBuffer[i], &msg, &status) == MAVLINK_FRAMING_OK) {
+ messages.push_back(msg);
+ }
+ }
+
+ return messages;
+}
+
+static std::vector collectTunnelPayload(const std::vector &messages)
+{
+ std::vector payload;
+
+ for (const mavlink_message_t &msg : messages) {
+ EXPECT_EQ(msg.msgid, MAVLINK_MSG_ID_TUNNEL);
+
+ mavlink_tunnel_t tunnel;
+ mavlink_msg_tunnel_decode(&msg, &tunnel);
+
+ EXPECT_EQ(tunnel.payload_type, 0x8001);
+ EXPECT_EQ(tunnel.target_system, testTunnelSourceSystem);
+ EXPECT_EQ(tunnel.target_component, testTunnelSourceComponent);
+
+ payload.insert(payload.end(), tunnel.payload, tunnel.payload + tunnel.payload_length);
+ }
+
+ return payload;
+}
+
static void initMavlinkTestState(void)
{
resetSerialBuffers();
+ fakeMillis = 0;
setWaypointCalls = 0;
resetWaypointCalls = 0;
mavlinkRxHandleCalls = 0;
+ mspCommandCallCount = 0;
+ mspPassthroughDispatchCount = 0;
+ mspRebootPostProcessCount = 0;
+ waitForSerialPortToFinishTransmittingCalls = 0;
+ lastPostProcessPort = NULL;
gcsValid = true;
waypointCount = 0;
memset(estimatedPosition, 0, sizeof(estimatedPosition));
@@ -185,6 +304,99 @@ static void initMavlinkTestState(void)
checkMAVLinkTelemetryState();
}
+TEST(MavlinkTelemetryTest, TunnelMalformedPayloadLengthIsDroppedAndDoesNotPoisonState)
+{
+ initMavlinkTestState();
+
+ std::vector request = makeMspV1Request(testSimpleMspCommand);
+ request.resize(MAVLINK_MSG_TUNNEL_FIELD_PAYLOAD_LEN, 0);
+
+ pushTunnelPayload(MAVLINK_MSG_TUNNEL_FIELD_PAYLOAD_LEN + 1, request);
+ handleMAVLinkTelemetry(1000);
+
+ EXPECT_EQ(mspCommandCallCount, 0);
+ EXPECT_TRUE(parseTxMessages().empty());
+
+ resetSerialBuffers();
+ pushTunnelPayload((uint8_t)makeMspV1Request(testSimpleMspCommand).size(), makeMspV1Request(testSimpleMspCommand));
+ handleMAVLinkTelemetry(1000);
+
+ EXPECT_EQ(mspCommandCallCount, 1);
+ EXPECT_EQ(collectTunnelPayload(parseTxMessages()), encodeMspV1Reply(testSimpleMspCommand, MSP_RESULT_ACK));
+}
+
+TEST(MavlinkTelemetryTest, TunnelRejectsPassthroughBeforeDispatch)
+{
+ initMavlinkTestState();
+
+ const std::vector request = makeMspV1Request((uint8_t)MSP_SET_PASSTHROUGH);
+
+ pushTunnelPayload((uint8_t)request.size(), request);
+ handleMAVLinkTelemetry(1000);
+
+ EXPECT_EQ(mspCommandCallCount, 0);
+ EXPECT_EQ(mspPassthroughDispatchCount, 0);
+ EXPECT_EQ(waitForSerialPortToFinishTransmittingCalls, 0);
+ EXPECT_EQ(mspRebootPostProcessCount, 0);
+ EXPECT_EQ(collectTunnelPayload(parseTxMessages()), encodeMspV1Reply((uint8_t)MSP_SET_PASSTHROUGH, MSP_RESULT_ERROR));
+}
+
+TEST(MavlinkTelemetryTest, TunnelRebootUsesIngressPortForPostProcess)
+{
+ initMavlinkTestState();
+
+ const std::vector request = makeMspV1Request((uint8_t)MSP_REBOOT);
+
+ pushTunnelPayload((uint8_t)request.size(), request);
+ handleMAVLinkTelemetry(1000);
+
+ EXPECT_EQ(mspCommandCallCount, 1);
+ EXPECT_EQ(waitForSerialPortToFinishTransmittingCalls, 1);
+ EXPECT_EQ(mspRebootPostProcessCount, 1);
+ EXPECT_EQ(lastPostProcessPort, &testSerialPort);
+ EXPECT_EQ(collectTunnelPayload(parseTxMessages()), encodeMspV1Reply((uint8_t)MSP_REBOOT, MSP_RESULT_ACK));
+}
+
+TEST(MavlinkTelemetryTest, TunnelStalePartialFrameResetsBeforeNextRequest)
+{
+ initMavlinkTestState();
+
+ pushTunnelPayload(3, {'$', 'M', '<'});
+ handleMAVLinkTelemetry(1000);
+
+ EXPECT_EQ(mspCommandCallCount, 0);
+ EXPECT_TRUE(parseTxMessages().empty());
+
+ resetSerialBuffers();
+ fakeMillis = 2000;
+
+ const std::vector request = makeMspV1Request(testSimpleMspCommand);
+ pushTunnelPayload((uint8_t)request.size(), request);
+ handleMAVLinkTelemetry(1000);
+
+ EXPECT_EQ(mspCommandCallCount, 1);
+ EXPECT_EQ(collectTunnelPayload(parseTxMessages()), encodeMspV1Reply(testSimpleMspCommand, MSP_RESULT_ACK));
+}
+
+TEST(MavlinkTelemetryTest, TunnelLargeReplyFragmentsAcrossMultipleMessages)
+{
+ initMavlinkTestState();
+
+ const std::vector request = makeMspV1Request(testLargeReplyMspCommand);
+ pushTunnelPayload((uint8_t)request.size(), request);
+ handleMAVLinkTelemetry(1000);
+
+ const std::vector messages = parseTxMessages();
+ ASSERT_EQ(messages.size(), 3U);
+
+ std::vector expectedPayload(300);
+ for (size_t i = 0; i < expectedPayload.size(); i++) {
+ expectedPayload[i] = (uint8_t)i;
+ }
+
+ EXPECT_EQ(collectTunnelPayload(messages), encodeMspV1Reply(testLargeReplyMspCommand, MSP_RESULT_ACK, expectedPayload));
+}
+
TEST(MavlinkTelemetryTest, AttitudeUsesRadiansPerSecond)
{
initMavlinkTestState();
@@ -1101,6 +1313,7 @@ int32_t debug[DEBUG32_VALUE_COUNT];
uint32_t armingFlags;
uint32_t stateFlags;
+bool cliMode;
attitudeEulerAngles_t attitude;
gyro_t gyro;
@@ -1119,7 +1332,7 @@ timeUs_t micros(void)
uint32_t millis(void)
{
- return 0;
+ return fakeMillis;
}
serialPortConfig_t *findSerialPortConfig(serialPortFunction_e function)
@@ -1216,6 +1429,29 @@ bool telemetryDetermineEnabledState(portSharing_e portSharing)
return true;
}
+bool serialIsConnected(const serialPort_t *instance)
+{
+ UNUSED(instance);
+ return true;
+}
+
+bool isSerialTransmitBufferEmpty(const serialPort_t *instance)
+{
+ UNUSED(instance);
+ return true;
+}
+
+void waitForSerialPortToFinishTransmitting(serialPort_t *serialPort)
+{
+ waitForSerialPortToFinishTransmittingCalls++;
+ lastPostProcessPort = serialPort;
+}
+
+void cliEnter(serialPort_t *serialPort)
+{
+ UNUSED(serialPort);
+}
+
bool sensors(uint32_t mask)
{
return (testSensorsMask & mask) != 0;
@@ -1386,6 +1622,16 @@ bool navigationSetAltitudeTargetWithDatum(geoAltitudeDatumFlag_e datumFlag, int3
return altitudeTargetSetResult;
}
+navigationFSMStateFlags_t navGetCurrentStateFlags(void)
+{
+ return (navigationFSMStateFlags_t)0;
+}
+
+void updateHeadingHoldTarget(int16_t heading)
+{
+ UNUSED(heading);
+}
+
void setWaypoint(uint8_t wpNumber, const navWaypoint_t *wp)
{
UNUSED(wpNumber);
@@ -1445,6 +1691,41 @@ void mavlinkRxHandleMessage(const mavlink_rc_channels_override_t *msg)
mavlinkRxHandleCalls++;
}
+static void testMspRebootPostProcess(serialPort_t *serialPort)
+{
+ mspRebootPostProcessCount++;
+ lastPostProcessPort = serialPort;
+}
+
+mspResult_e mspFcProcessCommand(mspPacket_t *cmd, mspPacket_t *reply, mspPostProcessFnPtr *mspPostProcessFn)
+{
+ mspCommandCallCount++;
+ reply->cmd = cmd->cmd;
+ reply->flags = 0;
+ reply->result = 0;
+
+ switch (cmd->cmd) {
+ case MSP_SET_PASSTHROUGH:
+ mspPassthroughDispatchCount++;
+ if (mspPostProcessFn) {
+ *mspPostProcessFn = testMspRebootPostProcess;
+ }
+ return MSP_RESULT_ACK;
+ case MSP_REBOOT:
+ if (mspPostProcessFn) {
+ *mspPostProcessFn = testMspRebootPostProcess;
+ }
+ return MSP_RESULT_ACK;
+ case testLargeReplyMspCommand:
+ for (uint16_t i = 0; i < 300; i++) {
+ sbufWriteU8(&reply->buf, (uint8_t)i);
+ }
+ return MSP_RESULT_ACK;
+ default:
+ return MSP_RESULT_ACK;
+ }
+}
+
adsbVehicleValues_t* getVehicleForFill(void)
{
return NULL;
diff --git a/src/utils/mavlink_tests/ROUTING_TEST.md b/src/utils/mavlink_tests/ROUTING_TEST.md
deleted file mode 100644
index 7ed080083d4..00000000000
--- a/src/utils/mavlink_tests/ROUTING_TEST.md
+++ /dev/null
@@ -1,33 +0,0 @@
-# MAVLink Routing Compliance Test
-
-- fc_system_id: `1`
-- links: `['link_camera', 'link_companion', 'link_gimbal', 'link_radio']`
-- gcs_link: `link_radio`
-- components: `[('mav2_companion_computer', 1, 191, 'link_companion'), ('mav1_elrs_receiver', 1, 68, 'link_radio'), ('mav3_camera', 1, 100, 'link_camera'), ('mav4_gimbal', 1, 154, 'link_gimbal')]`
-
-## Rule References
-
-- broadcast_forward: `routing.md:25-27,48-49`
-- known_target_forward: `routing.md:49-50; MAVLink_routing.cpp:66-80`
-- unknown_target_blocked: `routing.md:26-27,53`
-- no_ingress_loop: `MAVLink_routing.cpp:197-209`
-- no_repack: `routing.md:29-31`
-
-## Results
-
-| Case | Source(link) | Target(sys,comp) | Expected Links | Observed Links | Routing | No Ingress Loop | Payload Intact | Pass |
-| --- | --- | --- | --- | --- | --- | --- | --- | --- |
-| `gcs_broadcast` | `gcs (link_radio)` | `(0,0)` | `['link_camera', 'link_companion', 'link_gimbal']` | `['link_camera', 'link_companion', 'link_gimbal']` | `True` | `True` | `True` | `True` |
-| `gcs_target_local_system_component_broadcast` | `gcs (link_radio)` | `(1,0)` | `['link_camera', 'link_companion', 'link_gimbal']` | `['link_camera', 'link_companion', 'link_gimbal']` | `True` | `True` | `True` | `True` |
-| `gcs_target_mav2_companion_computer` | `gcs (link_radio)` | `(1,191)` | `['link_companion']` | `['link_companion']` | `True` | `True` | `True` | `True` |
-| `gcs_target_mav1_elrs_receiver` | `gcs (link_radio)` | `(1,68)` | `[]` | `[]` | `True` | `True` | `True` | `True` |
-| `gcs_target_mav3_camera` | `gcs (link_radio)` | `(1,100)` | `['link_camera']` | `['link_camera']` | `True` | `True` | `True` | `True` |
-| `gcs_target_mav4_gimbal` | `gcs (link_radio)` | `(1,154)` | `['link_gimbal']` | `['link_gimbal']` | `True` | `True` | `True` | `True` |
-| `gcs_target_unknown_component` | `gcs (link_radio)` | `(1,199)` | `[]` | `[]` | `True` | `True` | `True` | `True` |
-| `gcs_target_unknown_system` | `gcs (link_radio)` | `(42,1)` | `[]` | `[]` | `True` | `True` | `True` | `True` |
-| `mav2_companion_computer_broadcast` | `mav2_companion_computer (link_companion)` | `(0,0)` | `['link_camera', 'link_gimbal', 'link_radio']` | `['link_camera', 'link_gimbal', 'link_radio']` | `True` | `True` | `True` | `True` |
-| `mav2_companion_computer_to_mav1_elrs_receiver` | `mav2_companion_computer (link_companion)` | `(1,68)` | `['link_radio']` | `['link_radio']` | `True` | `True` | `True` | `True` |
-| `mav2_companion_computer_to_gcs` | `mav2_companion_computer (link_companion)` | `(1,68)` | `['link_radio']` | `['link_radio']` | `True` | `True` | `True` | `True` |
-
-summary pass_count=11 fail_count=0 total=11
-
diff --git a/src/utils/mavlink_tests/mav_multi_benchmark.py b/src/utils/mavlink_tests/mav_multi_benchmark.py
deleted file mode 100644
index bb74da85779..00000000000
--- a/src/utils/mavlink_tests/mav_multi_benchmark.py
+++ /dev/null
@@ -1,880 +0,0 @@
-#!/usr/bin/env python3
-"""
-Usage:
- conda run -n drone python mydev/branch/mav_multi/mav_multi_benchmark.py
- conda run -n drone python mydev/branch/mav_multi/mav_multi_benchmark.py --config mydev/branch/mav_multi/test_config.yaml
-"""
-
-from __future__ import annotations
-
-import argparse
-import asyncio
-import socket
-import subprocess
-import time
-from datetime import datetime, timezone
-from pathlib import Path
-from typing import Any, Dict, List, Tuple
-
-import yaml
-from mavsdk import System
-from pymavlink import mavutil
-from serial.serialutil import SerialException
-
-try:
- from mspapi2.msp_api import MSPApi
- from mspapi2.lib import InavMSP
-except ModuleNotFoundError:
- repo_root_guess = Path(__file__).resolve().parents[3]
- mspapi2_repo = repo_root_guess.parent / "mspapi2"
- if mspapi2_repo.exists():
- import sys
-
- sys.path.insert(0, str(mspapi2_repo))
- from mspapi2.msp_api import MSPApi
- from mspapi2.lib import InavMSP
-
-
-DEFAULT_CONFIG_PATH = Path("mydev/branch/mav_multi/test_config.yaml")
-CHANNELS = [1500, 1500, 900, 1500] + [900] * 14
-MAV_CMD_REQUEST_MESSAGE = int(mavutil.mavlink.MAV_CMD_REQUEST_MESSAGE)
-MAV_CMD_SET_MESSAGE_INTERVAL = int(mavutil.mavlink.MAV_CMD_SET_MESSAGE_INTERVAL)
-MAVLINK_MSG_ID_HEARTBEAT = int(mavutil.mavlink.MAVLINK_MSG_ID_HEARTBEAT)
-MAV_AUTOPILOT_INVALID = int(mavutil.mavlink.MAV_AUTOPILOT_INVALID)
-MAV_TYPE_GCS = int(mavutil.mavlink.MAV_TYPE_GCS)
-
-
-def load_config(config_path: Path) -> Dict[str, Any]:
- return yaml.safe_load(config_path.read_text(encoding="utf-8"))
-
-
-def wait_for_tcp_port(host: str, port: int, timeout_s: float) -> None:
- deadline = time.monotonic() + timeout_s
- while time.monotonic() < deadline:
- try:
- with socket.create_connection((host, port), timeout=1.0):
- return
- except ConnectionRefusedError:
- time.sleep(0.2)
- continue
- except socket.timeout:
- time.sleep(0.2)
- continue
- raise TimeoutError(f"TCP port {host}:{port} did not become available within {timeout_s}s")
-
-
-def wait_for_tcp_port_cycle(host: str, port: int, timeout_s: float) -> None:
- deadline = time.monotonic() + timeout_s
- saw_closed = False
- while time.monotonic() < deadline:
- try:
- with socket.create_connection((host, port), timeout=1.0):
- if saw_closed:
- return
- except (ConnectionRefusedError, socket.timeout, OSError):
- saw_closed = True
- time.sleep(0.2)
-
- if saw_closed:
- raise TimeoutError(f"TCP port {host}:{port} did not return after reboot within {timeout_s}s")
-
- # If no close window was observed, treat it as already rebooted and just ensure the port is reachable.
- wait_for_tcp_port(host, port, timeout_s)
-
-
-def cli_read_until_prompt(cli_socket: socket.socket) -> str:
- data = b""
- while b"\n# " not in data:
- chunk = cli_socket.recv(65536)
- if not chunk:
- raise ConnectionError("CLI socket closed before prompt")
- data += chunk
- return data.decode("utf-8", errors="replace")
-
-
-def wait_for_cli_ready(host: str, port: int, timeout_s: float) -> None:
- deadline = time.monotonic() + timeout_s
- while time.monotonic() < deadline:
- try:
- with socket.create_connection((host, port), timeout=1.0) as cli_socket:
- cli_socket.settimeout(1.0)
- cli_socket.sendall(b"#\n")
- cli_read_until_prompt(cli_socket)
- return
- except (ConnectionRefusedError, ConnectionError, socket.timeout, OSError):
- time.sleep(0.2)
- raise TimeoutError(f"CLI prompt did not become available on {host}:{port} within {timeout_s}s")
-
-
-def run_cli_commands(host: str, port: int, commands: List[str], reboot_timeout_s: float) -> bool:
- sent_save = False
- with socket.create_connection((host, port), timeout=5.0) as cli_socket:
- cli_socket.settimeout(3.0)
- cli_socket.sendall(b"#\n")
- cli_read_until_prompt(cli_socket)
- for command in commands:
- cli_socket.sendall(command.encode("utf-8") + b"\n")
- if command == "save":
- sent_save = True
- break
- cli_read_until_prompt(cli_socket)
- if sent_save:
- # Save triggers reboot; do not send '#' again because that re-enters CLI mode.
- time.sleep(min(reboot_timeout_s, 1.0))
- return sent_save
-
-
-def build_serial_command(index: int, function_mask: int, baud: int) -> str:
- return f"serial {index} {function_mask} {baud} {baud} 0 {baud}"
-
-
-def build_cli_config_commands(config: Dict[str, Any], mavlink_port_count: int) -> List[str]:
- cli_cfg = config["cli"]
- rc_baud = int(cli_cfg["rc_baud"])
- telemetry_baud = int(cli_cfg["telemetry_baud"])
- uart2_mask = 320 # FUNCTION_RX_SERIAL + FUNCTION_TELEMETRY_MAVLINK
- uart3_mask = 256 if mavlink_port_count >= 2 else 0 # FUNCTION_TELEMETRY_MAVLINK
- uart4_mask = 256 if mavlink_port_count >= 3 else 0 # FUNCTION_TELEMETRY_MAVLINK
- uart5_mask = 256 if mavlink_port_count >= 4 else 0 # FUNCTION_TELEMETRY_MAVLINK
- commands = [
- "feature TELEMETRY",
- "set receiver_type = SERIAL",
- "set serialrx_provider = MAVLINK",
- build_serial_command(0, 1, 115200), # MSP on UART1, always.
- build_serial_command(1, uart2_mask, rc_baud),
- build_serial_command(2, uart3_mask, telemetry_baud),
- build_serial_command(3, uart4_mask, telemetry_baud),
- build_serial_command(4, uart5_mask, telemetry_baud),
- "set mavlink_version = 2",
- "set mavlink_port1_compid = 1",
- "set mavlink_port2_compid = 2",
- "set mavlink_port3_compid = 3",
- "set mavlink_port4_compid = 4",
- "set mavlink_port1_high_latency = OFF",
- "set mavlink_port2_high_latency = OFF",
- "set mavlink_port3_high_latency = OFF",
- "set mavlink_port4_high_latency = OFF",
- "save",
- ]
- return commands
-
-
-def apply_config_and_wait(config: Dict[str, Any], mavlink_port_count: int) -> None:
- ports = config["ports"]
- commands = build_cli_config_commands(config, mavlink_port_count)
- sent_save = run_cli_commands(
- "127.0.0.1",
- int(ports["msp"]),
- commands,
- reboot_timeout_s=float(config["tests"]["save_reboot_timeout_s"]),
- )
- if sent_save:
- wait_for_tcp_port_cycle("127.0.0.1", int(ports["msp"]), float(config["tests"]["save_reboot_timeout_s"]))
- wait_for_tcp_port("127.0.0.1", int(ports["msp"]), float(config["tests"]["port_ready_timeout_s"]))
- wait_for_tcp_port("127.0.0.1", int(ports["rc"]), float(config["tests"]["port_ready_timeout_s"]))
- if mavlink_port_count >= 2:
- wait_for_tcp_port("127.0.0.1", int(ports["telemetry"][0]), float(config["tests"]["port_ready_timeout_s"]))
- if mavlink_port_count >= 3:
- wait_for_tcp_port("127.0.0.1", int(ports["telemetry"][1]), float(config["tests"]["port_ready_timeout_s"]))
- if mavlink_port_count >= 4:
- wait_for_tcp_port("127.0.0.1", int(ports["telemetry"][2]), float(config["tests"]["port_ready_timeout_s"]))
-
-
-async def mavsdk_probe(address: str, timeout_s: float) -> Dict[str, Any]:
- drone = System()
- result: Dict[str, Any] = {
- "address": address,
- "connected": False,
- "flight_mode": None,
- }
- await drone.connect(system_address=address)
- async with asyncio.timeout(timeout_s):
- async for state in drone.core.connection_state():
- if state.is_connected:
- result["connected"] = True
- break
- async with asyncio.timeout(timeout_s):
- async for flight_mode in drone.telemetry.flight_mode():
- result["flight_mode"] = str(flight_mode)
- break
- return result
-
-
-def probe_mavsdk_sync(address: str, timeout_s: float) -> Dict[str, Any]:
- return asyncio.run(mavsdk_probe(address, timeout_s))
-
-
-def open_mavlink_tcp_connection(port: int, source_system: int, source_component: int, timeout_s: float) -> Any:
- deadline = time.monotonic() + timeout_s
- while True:
- try:
- return mavutil.mavlink_connection(
- f"tcp:127.0.0.1:{port}",
- source_system=source_system,
- source_component=source_component,
- autoreconnect=True,
- )
- except OSError:
- if time.monotonic() >= deadline:
- raise
- time.sleep(0.2)
-
-
-def is_fc_heartbeat(msg: Any) -> bool:
- return int(msg.autopilot) != MAV_AUTOPILOT_INVALID and int(msg.type) != MAV_TYPE_GCS
-
-
-def run_workload(
- config: Dict[str, Any],
- sitl_pid: int,
- telemetry_ports: List[int],
- rc_port: int,
- load_rates_hz: Dict[int, float],
- duration_s: float,
- rc_tx_hz_override: float | None = None,
-) -> Dict[str, Any]:
- print(
- f"run_workload_start duration_s={duration_s} telemetry_ports={telemetry_ports} rc_port={rc_port} "
- f"load_rates_hz={load_rates_hz}",
- flush=True,
- )
- tests_cfg = config["tests"]
- rc_tx_hz = float(tests_cfg["rc_tx_hz"]) if rc_tx_hz_override is None else float(rc_tx_hz_override)
- msp_poll_hz = float(tests_cfg["msp_poll_hz"])
- inav_status_hz = float(tests_cfg.get("inav_status_hz", 1.0))
- msp_request_timeout_s = float(tests_cfg["msp_request_timeout_s"])
- command_message_id = int(tests_cfg["stress_command_message_id"])
- rc_target_system = int(tests_cfg["rc_target_system"])
- rc_target_component = int(tests_cfg["rc_target_component"])
- heartbeat_expected_hz = float(tests_cfg["heartbeat_expected_hz"])
- stream_cfg = config["cli"]
- port_ready_timeout_s = float(tests_cfg["port_ready_timeout_s"])
- warmup_s = float(tests_cfg.get("warmup_s", 3.0))
- warmup_heartbeat_count = int(tests_cfg.get("warmup_heartbeat_count", 3))
- warmup_timeout_s = float(tests_cfg.get("warmup_timeout_s", 30.0))
-
- listeners: Dict[int, Any] = {}
- targets: Dict[int, Tuple[int, int]] = {}
- port_stats: Dict[int, Dict[str, Any]] = {}
- load_senders: Dict[int, Any] = {}
- load_sent: Dict[int, int] = {}
- load_next_send: Dict[int, float] = {}
- msp_success = 0
- msp_fail = 0
- rc_sent = 0
- fc_cpu_load_samples: List[float] = []
- fc_cycle_time_samples: List[float] = []
- fc_status_fail = 0
- fc_status_last_error = ""
-
- source_base = 170
- ports_to_open = set(telemetry_ports)
- ports_to_open.update(load_rates_hz.keys())
- ports_to_open.add(rc_port)
- for port in sorted(ports_to_open):
- wait_for_tcp_port("127.0.0.1", int(port), port_ready_timeout_s)
-
- for idx, port in enumerate(telemetry_ports):
- conn = open_mavlink_tcp_connection(
- port=port,
- source_system=source_base + idx,
- source_component=190,
- timeout_s=port_ready_timeout_s,
- )
- listeners[port] = conn
- targets[port] = (rc_target_system, rc_target_component)
- port_stats[port] = {
- "heartbeat_count": 0,
- "rc_count": 0,
- "command_ack_total": 0,
- "command_ack_ok": 0,
- "mav_msg_count": 0,
- "mav_seq_lost": 0,
- "last_seq_by_source": {},
- "seq_track_source": None,
- }
-
- for idx, port in enumerate(sorted(load_rates_hz.keys())):
- if port in listeners:
- sender = listeners[port]
- else:
- sender = open_mavlink_tcp_connection(
- port=port,
- source_system=210 + idx,
- source_component=191,
- timeout_s=port_ready_timeout_s,
- )
- load_senders[port] = sender
- load_sent[port] = 0
- load_next_send[port] = time.monotonic()
- if port not in targets:
- targets[port] = (rc_target_system, rc_target_component)
-
- if rc_port in listeners:
- rc_sender = listeners[rc_port]
- else:
- rc_sender = open_mavlink_tcp_connection(
- port=rc_port,
- source_system=239,
- source_component=191,
- timeout_s=port_ready_timeout_s,
- )
- if telemetry_ports:
- telemetry_target = targets[telemetry_ports[0]]
- rc_target_system, rc_target_component = telemetry_target
-
- rc_period_s = 1.0 / rc_tx_hz
- next_rc_send_t = time.monotonic()
- heartbeat_period_s = 1.0
- next_heartbeat_send_t = next_rc_send_t
-
- warmup_hb_seen: Dict[int, int] = {port: 0 for port in telemetry_ports}
- warmup_start_t = time.monotonic()
- warmup_deadline_t = warmup_start_t + warmup_timeout_s
-
- while True:
- now = time.monotonic()
-
- if now >= next_heartbeat_send_t:
- heartbeat_conns: Dict[int, Any] = {}
- for conn in listeners.values():
- heartbeat_conns[id(conn)] = conn
- for conn in load_senders.values():
- heartbeat_conns[id(conn)] = conn
- heartbeat_conns[id(rc_sender)] = rc_sender
- for conn in heartbeat_conns.values():
- conn.mav.heartbeat_send(
- mavutil.mavlink.MAV_TYPE_GCS,
- mavutil.mavlink.MAV_AUTOPILOT_INVALID,
- 0,
- 0,
- 0,
- )
- next_heartbeat_send_t += heartbeat_period_s
- if next_heartbeat_send_t < now:
- next_heartbeat_send_t = now + heartbeat_period_s
-
- if now >= next_rc_send_t:
- rc_target = targets.get(rc_port)
- if rc_target is not None:
- rc_target_system, rc_target_component = rc_target
- rc_sender.mav.rc_channels_override_send(rc_target_system, rc_target_component, *CHANNELS[:8])
- next_rc_send_t += rc_period_s
- if next_rc_send_t < now:
- next_rc_send_t = now + rc_period_s
-
- for port, conn in listeners.items():
- while True:
- msg = conn.recv_match(blocking=False)
- if msg is None:
- break
- msg_type = msg.get_type()
- if msg_type == "HEARTBEAT":
- src_system = int(msg.get_srcSystem())
- src_component = int(msg.get_srcComponent())
- if is_fc_heartbeat(msg):
- targets[port] = (src_system, src_component)
- warmup_hb_seen[port] += 1
-
- if telemetry_ports and all(count >= warmup_heartbeat_count for count in warmup_hb_seen.values()) and (now - warmup_start_t) >= warmup_s:
- break
- if (not telemetry_ports) and (now - warmup_start_t) >= warmup_s:
- break
- if now >= warmup_deadline_t:
- raise TimeoutError(
- f"Warmup failed: heartbeat_counts={warmup_hb_seen} required={warmup_heartbeat_count} timeout_s={warmup_timeout_s}"
- )
-
- time.sleep(0.001)
-
- for port, conn in listeners.items():
- target_system, target_component = targets[port]
- port_stats[port]["seq_track_source"] = (target_system, target_component)
- conn.mav.request_data_stream_send(
- target_system,
- target_component,
- int(mavutil.mavlink.MAV_DATA_STREAM_EXTENDED_STATUS),
- int(stream_cfg["ext_status_rate_hz"]),
- 1 if int(stream_cfg["ext_status_rate_hz"]) > 0 else 0,
- )
- conn.mav.request_data_stream_send(
- target_system,
- target_component,
- int(mavutil.mavlink.MAV_DATA_STREAM_RC_CHANNELS),
- int(stream_cfg["rc_chan_rate_hz"]),
- 1 if int(stream_cfg["rc_chan_rate_hz"]) > 0 else 0,
- )
- conn.mav.request_data_stream_send(
- target_system,
- target_component,
- int(mavutil.mavlink.MAV_DATA_STREAM_POSITION),
- int(stream_cfg["pos_rate_hz"]),
- 1 if int(stream_cfg["pos_rate_hz"]) > 0 else 0,
- )
- conn.mav.request_data_stream_send(
- target_system,
- target_component,
- int(mavutil.mavlink.MAV_DATA_STREAM_EXTRA1),
- int(stream_cfg["extra1_rate_hz"]),
- 1 if int(stream_cfg["extra1_rate_hz"]) > 0 else 0,
- )
- conn.mav.request_data_stream_send(
- target_system,
- target_component,
- int(mavutil.mavlink.MAV_DATA_STREAM_EXTRA2),
- int(stream_cfg["extra2_rate_hz"]),
- 1 if int(stream_cfg["extra2_rate_hz"]) > 0 else 0,
- )
- conn.mav.request_data_stream_send(
- target_system,
- target_component,
- int(mavutil.mavlink.MAV_DATA_STREAM_EXTRA3),
- int(stream_cfg["extra3_rate_hz"]),
- 1 if int(stream_cfg["extra3_rate_hz"]) > 0 else 0,
- )
- conn.mav.command_long_send(
- target_system,
- target_component,
- MAV_CMD_SET_MESSAGE_INTERVAL,
- 0,
- float(MAVLINK_MSG_ID_HEARTBEAT),
- float(int(1_000_000.0 / heartbeat_expected_hz)),
- 0,
- 0,
- 0,
- 0,
- 0,
- )
- time.sleep(0.1)
-
- for stats in port_stats.values():
- stats["heartbeat_count"] = 0
- stats["rc_count"] = 0
- stats["command_ack_total"] = 0
- stats["command_ack_ok"] = 0
- stats["mav_msg_count"] = 0
- stats["mav_seq_lost"] = 0
- stats["last_seq_by_source"] = {}
-
- rc_sent = 0
- measurement_start_t = time.monotonic()
- next_rc_send_t = measurement_start_t
- next_heartbeat_send_t = measurement_start_t
- for port in load_next_send:
- load_next_send[port] = measurement_start_t
- next_resource_sample_t = measurement_start_t + (1.0 / inav_status_hz)
- next_msp_poll_t = measurement_start_t + (1.0 / msp_poll_hz)
- workload_end_t = measurement_start_t + duration_s
-
- with MSPApi(tcp_endpoint=f"127.0.0.1:{int(config['ports']['msp'])}") as msp_api:
- msp_api._serial._max_retries = 1
- msp_api._serial._reconnect_delay = 0.05
- while time.monotonic() < workload_end_t:
- now = time.monotonic()
-
- if now >= next_heartbeat_send_t:
- heartbeat_conns: Dict[int, Any] = {}
- for conn in listeners.values():
- heartbeat_conns[id(conn)] = conn
- for conn in load_senders.values():
- heartbeat_conns[id(conn)] = conn
- heartbeat_conns[id(rc_sender)] = rc_sender
- for conn in heartbeat_conns.values():
- conn.mav.heartbeat_send(
- mavutil.mavlink.MAV_TYPE_GCS,
- mavutil.mavlink.MAV_AUTOPILOT_INVALID,
- 0,
- 0,
- 0,
- )
- next_heartbeat_send_t += heartbeat_period_s
- if next_heartbeat_send_t < now:
- next_heartbeat_send_t = now + heartbeat_period_s
-
- if now >= next_rc_send_t:
- rc_target = targets.get(rc_port)
- if rc_target is not None:
- rc_target_system, rc_target_component = rc_target
- rc_sender.mav.rc_channels_override_send(rc_target_system, rc_target_component, *CHANNELS[:8])
- rc_sent += 1
- next_rc_send_t += rc_period_s
- if next_rc_send_t < now:
- next_rc_send_t = now + rc_period_s
-
- for port, rate_hz in load_rates_hz.items():
- next_send_t = load_next_send[port]
- if now >= next_send_t:
- target_system, target_component = targets[port]
- load_senders[port].mav.command_long_send(
- target_system,
- target_component,
- MAV_CMD_REQUEST_MESSAGE,
- 0,
- float(command_message_id),
- 0,
- 0,
- 0,
- 0,
- 0,
- 0,
- )
- load_sent[port] += 1
- next_send_t += 1.0 / rate_hz
- if next_send_t < now:
- next_send_t = now + (1.0 / rate_hz)
- load_next_send[port] = next_send_t
-
- for port, conn in listeners.items():
- while True:
- msg = conn.recv_match(blocking=False)
- if msg is None:
- break
- msg_type = msg.get_type()
- stats = port_stats[port]
- seq = None
- if hasattr(msg, "get_seq"):
- try:
- seq = int(msg.get_seq())
- except (TypeError, ValueError):
- seq = None
- if seq is None:
- header = getattr(msg, "_header", None)
- if header is not None and hasattr(header, "seq"):
- seq = int(header.seq)
- if seq is not None:
- src_key = (int(msg.get_srcSystem()), int(msg.get_srcComponent()))
- if src_key == stats["seq_track_source"]:
- last_seq = stats["last_seq_by_source"].get(src_key)
- if last_seq is not None:
- seq_delta = (seq - int(last_seq)) & 0xFF
- if seq_delta > 0:
- stats["mav_seq_lost"] += max(seq_delta - 1, 0)
- stats["last_seq_by_source"][src_key] = seq
- stats["mav_msg_count"] += 1
-
- if msg_type == "HEARTBEAT":
- src_system = int(msg.get_srcSystem())
- src_component = int(msg.get_srcComponent())
- if is_fc_heartbeat(msg):
- targets[port] = (src_system, src_component)
- stats["heartbeat_count"] += 1
- elif msg_type == "RC_CHANNELS":
- stats["rc_count"] += 1
- elif msg_type == "COMMAND_ACK":
- if int(msg.command) == MAV_CMD_REQUEST_MESSAGE:
- stats["command_ack_total"] += 1
- if int(msg.result) == int(mavutil.mavlink.MAV_RESULT_ACCEPTED):
- stats["command_ack_ok"] += 1
-
- if now >= next_msp_poll_t:
- try:
- msp_api._request_raw(InavMSP.MSP_RC, timeout=msp_request_timeout_s)
- msp_success += 1
- except (SerialException, RuntimeError, TimeoutError, ConnectionRefusedError, OSError):
- msp_fail += 1
- next_msp_poll_t += 1.0 / msp_poll_hz
-
- if now >= next_resource_sample_t:
- try:
- status = msp_api.get_inav_status()
- fc_cpu_load_samples.append(float(status["cpuLoad"]))
- fc_cycle_time_samples.append(float(status["cycleTime"]))
- except (SerialException, RuntimeError, TimeoutError, ConnectionRefusedError, OSError, KeyError, ValueError) as exc:
- fc_status_fail += 1
- fc_status_last_error = str(exc)
- next_resource_sample_t += 1.0 / inav_status_hz
-
- time.sleep(0.001)
-
- all_connections: Dict[int, Any] = {}
- for conn in listeners.values():
- all_connections[id(conn)] = conn
- for conn in load_senders.values():
- all_connections[id(conn)] = conn
- all_connections[id(rc_sender)] = rc_sender
- for conn in all_connections.values():
- conn.close()
-
- if not fc_cpu_load_samples:
- raise RuntimeError(f"No MSP2_INAV_STATUS samples collected; last_error={fc_status_last_error} fail_count={fc_status_fail}")
-
- summarized_ports: Dict[int, Dict[str, Any]] = {}
- for port in telemetry_ports:
- stats = port_stats[port]
- mav_total = int(stats["mav_msg_count"])
- mav_lost = int(stats["mav_seq_lost"])
- mav_expected = mav_total + mav_lost
- sent = load_sent.get(port, 0)
- ack_total = stats["command_ack_total"]
- ack_ok = stats["command_ack_ok"]
- ack_missing = max(sent - ack_total, 0)
- command_failed_total = max(sent - ack_ok, 0)
- summarized_ports[port] = {
- "heartbeat_count": stats["heartbeat_count"],
- "rc_count": stats["rc_count"],
- "mav_msg_count": mav_total,
- "mav_seq_lost": mav_lost,
- "mav_seq_loss_rate": (mav_lost / mav_expected) if mav_expected > 0 else 0.0,
- "command_sent": sent,
- "command_ack_total": ack_total,
- "command_ack_ok": ack_ok,
- "command_failed_total": command_failed_total,
- "command_ack_missing": ack_missing,
- "command_ack_failure_rate": (command_failed_total / sent) if sent > 0 else 0.0,
- }
-
- result = {
- "duration_s": duration_s,
- "ports": summarized_ports,
- "msp_success": msp_success,
- "msp_fail": msp_fail,
- "rc_sent": rc_sent,
- "rc_sent_hz": (rc_sent / max(duration_s, 1e-6)),
- "msp_failure_rate": (msp_fail / max(msp_success + msp_fail, 1)),
- "fc_cpu_load_avg_pct": (sum(fc_cpu_load_samples) / len(fc_cpu_load_samples)) if fc_cpu_load_samples else 0.0,
- "fc_cpu_load_max_pct": max(fc_cpu_load_samples) if fc_cpu_load_samples else 0.0,
- "fc_cycle_time_avg_us": (sum(fc_cycle_time_samples) / len(fc_cycle_time_samples)) if fc_cycle_time_samples else 0.0,
- "fc_cycle_time_max_us": max(fc_cycle_time_samples) if fc_cycle_time_samples else 0.0,
- "fc_status_samples": len(fc_cpu_load_samples),
- }
- print(
- f"run_workload_done duration_s={duration_s} fc_cpu_load_avg_pct={result['fc_cpu_load_avg_pct']:.2f} "
- f"msp_fail_rate={result['msp_failure_rate']:.4f}",
- flush=True,
- )
- return result
-
-
-def format_port_table(port_result: Dict[int, Dict[str, Any]]) -> str:
- if not port_result:
- return "_No MAVLink telemetry ports active in this scenario._"
-
- lines = [
- "| Port | MAV Msg Count | MAV Seq Lost | MAV Seq Loss % | HB Count | RC_CHANNELS Count | Cmd Sent | Cmd Ack OK | Cmd Failed Total | Cmd Missing Ack |",
- "| --- | ---: | ---: | ---: | ---: | ---: | ---: | ---: | ---: | ---: |",
- ]
- for port in sorted(port_result.keys()):
- data = port_result[port]
- lines.append(
- "| "
- f"{port} | {data['mav_msg_count']} | {data['mav_seq_lost']} | {(data['mav_seq_loss_rate'] * 100.0):.2f}% | "
- f"{data['heartbeat_count']} | {data['rc_count']} | {data['command_sent']} | "
- f"{data['command_ack_ok']} | {data['command_failed_total']} | {data['command_ack_missing']} |"
- )
- return "\n".join(lines)
-
-
-def summarize_command_failures(port_result: Dict[int, Dict[str, Any]]) -> Dict[str, float]:
- sent_total = sum(int(item["command_sent"]) for item in port_result.values())
- failed_total = sum(int(item["command_failed_total"]) for item in port_result.values())
- missing_ack_total = sum(int(item["command_ack_missing"]) for item in port_result.values())
- mav_seq_lost_total = sum(int(item["mav_seq_lost"]) for item in port_result.values())
- mav_msg_total = sum(int(item["mav_msg_count"]) for item in port_result.values())
- mav_seq_loss_pct = (mav_seq_lost_total / max(mav_seq_lost_total + mav_msg_total, 1)) * 100.0
- return {
- "sent_total": float(sent_total),
- "failed_total": float(failed_total),
- "failed_pct": (failed_total / max(sent_total, 1)) * 100.0,
- "missing_ack_total": float(missing_ack_total),
- "mav_seq_loss_pct": mav_seq_loss_pct,
- }
-
-
-def write_testing_report(config: Dict[str, Any], report: Dict[str, Any]) -> None:
- out_path = Path(config["output"]["testing_md"])
- timestamp = datetime.now(timezone.utc).isoformat()
- lines: List[str] = []
- lines.append("# MAVLink Multiport Testing")
- lines.append("")
- lines.append(f"- Generated: `{timestamp}`")
- lines.append(f"- Conda env: `drone`")
- lines.append(f"- SITL binary: `{config['sitl']['binary']}`")
- lines.append(f"- EEPROM: `{config['sitl']['eeprom_path']}`")
- lines.append("- MSP kept on UART1 by design (`serial 0 ... functionMask=1`).")
- lines.append("- CLI under test sets `receiver_type=SERIAL` and `serialrx_provider=MAVLINK`.")
- lines.append("- Stream rates are configured at runtime via MAVLink `REQUEST_DATA_STREAM` and `MAV_CMD_SET_MESSAGE_INTERVAL`.")
- lines.append("- `RC_CHANNELS` metrics below are MAVLink telemetry stream metrics, not RX input ownership.")
- lines.append("")
- lines.append("## MAVSDK Probe")
- lines.append("")
- lines.append("| Address | Connected | Flight Mode |")
- lines.append("| --- | --- | --- |")
- if report["mavsdk_probes"]:
- for probe in report["mavsdk_probes"]:
- lines.append(f"| {probe['address']} | {probe['connected']} | {probe['flight_mode']} |")
- else:
- lines.append("| _skipped_ | _skipped_ | _skipped_ |")
- lines.append("")
- lines.append("## Port Count Baseline (1 RC, then +Telemetry ports)")
- lines.append("")
- for label, result in report["baseline"].items():
- cmd_summary = summarize_command_failures(result["ports"])
- lines.append(f"### {label}")
- lines.append("")
- lines.append(
- f"- Duration: `{result['duration_s']}s` | FC cpuLoad avg/max: `{result['fc_cpu_load_avg_pct']:.2f}% / {result['fc_cpu_load_max_pct']:.2f}%` | "
- f"FC cycleTime avg/max: `{result['fc_cycle_time_avg_us']:.1f} / {result['fc_cycle_time_max_us']:.1f}` us | "
- f"Status samples: `{result['fc_status_samples']}`"
- )
- lines.append(
- f"- MSP success/fail: `{result['msp_success']}/{result['msp_fail']}` | MSP failure rate: `{(result['msp_failure_rate'] * 100.0):.2f}%`"
- )
- lines.append(
- f"- Commands sent/failed: `{int(cmd_summary['sent_total'])}/{int(cmd_summary['failed_total'])}` (`{cmd_summary['failed_pct']:.2f}%`) | "
- f"Missing ACK: `{int(cmd_summary['missing_ack_total'])}` | MAVLink seq loss: `{cmd_summary['mav_seq_loss_pct']:.2f}%`"
- )
- lines.append(f"- RC override send rate: `{result['rc_sent_hz']:.2f} Hz` (`{result['rc_sent']}` packets)")
- lines.append("")
- lines.append(format_port_table(result["ports"]))
- lines.append("")
- lines.append("## Stress Test: Progressive Overload On One MAVLink Port")
- lines.append("")
- for item in report["single_port_stress"]:
- rate = item["rate_hz"]
- result = item["result"]
- cmd_summary = summarize_command_failures(result["ports"])
- lines.append(f"### Load Rate `{rate} req/s` on telemetry port")
- lines.append("")
- lines.append(
- f"- Duration: `{result['duration_s']}s` | FC cpuLoad avg/max: `{result['fc_cpu_load_avg_pct']:.2f}% / {result['fc_cpu_load_max_pct']:.2f}%` | "
- f"FC cycleTime avg/max: `{result['fc_cycle_time_avg_us']:.1f} / {result['fc_cycle_time_max_us']:.1f}` us | "
- f"Status samples: `{result['fc_status_samples']}`"
- )
- lines.append(
- f"- MSP success/fail: `{result['msp_success']}/{result['msp_fail']}` | MSP failure rate: `{(result['msp_failure_rate'] * 100.0):.2f}%`"
- )
- lines.append(
- f"- Commands sent/failed: `{int(cmd_summary['sent_total'])}/{int(cmd_summary['failed_total'])}` (`{cmd_summary['failed_pct']:.2f}%`) | "
- f"Missing ACK: `{int(cmd_summary['missing_ack_total'])}` | MAVLink seq loss: `{cmd_summary['mav_seq_loss_pct']:.2f}%`"
- )
- lines.append(f"- RC override send rate: `{result['rc_sent_hz']:.2f} Hz` (`{result['rc_sent']}` packets)")
- lines.append("")
- lines.append(format_port_table(result["ports"]))
- lines.append("")
- max_result = report["all_ports_max"]
- cmd_summary = summarize_command_failures(max_result["ports"])
- max_ports = len(max_result["ports"])
- lines.append(f"## Stress Test: All {max_ports} MAVLink Ports At Max Load")
- lines.append("")
- lines.append(
- f"- Duration: `{max_result['duration_s']}s` | FC cpuLoad avg/max: `{max_result['fc_cpu_load_avg_pct']:.2f}% / {max_result['fc_cpu_load_max_pct']:.2f}%` | "
- f"FC cycleTime avg/max: `{max_result['fc_cycle_time_avg_us']:.1f} / {max_result['fc_cycle_time_max_us']:.1f}` us | "
- f"Status samples: `{max_result['fc_status_samples']}`"
- )
- lines.append(
- f"- MSP success/fail: `{max_result['msp_success']}/{max_result['msp_fail']}` | MSP failure rate: `{(max_result['msp_failure_rate'] * 100.0):.2f}%`"
- )
- lines.append(
- f"- Commands sent/failed: `{int(cmd_summary['sent_total'])}/{int(cmd_summary['failed_total'])}` (`{cmd_summary['failed_pct']:.2f}%`) | "
- f"Missing ACK: `{int(cmd_summary['missing_ack_total'])}` | MAVLink seq loss: `{cmd_summary['mav_seq_loss_pct']:.2f}%`"
- )
- lines.append(f"- RC override send rate: `{max_result['rc_sent_hz']:.2f} Hz` (`{max_result['rc_sent']}` packets)")
- lines.append("")
- lines.append(format_port_table(max_result["ports"]))
- lines.append("")
- out_path.write_text("\n".join(lines) + "\n", encoding="utf-8")
-
-
-if __name__ == "__main__":
- parser = argparse.ArgumentParser(description="Run MAVLink multiport RC/telemetry/stress benchmark and write TESTING.md")
- parser.add_argument("--config", default=str(DEFAULT_CONFIG_PATH), help="YAML configuration path")
- args = parser.parse_args()
-
- config_path = Path(args.config)
- config = load_config(config_path)
-
- sitl_bin = Path(config["sitl"]["binary"])
- sitl_workdir = Path(config["sitl"]["workdir"])
- sitl_eeprom = str(config["sitl"]["eeprom_path"])
- sitl_log = Path(config["sitl"]["runtime_log"])
- sitl_log.parent.mkdir(parents=True, exist_ok=True)
- log_handle = sitl_log.open("w", encoding="utf-8")
- sitl_proc = subprocess.Popen(
- [str(sitl_bin), f"--path={sitl_eeprom}"],
- cwd=str(sitl_workdir),
- stdout=log_handle,
- stderr=subprocess.STDOUT,
- text=True,
- )
-
- report: Dict[str, Any] = {
- "mavsdk_probes": [],
- "baseline": {},
- "single_port_stress": [],
- "all_ports_max": {},
- }
-
- try:
- wait_for_tcp_port("127.0.0.1", int(config["ports"]["msp"]), float(config["tests"]["port_ready_timeout_s"]))
-
- configured_port_count = 1 + len(config["ports"]["telemetry"])
- print(f"single_config_start count={configured_port_count}", flush=True)
- apply_config_and_wait(config, configured_port_count)
- print(f"single_config_done count={configured_port_count}", flush=True)
-
- baseline_scenarios: List[Tuple[str, List[int]]] = []
- rc_port = int(config["ports"]["rc"])
- telemetry_ports = [int(port) for port in config["ports"]["telemetry"]]
- for count in range(1, configured_port_count + 1):
- baseline_scenarios.append((f"{count} MAVLink port(s)", [rc_port] + telemetry_ports[: max(0, count - 1)]))
- for label, active_telemetry_ports in baseline_scenarios:
- print(f"baseline_run_start label={label} ports={active_telemetry_ports}", flush=True)
- result = run_workload(
- config=config,
- sitl_pid=sitl_proc.pid,
- telemetry_ports=active_telemetry_ports,
- rc_port=int(config["ports"]["rc"]),
- load_rates_hz={},
- duration_s=float(config["tests"]["baseline_duration_s"]),
- )
- report["baseline"][label] = result
- print(f"baseline_run_done label={label}", flush=True)
-
- if bool(config["tests"].get("run_mavsdk_probe", True)):
- print("mavsdk_probe_start", flush=True)
- mavsdk_probe_ports = [int(config["ports"]["rc"])] + [int(p) for p in config["ports"]["telemetry"]]
- for port in mavsdk_probe_ports:
- probe = probe_mavsdk_sync(f"tcp://127.0.0.1:{port}", float(config["tests"]["mavsdk_probe_timeout_s"]))
- report["mavsdk_probes"].append(probe)
- print("mavsdk_probe_done", flush=True)
- else:
- print("mavsdk_probe_skipped", flush=True)
-
- stress_port = int(config["ports"]["telemetry"][0])
- active_telemetry_ports = [int(config["ports"]["rc"])] + [int(port) for port in config["ports"]["telemetry"]]
- for rate in config["tests"]["progressive_rates_hz"]:
- print(f"single_port_stress_start rate={rate}", flush=True)
- result = run_workload(
- config=config,
- sitl_pid=sitl_proc.pid,
- telemetry_ports=active_telemetry_ports,
- rc_port=int(config["ports"]["rc"]),
- load_rates_hz={stress_port: float(rate)},
- duration_s=float(config["tests"]["stress_duration_s"]),
- )
- report["single_port_stress"].append({"rate_hz": rate, "result": result})
-
- print("all_ports_max_start", flush=True)
- max_rate = float(config["tests"]["max_rate_hz"])
- max_loads = {port: max_rate for port in active_telemetry_ports}
- result = run_workload(
- config=config,
- sitl_pid=sitl_proc.pid,
- telemetry_ports=active_telemetry_ports,
- rc_port=int(config["ports"]["rc"]),
- load_rates_hz=max_loads,
- duration_s=float(config["tests"]["all_ports_max_duration_s"]),
- )
- report["all_ports_max"] = result
- print("all_ports_max_done", flush=True)
-
- write_testing_report(config, report)
- print(f"report_written={config['output']['testing_md']}")
- finally:
- sitl_proc.terminate()
- try:
- sitl_proc.wait(timeout=5.0)
- except subprocess.TimeoutExpired:
- sitl_proc.kill()
- sitl_proc.wait(timeout=5.0)
- log_handle.close()
diff --git a/src/utils/mavlink_tests/mav_multi_sweep.py b/src/utils/mavlink_tests/mav_multi_sweep.py
deleted file mode 100644
index bb7a38b741e..00000000000
--- a/src/utils/mavlink_tests/mav_multi_sweep.py
+++ /dev/null
@@ -1,164 +0,0 @@
-#!/usr/bin/env python3
-"""
-Usage:
- conda run -n drone python src/utils/mavlink_tests/mav_multi_sweep.py
- conda run -n drone python src/utils/mavlink_tests/mav_multi_sweep.py --config src/utils/mavlink_tests/test_config_multiport4_sweep_rc460800_tele115200.yaml
-"""
-
-from __future__ import annotations
-
-import argparse
-import importlib.util
-import subprocess
-from datetime import datetime, timezone
-from pathlib import Path
-from typing import Any, Dict, List, Tuple
-
-import yaml
-
-
-TESTS_DIR = Path(__file__).resolve().parent
-DEFAULT_CONFIG_PATH = TESTS_DIR / "test_config_multiport4_sweep_rc460800_tele115200.yaml"
-BENCHMARK_MODULE_PATH = TESTS_DIR / "mav_multi_benchmark.py"
-
-spec = importlib.util.spec_from_file_location("mav_multi_benchmark", BENCHMARK_MODULE_PATH)
-benchmark = importlib.util.module_from_spec(spec)
-assert spec is not None
-assert spec.loader is not None
-spec.loader.exec_module(benchmark)
-
-
-parser = argparse.ArgumentParser(description="Run MAVLink total-load sweep table for 1..4 ports and [50,100,200,max] req/s total")
-parser.add_argument("--config", default=str(DEFAULT_CONFIG_PATH), help="YAML configuration path")
-args = parser.parse_args()
-
-config_path = Path(args.config)
-config: Dict[str, Any] = yaml.safe_load(config_path.read_text(encoding="utf-8"))
-
-sitl_bin = Path(config["sitl"]["binary"])
-sitl_workdir = Path(config["sitl"]["workdir"])
-sitl_eeprom = str(config["sitl"]["eeprom_path"])
-sitl_log = Path(config["sitl"]["runtime_log"])
-sitl_log.parent.mkdir(parents=True, exist_ok=True)
-
-rate_labels: List[Tuple[str, float]] = [
- ("50", 50.0),
- ("100", 100.0),
- ("200", 200.0),
- ("max", float(config["tests"]["max_rate_hz"])),
-]
-
-results: Dict[str, Dict[int, Dict[str, Any]]] = {}
-
-rc_port = int(config["ports"]["rc"])
-telemetry_ports = [int(port) for port in config["ports"]["telemetry"]]
-sweep_duration_s = float(config["tests"]["sweep_duration_s"])
-
-rate_cache: Dict[float, Dict[int, Dict[str, Any]]] = {}
-
-for label, total_rate_hz in rate_labels:
- if total_rate_hz not in rate_cache:
- rate_cache[total_rate_hz] = {}
- for port_count in range(1, 5):
- scenario_log = sitl_log.with_name(f"{sitl_log.stem}_{label}_{port_count}{sitl_log.suffix}")
- log_handle = scenario_log.open("w", encoding="utf-8")
- sitl_proc = subprocess.Popen(
- [str(sitl_bin), f"--path={sitl_eeprom}"],
- cwd=str(sitl_workdir),
- stdout=log_handle,
- stderr=subprocess.STDOUT,
- text=True,
- )
- try:
- benchmark.wait_for_tcp_port("127.0.0.1", int(config["ports"]["msp"]), float(config["tests"]["port_ready_timeout_s"]))
- benchmark.apply_config_and_wait(config, 4)
- active_ports = [rc_port] + telemetry_ports[: max(0, port_count - 1)]
- per_port_rate_hz = total_rate_hz / float(port_count)
- load_rates_hz = {port: per_port_rate_hz for port in active_ports}
- print(
- f"sweep_run_start label={label} total_rate={total_rate_hz} per_port_rate={per_port_rate_hz} ports={port_count}",
- flush=True,
- )
- result = benchmark.run_workload(
- config=config,
- sitl_pid=sitl_proc.pid,
- telemetry_ports=active_ports,
- rc_port=rc_port,
- load_rates_hz=load_rates_hz,
- duration_s=sweep_duration_s,
- )
- rate_cache[total_rate_hz][port_count] = result
- print(
- f"sweep_run_done label={label} total_rate={total_rate_hz} per_port_rate={per_port_rate_hz} ports={port_count}",
- flush=True,
- )
- finally:
- sitl_proc.terminate()
- try:
- sitl_proc.wait(timeout=5.0)
- except subprocess.TimeoutExpired:
- sitl_proc.kill()
- sitl_proc.wait(timeout=5.0)
- log_handle.close()
- scenario_log.unlink(missing_ok=True)
- results[label] = rate_cache[total_rate_hz]
-
-output_path = Path(config["output"]["testing_md"])
-lines: List[str] = [
- "# MAVLink Port Load Sweep",
- "",
- f"- Generated: `{datetime.now(timezone.utc).isoformat()}`",
- f"- SITL binary: `{config['sitl']['binary']}`",
- f"- EEPROM: `{config['sitl']['eeprom_path']}`",
- "- UART1 MSP only.",
- "- UART2 is MAVLink RC (460800), RC override target is 100 Hz.",
- "- Additional MAVLink telemetry ports are 115200 baud.",
- "- Total command rate is held constant per load label and split evenly across active MAVLink ports.",
- "",
- "## Comparison Table",
- "",
- "| Load Label | Total Msg/s | Active MAVLink ports | Msg/s per active port | FC cpuLoad avg/max | FC cycleTime avg/max (us) | MAV seq loss max | Cmd failed total | Cmd failed % | MSP fail % |",
- "| --- | ---: | ---: | ---: | --- | --- | ---: | ---: | ---: | ---: |",
-]
-
-for label, total_rate_hz in rate_labels:
- rate_results = results[label]
- for port_count in range(1, 5):
- result = rate_results[port_count]
- per_port = list(result["ports"].values())
- mav_seq_loss_max_pct = max(item["mav_seq_loss_rate"] * 100.0 for item in per_port)
- cmd_sent_total = sum(int(item["command_sent"]) for item in per_port)
- cmd_failed_total = sum(int(item["command_failed_total"]) for item in per_port)
- cmd_failed_pct = (cmd_failed_total / max(cmd_sent_total, 1)) * 100.0
- per_port_rate_hz = total_rate_hz / float(port_count)
- lines.append(
- f"| {label} | {total_rate_hz:.1f} | {port_count} | {per_port_rate_hz:.2f} | "
- f"{result['fc_cpu_load_avg_pct']:.2f}% / {result['fc_cpu_load_max_pct']:.2f}% | "
- f"{result['fc_cycle_time_avg_us']:.1f} / {result['fc_cycle_time_max_us']:.1f} | "
- f"{mav_seq_loss_max_pct:.2f}% | {cmd_failed_total} | {cmd_failed_pct:.2f}% | {(result['msp_failure_rate'] * 100.0):.2f}% |"
- )
-
-lines.append("")
-lines.append("## Raw Scenario Details")
-lines.append("")
-for label, total_rate_hz in rate_labels:
- lines.append(f"### {label} ({total_rate_hz:.1f} total msg/s)")
- lines.append("")
- for port_count in range(1, 5):
- result = results[label][port_count]
- per_port_rate_hz = total_rate_hz / float(port_count)
- lines.append(f"#### {port_count} active MAVLink port(s)")
- lines.append("")
- lines.append(f"- Total command rate: `{total_rate_hz:.1f} msg/s`")
- lines.append(f"- Per-port command rate: `{per_port_rate_hz:.2f} msg/s`")
- lines.append(
- f"- FC cpuLoad avg/max: `{result['fc_cpu_load_avg_pct']:.2f}% / {result['fc_cpu_load_max_pct']:.2f}%` | "
- f"FC cycleTime avg/max: `{result['fc_cycle_time_avg_us']:.1f} / {result['fc_cycle_time_max_us']:.1f}` us | "
- f"MSP fail rate: `{(result['msp_failure_rate'] * 100.0):.2f}%`"
- )
- lines.append("")
- lines.append(benchmark.format_port_table(result["ports"]))
- lines.append("")
-
-output_path.write_text("\n".join(lines) + "\n", encoding="utf-8")
-print(f"report_written={output_path}", flush=True)
diff --git a/src/utils/mavlink_tests/mavlink_routing_compliance_test.py b/src/utils/mavlink_tests/mavlink_routing_compliance_test.py
deleted file mode 100644
index 0ea996ec1b5..00000000000
--- a/src/utils/mavlink_tests/mavlink_routing_compliance_test.py
+++ /dev/null
@@ -1,499 +0,0 @@
-#!/usr/bin/env python3
-"""
-Usage:
- conda run -n drone python src/utils/mavlink_tests/mavlink_routing_compliance_test.py --config src/utils/mavlink_tests/routing_test_config.yaml
-"""
-
-from __future__ import annotations
-
-import argparse
-import math
-import time
-from pathlib import Path
-from typing import Any, Dict, List
-
-import yaml
-from pymavlink import mavutil
-
-
-MAV_AUTOPILOT_INVALID = int(mavutil.mavlink.MAV_AUTOPILOT_INVALID)
-MAV_MODE_FLAG_CUSTOM_MODE_ENABLED = int(mavutil.mavlink.MAV_MODE_FLAG_CUSTOM_MODE_ENABLED)
-MAV_STATE_ACTIVE = int(mavutil.mavlink.MAV_STATE_ACTIVE)
-MAV_TYPE_GCS = int(mavutil.mavlink.MAV_TYPE_GCS)
-
-ROUTING_RULE_REFERENCES = {
- "broadcast_forward": "routing.md:25-27,48-49",
- "known_target_forward": "routing.md:49-50; MAVLink_routing.cpp:66-80",
- "unknown_target_blocked": "routing.md:26-27,53",
- "no_ingress_loop": "MAVLink_routing.cpp:197-209",
- "no_repack": "routing.md:29-31",
-}
-
-
-def load_config(config_path: Path) -> Dict[str, Any]:
- return yaml.safe_load(config_path.read_text(encoding="utf-8"))
-
-
-def open_mavlink_connection(endpoint: str, source_system: int, source_component: int, timeout_s: float) -> Any:
- deadline = time.monotonic() + timeout_s
- while True:
- try:
- return mavutil.mavlink_connection(
- endpoint,
- source_system=source_system,
- source_component=source_component,
- autoreconnect=True,
- )
- except OSError as error:
- if time.monotonic() >= deadline:
- raise TimeoutError(
- f"endpoint={endpoint} source_system={source_system} source_component={source_component} timeout_s={timeout_s}"
- ) from error
- time.sleep(0.2)
-
-
-def set_source_identity(connection: Any, system_id: int, component_id: int) -> None:
- connection.mav.srcSystem = system_id
- connection.mav.srcComponent = component_id
-
-
-def send_heartbeat(connection: Any, system_id: int, component_id: int, mav_type: int) -> None:
- set_source_identity(connection, system_id, component_id)
- connection.mav.heartbeat_send(
- mav_type,
- MAV_AUTOPILOT_INVALID,
- MAV_MODE_FLAG_CUSTOM_MODE_ENABLED,
- 0,
- MAV_STATE_ACTIVE,
- )
-
-
-def drain_link(connection: Any, duration_s: float) -> None:
- deadline = time.monotonic() + duration_s
- while time.monotonic() < deadline:
- message = connection.recv_match(blocking=False)
- if message is None:
- time.sleep(0.002)
-
-
-def drain_all_links(connections: Dict[str, Any], duration_s: float) -> None:
- for connection in connections.values():
- drain_link(connection, duration_s)
-
-
-def collect_command_observations(connections: Dict[str, Any], command_id: int, observation_window_s: float) -> Dict[str, List[Dict[str, Any]]]:
- observations: Dict[str, List[Dict[str, Any]]] = {link_name: [] for link_name in connections}
- deadline = time.monotonic() + observation_window_s
- while time.monotonic() < deadline:
- saw_message = False
- for link_name, connection in connections.items():
- while True:
- message = connection.recv_match(type=["COMMAND_LONG"], blocking=False)
- if message is None:
- break
- if int(message.command) != command_id:
- continue
- observations[link_name].append(
- {
- "src_system": int(message.get_srcSystem()),
- "src_component": int(message.get_srcComponent()),
- "target_system": int(message.target_system),
- "target_component": int(message.target_component),
- "command": int(message.command),
- "confirmation": int(message.confirmation),
- "params": [
- float(message.param1),
- float(message.param2),
- float(message.param3),
- float(message.param4),
- float(message.param5),
- float(message.param6),
- float(message.param7),
- ],
- }
- )
- saw_message = True
- if not saw_message:
- time.sleep(0.002)
- return observations
-
-
-if __name__ == "__main__":
- parser = argparse.ArgumentParser(description="Run MAVLink routing compliance checks against INAV multiport routing.")
- parser.add_argument("--config", required=True, type=Path, help="YAML config path")
- args = parser.parse_args()
-
- config = load_config(args.config)
- timing = config["timing"]
- network = config["network"]
- tests = config["tests"]
- components_cfg = config["components"]
- vehicle = config["vehicle"]
-
- gcs_link_name = network["gcs_link"]
- fc_system_id = int(vehicle["fc_system_id"])
- unknown_component_id = int(tests["unknown_component_id"])
- unknown_system_id = int(tests["unknown_system_id"])
- marker_command_base = int(tests["marker_command_base"])
- report_path = Path(tests["report_markdown"])
-
- link_cfgs = network["links"]
- if gcs_link_name not in link_cfgs:
- raise ValueError(f"gcs_link={gcs_link_name} missing from network.links")
-
- components: List[Dict[str, Any]] = []
- for component in components_cfg:
- if component["link"] not in link_cfgs:
- raise ValueError(f"component={component['name']} link={component['link']} missing from network.links")
- components.append(
- {
- "name": component["name"],
- "link": component["link"],
- "system_id": int(component["system_id"]),
- "component_id": int(component["component_id"]),
- "mav_type": int(component["mav_type"]),
- }
- )
-
- component_ids = {component["component_id"] for component in components}
- component_system_ids = {component["system_id"] for component in components}
- if unknown_component_id in component_ids:
- raise ValueError(f"unknown_component_id={unknown_component_id} collides with configured component IDs")
- if unknown_system_id in component_system_ids or unknown_system_id == fc_system_id:
- raise ValueError(f"unknown_system_id={unknown_system_id} collides with configured systems")
-
- gcs_actor = {
- "name": "gcs",
- "link": gcs_link_name,
- "system_id": int(link_cfgs[gcs_link_name]["source_system"]),
- "component_id": int(link_cfgs[gcs_link_name]["source_component"]),
- "mav_type": MAV_TYPE_GCS,
- }
-
- inter_source = components[0]
- inter_target = None
- for component in components:
- if component["link"] != inter_source["link"]:
- inter_target = component
- break
- if inter_target is None:
- raise ValueError("Need at least one component on a different link for inter-component routing test")
-
- connections: Dict[str, Any] = {}
- fc_heartbeats: Dict[str, Dict[str, int]] = {}
-
- try:
- for link_name, link_cfg in link_cfgs.items():
- connection = open_mavlink_connection(
- endpoint=link_cfg["endpoint"],
- source_system=int(link_cfg["source_system"]),
- source_component=int(link_cfg["source_component"]),
- timeout_s=float(timing["connect_timeout_s"]),
- )
- connections[link_name] = connection
-
- for link_name, connection in connections.items():
- heartbeat = connection.wait_heartbeat(timeout=float(timing["connect_timeout_s"]))
- if heartbeat is None:
- raise TimeoutError(f"link={link_name} wait_heartbeat timed out")
- fc_heartbeats[link_name] = {
- "system_id": int(heartbeat.get_srcSystem()),
- "component_id": int(heartbeat.get_srcComponent()),
- }
- print(
- f"fc_heartbeat link={link_name} system_id={fc_heartbeats[link_name]['system_id']} "
- f"component_id={fc_heartbeats[link_name]['component_id']}",
- flush=True,
- )
-
- time.sleep(float(timing["settle_after_connect_s"]))
- drain_all_links(connections, float(timing["drain_window_s"]))
-
- send_heartbeat(
- connections[gcs_actor["link"]],
- gcs_actor["system_id"],
- gcs_actor["component_id"],
- gcs_actor["mav_type"],
- )
- for component in components:
- send_heartbeat(
- connections[component["link"]],
- component["system_id"],
- component["component_id"],
- component["mav_type"],
- )
- print(
- f"route_learn_heartbeat component={component['name']} link={component['link']} "
- f"system_id={component['system_id']} component_id={component['component_id']} mav_type={component['mav_type']}",
- flush=True,
- )
- time.sleep(float(timing["route_learn_settle_s"]))
- drain_all_links(connections, float(timing["drain_window_s"]))
-
- cases: List[Dict[str, Any]] = []
- all_other_than_gcs = sorted([link_name for link_name in connections if link_name != gcs_link_name])
-
- cases.append(
- {
- "name": "gcs_broadcast",
- "source": gcs_actor,
- "target_system": 0,
- "target_component": 0,
- "expected_links": all_other_than_gcs,
- "rules": [ROUTING_RULE_REFERENCES["broadcast_forward"], ROUTING_RULE_REFERENCES["no_ingress_loop"]],
- }
- )
-
- cases.append(
- {
- "name": "gcs_target_local_system_component_broadcast",
- "source": gcs_actor,
- "target_system": fc_system_id,
- "target_component": 0,
- "expected_links": all_other_than_gcs,
- "rules": [ROUTING_RULE_REFERENCES["broadcast_forward"], ROUTING_RULE_REFERENCES["no_ingress_loop"]],
- }
- )
-
- for component in components:
- expected_links = [component["link"]]
- if component["link"] == gcs_link_name:
- expected_links = []
- cases.append(
- {
- "name": f"gcs_target_{component['name']}",
- "source": gcs_actor,
- "target_system": component["system_id"],
- "target_component": component["component_id"],
- "expected_links": sorted(expected_links),
- "rules": [ROUTING_RULE_REFERENCES["known_target_forward"], ROUTING_RULE_REFERENCES["no_ingress_loop"]],
- }
- )
-
- cases.append(
- {
- "name": "gcs_target_unknown_component",
- "source": gcs_actor,
- "target_system": fc_system_id,
- "target_component": unknown_component_id,
- "expected_links": [],
- "rules": [ROUTING_RULE_REFERENCES["unknown_target_blocked"]],
- }
- )
-
- cases.append(
- {
- "name": "gcs_target_unknown_system",
- "source": gcs_actor,
- "target_system": unknown_system_id,
- "target_component": 1,
- "expected_links": [],
- "rules": [ROUTING_RULE_REFERENCES["unknown_target_blocked"]],
- }
- )
-
- component_broadcast_expected = sorted([link_name for link_name in connections if link_name != inter_source["link"]])
- cases.append(
- {
- "name": f"{inter_source['name']}_broadcast",
- "source": inter_source,
- "target_system": 0,
- "target_component": 0,
- "expected_links": component_broadcast_expected,
- "rules": [ROUTING_RULE_REFERENCES["broadcast_forward"], ROUTING_RULE_REFERENCES["no_ingress_loop"]],
- }
- )
-
- cases.append(
- {
- "name": f"{inter_source['name']}_to_{inter_target['name']}",
- "source": inter_source,
- "target_system": inter_target["system_id"],
- "target_component": inter_target["component_id"],
- "expected_links": [inter_target["link"]],
- "rules": [ROUTING_RULE_REFERENCES["known_target_forward"], ROUTING_RULE_REFERENCES["no_ingress_loop"]],
- }
- )
-
- cases.append(
- {
- "name": f"{inter_source['name']}_to_gcs",
- "source": inter_source,
- "target_system": gcs_actor["system_id"],
- "target_component": gcs_actor["component_id"],
- "expected_links": [gcs_actor["link"]],
- "rules": [ROUTING_RULE_REFERENCES["known_target_forward"], ROUTING_RULE_REFERENCES["no_ingress_loop"]],
- }
- )
-
- if marker_command_base + len(cases) > 65535:
- raise ValueError(f"marker_command_base={marker_command_base} too high for case_count={len(cases)}")
-
- results: List[Dict[str, Any]] = []
- for case_index, case in enumerate(cases, start=1):
- drain_all_links(connections, float(timing["drain_window_s"]))
- command_id = marker_command_base + case_index
- confirmation = case_index % 256
- params = [
- float(1000 + case_index),
- float(2000 + case_index),
- float(3000 + case_index),
- float(4000 + case_index),
- float(5000 + case_index),
- float(6000 + case_index),
- float(7000 + case_index),
- ]
-
- source = case["source"]
- source_connection = connections[source["link"]]
- set_source_identity(source_connection, source["system_id"], source["component_id"])
- source_connection.mav.command_long_send(
- int(case["target_system"]),
- int(case["target_component"]),
- command_id,
- confirmation,
- params[0],
- params[1],
- params[2],
- params[3],
- params[4],
- params[5],
- params[6],
- )
-
- observations = collect_command_observations(
- connections=connections,
- command_id=command_id,
- observation_window_s=float(timing["observation_window_s"]),
- )
- observed_links = sorted([link_name for link_name, msgs in observations.items() if len(msgs) > 0])
- expected_links = sorted(case["expected_links"])
- no_ingress_loop = source["link"] not in observed_links
- routing_match = observed_links == expected_links
-
- payload_intact = True
- payload_issues: List[str] = []
- for link_name, messages in observations.items():
- for message in messages:
- if message["src_system"] != int(source["system_id"]) or message["src_component"] != int(source["component_id"]):
- payload_intact = False
- payload_issues.append(
- f"link={link_name} src_mismatch expected=({source['system_id']},{source['component_id']}) "
- f"observed=({message['src_system']},{message['src_component']})"
- )
- if message["target_system"] != int(case["target_system"]) or message["target_component"] != int(case["target_component"]):
- payload_intact = False
- payload_issues.append(
- f"link={link_name} target_mismatch expected=({case['target_system']},{case['target_component']}) "
- f"observed=({message['target_system']},{message['target_component']})"
- )
- if message["command"] != command_id or message["confirmation"] != confirmation:
- payload_intact = False
- payload_issues.append(
- f"link={link_name} cmd_mismatch expected=(command={command_id},confirmation={confirmation}) "
- f"observed=(command={message['command']},confirmation={message['confirmation']})"
- )
- for index, observed_value in enumerate(message["params"]):
- expected_value = params[index]
- if not math.isclose(observed_value, expected_value, rel_tol=0.0, abs_tol=1e-3):
- payload_intact = False
- payload_issues.append(
- f"link={link_name} param{index + 1}_mismatch expected={expected_value} observed={observed_value}"
- )
-
- case_pass = routing_match and no_ingress_loop and payload_intact
- results.append(
- {
- "name": case["name"],
- "source": source["name"],
- "source_link": source["link"],
- "target_system": int(case["target_system"]),
- "target_component": int(case["target_component"]),
- "command_id": command_id,
- "expected_links": expected_links,
- "observed_links": observed_links,
- "routing_match": routing_match,
- "no_ingress_loop": no_ingress_loop,
- "payload_intact": payload_intact,
- "pass": case_pass,
- "rules": case["rules"],
- "payload_issues": payload_issues,
- }
- )
-
- print(
- f"case={case['name']} command_id={command_id} source={source['name']} source_link={source['link']} "
- f"target=({case['target_system']},{case['target_component']}) expected_links={expected_links} observed_links={observed_links} "
- f"routing_match={routing_match} no_ingress_loop={no_ingress_loop} payload_intact={payload_intact} pass={case_pass}",
- flush=True,
- )
- time.sleep(float(timing["inter_case_pause_s"]))
-
- finally:
- for connection in connections.values():
- connection.close()
-
- pass_count = sum(1 for result in results if result["pass"])
- fail_count = len(results) - pass_count
-
- markdown_lines: List[str] = []
- markdown_lines.append("# MAVLink Routing Compliance Test")
- markdown_lines.append("")
- markdown_lines.append(
- f"- fc_system_id: `{fc_system_id}`"
- )
- markdown_lines.append(
- f"- links: `{sorted(list(link_cfgs.keys()))}`"
- )
- markdown_lines.append(
- f"- gcs_link: `{gcs_link_name}`"
- )
- markdown_lines.append(
- f"- components: `{[(component['name'], component['system_id'], component['component_id'], component['link']) for component in components]}`"
- )
- markdown_lines.append("")
- markdown_lines.append("## Rule References")
- markdown_lines.append("")
- markdown_lines.append(f"- broadcast_forward: `{ROUTING_RULE_REFERENCES['broadcast_forward']}`")
- markdown_lines.append(f"- known_target_forward: `{ROUTING_RULE_REFERENCES['known_target_forward']}`")
- markdown_lines.append(f"- unknown_target_blocked: `{ROUTING_RULE_REFERENCES['unknown_target_blocked']}`")
- markdown_lines.append(f"- no_ingress_loop: `{ROUTING_RULE_REFERENCES['no_ingress_loop']}`")
- markdown_lines.append(f"- no_repack: `{ROUTING_RULE_REFERENCES['no_repack']}`")
- markdown_lines.append("")
- markdown_lines.append("## Results")
- markdown_lines.append("")
- markdown_lines.append("| Case | Source(link) | Target(sys,comp) | Expected Links | Observed Links | Routing | No Ingress Loop | Payload Intact | Pass |")
- markdown_lines.append("| --- | --- | --- | --- | --- | --- | --- | --- | --- |")
- for result in results:
- markdown_lines.append(
- f"| `{result['name']}` | `{result['source']} ({result['source_link']})` | "
- f"`({result['target_system']},{result['target_component']})` | "
- f"`{result['expected_links']}` | `{result['observed_links']}` | "
- f"`{result['routing_match']}` | `{result['no_ingress_loop']}` | `{result['payload_intact']}` | `{result['pass']}` |"
- )
- markdown_lines.append("")
- markdown_lines.append(f"summary pass_count={pass_count} fail_count={fail_count} total={len(results)}")
- markdown_lines.append("")
-
- failures = [result for result in results if not result["pass"]]
- if failures:
- markdown_lines.append("## Failure Details")
- markdown_lines.append("")
- for failure in failures:
- markdown_lines.append(f"### {failure['name']}")
- markdown_lines.append("")
- markdown_lines.append(
- f"- expected_links: `{failure['expected_links']}` observed_links: `{failure['observed_links']}` "
- f"routing_match: `{failure['routing_match']}` no_ingress_loop: `{failure['no_ingress_loop']}` "
- f"payload_intact: `{failure['payload_intact']}`"
- )
- if failure["payload_issues"]:
- markdown_lines.append(f"- payload_issues: `{failure['payload_issues']}`")
- markdown_lines.append(f"- rule_refs: `{failure['rules']}`")
- markdown_lines.append("")
-
- report_path.write_text("\n".join(markdown_lines) + "\n", encoding="utf-8")
- print(f"report_path={report_path} pass_count={pass_count} fail_count={fail_count} total={len(results)}", flush=True)
-
- if fail_count > 0:
- raise SystemExit(1)
diff --git a/src/utils/mavlink_tests/mavlink_test_rc.py b/src/utils/mavlink_tests/mavlink_test_rc.py
deleted file mode 100644
index 4862ec7aad2..00000000000
--- a/src/utils/mavlink_tests/mavlink_test_rc.py
+++ /dev/null
@@ -1,141 +0,0 @@
-#!/usr/bin/env python3
-"""
-Usage:
- conda run -n drone python mydev/branch/mav_multi/mavlink_test_rc.py --master tcp:127.0.0.1:5761
- conda run -n drone python mydev/branch/mav_multi/mavlink_test_rc.py --master tcp:127.0.0.1:5761 --duration 20 --tx-hz 100 --roll MID --pitch MID --yaw MID --throttle LOW
-"""
-
-from __future__ import annotations
-
-import argparse
-import time
-from collections import Counter
-from typing import List
-
-from pymavlink import mavutil
-
-
-CHANNEL_ORDER = [
- "roll",
- "pitch",
- "throttle",
- "yaw",
- "ch5",
- "ch6",
- "ch7",
- "ch8",
- "ch9",
- "ch10",
- "ch11",
- "ch12",
- "ch13",
- "ch14",
- "ch15",
- "ch16",
- "ch17",
- "ch18",
-]
-DEFAULT_CHANNELS = [900] * 18
-DEFAULT_CHANNELS[0] = 1500
-DEFAULT_CHANNELS[1] = 1500
-DEFAULT_CHANNELS[3] = 1500
-LEVEL_TO_PWM = {"LOW": 900, "MID": 1500, "HIGH": 2100}
-
-
-if __name__ == "__main__":
- parser = argparse.ArgumentParser(description="Send MAVLink RC_CHANNELS_OVERRIDE stream and monitor RC echo.")
- parser.add_argument("--master", required=True, help='pymavlink master endpoint, e.g. "tcp:127.0.0.1:5761"')
- parser.add_argument("--tx-hz", type=float, default=100.0, help="RC override transmit rate in Hz")
- parser.add_argument("--duration", type=float, default=0.0, help="Test duration in seconds, 0 means run forever")
- parser.add_argument("--source-system", type=int, default=240, help="MAVLink source system ID")
- parser.add_argument("--source-component", type=int, default=191, help="MAVLink source component ID")
- parser.add_argument("--echo-tolerance", type=int, default=20, help="Allowed absolute PWM error for RC_CHANNELS echo checks")
- for channel_name in CHANNEL_ORDER:
- parser.add_argument(f"--{channel_name}", default=None, help="LOW/MID/HIGH or integer PWM")
- args = parser.parse_args()
-
- channels: List[int] = list(DEFAULT_CHANNELS)
- for idx, channel_name in enumerate(CHANNEL_ORDER):
- raw_value = getattr(args, channel_name)
- if raw_value is None:
- continue
- level_name = raw_value.upper()
- if level_name in LEVEL_TO_PWM:
- channels[idx] = LEVEL_TO_PWM[level_name]
- else:
- channels[idx] = int(raw_value)
-
- print(
- f"master={args.master} tx_hz={args.tx_hz} duration={args.duration} "
- f"source_system={args.source_system} source_component={args.source_component} channels={channels}",
- flush=True,
- )
-
- master = mavutil.mavlink_connection(
- args.master,
- source_system=args.source_system,
- source_component=args.source_component,
- autoreconnect=True,
- )
- heartbeat = master.wait_heartbeat(timeout=10)
- if heartbeat is None:
- raise TimeoutError("No heartbeat received from FC")
- target_system = heartbeat.get_srcSystem()
- target_component = heartbeat.get_srcComponent()
- print(f"target_system={target_system} target_component={target_component}", flush=True)
-
- period_s = 1.0 / args.tx_hz
- tx_count = 0
- rx_count = 0
- mismatch_count = 0
- decode_errors = 0
- last_rx_time = 0.0
- loop_start = time.monotonic()
- next_tx_time = loop_start
- next_report_time = loop_start + 1.0
- mismatch_hist = Counter()
-
- while True:
- now = time.monotonic()
- if args.duration > 0 and (now - loop_start) >= args.duration:
- break
-
- if now >= next_tx_time:
- master.mav.rc_channels_override_send(target_system, target_component, *channels[:8])
- tx_count += 1
- next_tx_time += period_s
- if next_tx_time < now:
- next_tx_time = now + period_s
-
- message = master.recv_match(type=["RC_CHANNELS", "RC_CHANNELS_RAW"], blocking=False)
- if message is not None:
- rx_count += 1
- last_rx_time = now
- if message.get_type() == "RC_CHANNELS":
- for i in range(4):
- key = f"chan{i + 1}_raw"
- observed = int(getattr(message, key))
- err = abs(observed - channels[i])
- if err > args.echo_tolerance:
- mismatch_count += 1
- mismatch_hist[i + 1] += 1
- else:
- decode_errors += 1
-
- if now >= next_report_time:
- rx_age = -1.0 if last_rx_time == 0.0 else (now - last_rx_time)
- print(
- f"status_s={now - loop_start:.1f} tx={tx_count} rx={rx_count} mismatches={mismatch_count} "
- f"decode_errors={decode_errors} rx_age_s={rx_age:.3f} mismatch_hist={dict(mismatch_hist)}",
- flush=True,
- )
- next_report_time += 1.0
-
- time.sleep(0.001)
-
- elapsed = max(time.monotonic() - loop_start, 1e-6)
- print(
- f"summary elapsed_s={elapsed:.2f} tx={tx_count} rx={rx_count} mismatch_count={mismatch_count} "
- f"mismatch_rate={mismatch_count / max(rx_count, 1):.6f} tx_hz={tx_count / elapsed:.2f} rx_hz={rx_count / elapsed:.2f}",
- flush=True,
- )
diff --git a/src/utils/mavlink_tests/msp_test_rc.py b/src/utils/mavlink_tests/msp_test_rc.py
deleted file mode 100644
index 9cd41cb6c5d..00000000000
--- a/src/utils/mavlink_tests/msp_test_rc.py
+++ /dev/null
@@ -1,145 +0,0 @@
-#!/usr/bin/env python3
-"""
-Usage:
- conda run -n drone python mydev/branch/mav_multi/msp_test_rc.py --msp-endpoint 127.0.0.1:5760 --duration 20
- conda run -n drone python mydev/branch/mav_multi/msp_test_rc.py --msp-endpoint 127.0.0.1:5760 --poll-hz 25 --roll MID --pitch MID --yaw MID --throttle LOW
-"""
-
-from __future__ import annotations
-
-import argparse
-import struct
-import time
-from collections import Counter
-from pathlib import Path
-from typing import List
-
-from serial.serialutil import SerialException
-
-try:
- from mspapi2.msp_api import MSPApi
- from mspapi2.lib import InavMSP
-except ModuleNotFoundError:
- repo_root_guess = Path(__file__).resolve().parents[3]
- mspapi2_repo = repo_root_guess.parent / "mspapi2"
- if mspapi2_repo.exists():
- import sys
-
- sys.path.insert(0, str(mspapi2_repo))
- from mspapi2.msp_api import MSPApi
- from mspapi2.lib import InavMSP
-
-
-CHANNEL_ORDER = [
- "roll",
- "pitch",
- "throttle",
- "yaw",
- "ch5",
- "ch6",
- "ch7",
- "ch8",
- "ch9",
- "ch10",
- "ch11",
- "ch12",
- "ch13",
- "ch14",
- "ch15",
- "ch16",
- "ch17",
- "ch18",
-]
-DEFAULT_CHANNELS = [900] * 18
-DEFAULT_CHANNELS[0] = 1500
-DEFAULT_CHANNELS[1] = 1500
-DEFAULT_CHANNELS[3] = 1500
-LEVEL_TO_PWM = {"LOW": 900, "MID": 1500, "HIGH": 2100}
-
-
-if __name__ == "__main__":
- parser = argparse.ArgumentParser(description="Poll MSP_RC and monitor RC values against expected channels.")
- parser.add_argument("--msp-endpoint", required=True, help='MSP endpoint, e.g. "127.0.0.1:5760"')
- parser.add_argument("--poll-hz", type=float, default=25.0, help="MSP_RC poll rate in Hz")
- parser.add_argument("--timeout-s", type=float, default=0.2, help="Per MSP request timeout")
- parser.add_argument("--duration", type=float, default=0.0, help="Test duration in seconds, 0 means run forever")
- parser.add_argument("--echo-tolerance", type=int, default=40, help="Allowed absolute PWM error per channel")
- for channel_name in CHANNEL_ORDER:
- parser.add_argument(f"--{channel_name}", default=None, help="LOW/MID/HIGH or integer PWM")
- args = parser.parse_args()
-
- expected_channels: List[int] = list(DEFAULT_CHANNELS)
- for idx, channel_name in enumerate(CHANNEL_ORDER):
- raw_value = getattr(args, channel_name)
- if raw_value is None:
- continue
- level_name = raw_value.upper()
- if level_name in LEVEL_TO_PWM:
- expected_channels[idx] = LEVEL_TO_PWM[level_name]
- else:
- expected_channels[idx] = int(raw_value)
-
- print(
- f"msp_endpoint={args.msp_endpoint} poll_hz={args.poll_hz} duration={args.duration} "
- f"timeout_s={args.timeout_s} expected_channels={expected_channels}",
- flush=True,
- )
-
- poll_period_s = 1.0 / args.poll_hz
- success_count = 0
- fail_count = 0
- mismatch_count = 0
- mismatch_hist = Counter()
- last_success_time = 0.0
- start_t = time.monotonic()
- next_poll_t = start_t
- next_report_t = start_t + 1.0
-
- with MSPApi(tcp_endpoint=args.msp_endpoint) as msp_api:
- msp_api._serial._max_retries = 1
- msp_api._serial._reconnect_delay = 0.05
- while True:
- now = time.monotonic()
- if args.duration > 0 and (now - start_t) >= args.duration:
- break
-
- if now >= next_poll_t:
- try:
- _, payload = msp_api._request_raw(InavMSP.MSP_RC, timeout=args.timeout_s)
- if len(payload) % 2:
- raise ValueError("MSP RC payload length must be even")
- channel_count = len(payload) // 2
- observed_channels = list(struct.unpack(f"<{channel_count}H", payload))
- success_count += 1
- last_success_time = now
- for i in range(min(channel_count, len(expected_channels))):
- error = abs(observed_channels[i] - expected_channels[i])
- if error > args.echo_tolerance:
- mismatch_count += 1
- mismatch_hist[i + 1] += 1
- except (SerialException, RuntimeError, TimeoutError, ConnectionRefusedError):
- fail_count += 1
- next_poll_t += poll_period_s
- if next_poll_t < now:
- next_poll_t = now + poll_period_s
-
- if now >= next_report_t:
- last_ok_age_s = -1.0 if last_success_time == 0.0 else (now - last_success_time)
- total = success_count + fail_count
- print(
- f"status_s={now - start_t:.1f} ok={success_count} fail={fail_count} fail_rate={fail_count / max(total, 1):.6f} "
- f"mismatch={mismatch_count} mismatch_rate={mismatch_count / max(success_count, 1):.6f} "
- f"last_ok_age_s={last_ok_age_s:.3f} mismatch_hist={dict(mismatch_hist)}",
- flush=True,
- )
- next_report_t += 1.0
-
- time.sleep(0.001)
-
- elapsed = max(time.monotonic() - start_t, 1e-6)
- total = success_count + fail_count
- print(
- f"summary elapsed_s={elapsed:.2f} ok={success_count} fail={fail_count} fail_rate={fail_count / max(total, 1):.6f} "
- f"mismatch={mismatch_count} mismatch_rate={mismatch_count / max(success_count, 1):.6f} poll_hz={success_count / elapsed:.2f}",
- flush=True,
- )
diff --git a/src/utils/mavlink_tests/routing_test_config.yaml b/src/utils/mavlink_tests/routing_test_config.yaml
deleted file mode 100644
index d4677ba4ebf..00000000000
--- a/src/utils/mavlink_tests/routing_test_config.yaml
+++ /dev/null
@@ -1,58 +0,0 @@
-timing:
- connect_timeout_s: 10.0
- settle_after_connect_s: 0.5
- route_learn_settle_s: 0.5
- drain_window_s: 0.15
- observation_window_s: 0.8
- inter_case_pause_s: 0.15
-
-network:
- gcs_link: link_radio
- links:
- link_radio:
- endpoint: tcp:127.0.0.1:5761
- source_system: 1
- source_component: 68
- link_companion:
- endpoint: tcp:127.0.0.1:5762
- source_system: 1
- source_component: 191
- link_camera:
- endpoint: tcp:127.0.0.1:5763
- source_system: 1
- source_component: 100
- link_gimbal:
- endpoint: tcp:127.0.0.1:5764
- source_system: 1
- source_component: 154
-
-vehicle:
- fc_system_id: 1
-
-tests:
- marker_command_base: 31000
- unknown_component_id: 199
- unknown_system_id: 42
- report_markdown: src/utils/mavlink_tests/ROUTING_TEST.md
-
-components:
- - name: mav2_companion_computer
- link: link_companion
- system_id: 1
- component_id: 191
- mav_type: 18
- - name: mav1_elrs_receiver
- link: link_radio
- system_id: 1
- component_id: 68
- mav_type: 49
- - name: mav3_camera
- link: link_camera
- system_id: 1
- component_id: 100
- mav_type: 30
- - name: mav4_gimbal
- link: link_gimbal
- system_id: 1
- component_id: 154
- mav_type: 26
diff --git a/src/utils/mavlink_tests/test_config_multiport4_sweep_rc460800_tele115200.yaml b/src/utils/mavlink_tests/test_config_multiport4_sweep_rc460800_tele115200.yaml
deleted file mode 100644
index a73523f0698..00000000000
--- a/src/utils/mavlink_tests/test_config_multiport4_sweep_rc460800_tele115200.yaml
+++ /dev/null
@@ -1,51 +0,0 @@
-sitl:
- binary: /media/anon/WD2TB/DataVault/TechProjects/Software/GitRepos/inav/cmake/build_SITL/inav_9.0.0_SITL
- workdir: /media/anon/WD2TB/DataVault/TechProjects/Software/GitRepos/inav/cmake
- eeprom_path: /media/anon/WD2TB/DataVault/TechProjects/Software/GitRepos/inav/mydev/branch/mav_multi/eeprom_multi4_sweep.bin
- runtime_log: /media/anon/WD2TB/DataVault/TechProjects/Software/GitRepos/inav/mydev/branch/mav_multi/sitl_runtime_multi4_sweep.log
-
-ports:
- msp: 5760
- rc: 5761
- telemetry:
- - 5762
- - 5763
- - 5764
-
-cli:
- rc_baud: 460800
- telemetry_baud: 115200
- ext_status_rate_hz: 10
- rc_chan_rate_hz: 25
- pos_rate_hz: 10
- extra1_rate_hz: 10
- extra2_rate_hz: 10
- extra3_rate_hz: 5
-
-tests:
- port_ready_timeout_s: 30
- save_reboot_timeout_s: 45
- mavsdk_probe_timeout_s: 10
- heartbeat_expected_hz: 1.0
- rc_expected_hz: 25.0
- rc_target_system: 1
- rc_target_component: 1
- rc_tx_hz: 100.0
- rc_tx_hz_max: 400.0
- msp_poll_hz: 50.0
- inav_status_hz: 5.0
- msp_request_timeout_s: 0.2
- stress_command_message_id: 33
- baseline_duration_s: 30
- progressive_rates_hz:
- - 50
- - 100
- - 200
- - 400
- stress_duration_s: 20
- max_rate_hz: 400
- all_ports_max_duration_s: 30
- sweep_duration_s: 8
-
-output:
- testing_md: /media/anon/WD2TB/DataVault/TechProjects/Software/GitRepos/inav/mydev/branch/mav_multi/TESTING_multiport4_sweep_rc460800_tele115200.md
From b2194921d2829991923dfde16a77bf6eaf77ecf9 Mon Sep 17 00:00:00 2001
From: frogmane <7685285+xznhj8129@users.noreply.github.com>
Date: Fri, 3 Apr 2026 13:53:22 -0400
Subject: [PATCH 33/46] Fix MAVLink routing and intervals
---
docs/Mavlink.md | 17 +-
docs/Settings.md | 40 ---
src/main/fc/settings.yaml | 28 --
src/main/io/serial.c | 2 +
src/main/telemetry/mavlink.c | 391 +++++++++++++++++++---------
src/main/telemetry/mavlink.h | 18 ++
src/main/telemetry/telemetry.c | 4 -
src/main/telemetry/telemetry.h | 1 -
src/test/unit/mavlink_unittest.cc | 412 +++++++++++++++++++++++++++++-
9 files changed, 716 insertions(+), 197 deletions(-)
diff --git a/docs/Mavlink.md b/docs/Mavlink.md
index c42310a30ab..5194881c29f 100644
--- a/docs/Mavlink.md
+++ b/docs/Mavlink.md
@@ -17,7 +17,6 @@ INAV supports up to 4 concurrent MAVLink telemetry ports (`MAX_MAVLINK_PORTS`),
### Usage guidance
- If you rely on RC via MAVLink, ensure the serial receiver type is set to `SERIALRX_MAVLINK` and consider enabling `telemetry_halfduplex` when RX shares the port.
- To reduce bandwidth, lower the stream rates for groups you do not need, or disable them entirely by setting the rate to 0.
-- Assign a unique `mavlink_port{1-4}_compid` to each INAV MAVLink port to avoid ambiguous local targeting.
- If a GCS or companion needs telemetry on ports 2..4, explicitly request streams (`REQUEST_DATA_STREAM` or `MAV_CMD_SET_MESSAGE_INTERVAL`) because only heartbeat is enabled by default.
- If you depend on directed forwarding between links, ensure each remote endpoint transmits at least one frame early so route learning is populated.
@@ -35,11 +34,12 @@ INAV supports up to 4 concurrent MAVLink telemetry ports (`MAX_MAVLINK_PORTS`),
- `mavlink_port{1-4}_extra3_rate`.
- Port 1 uses configured CLI rates (`mavlink_port1_*_rate`).
- Ports 2..4 start with heartbeat only (1 Hz), all other streams disabled.
-- `mavlink_port{1-4}_compid` - MAV_COMPONENT ID of port. Ensure these are different.
- `mavlink_port{1-4}_min_txbuffer` - minimum remote TX buffer level before sending when `RADIO_STATUS` provides flow control.
- `mavlink_port{1-4}_radio_type`- scales `RADIO_STATUS` RSSI/SNR for **generic**, **ELRS**, or **SiK** links.
- `mavlink_port{1-4}_high_latency`- turns on Mavlink HIGH_LATENCY2 mode on this port
+INAV always transmits as MAVLink component `MAV_COMP_ID_AUTOPILOT1`. Attached MAVLink devices are remote components learned from incoming traffic; they are not modeled as local per-port FC identities.
+
## Datastream groups and defaults
@@ -55,7 +55,7 @@ Ports 2..N use a secondary startup profile (heartbeat at 1 Hz, other streams dis
| `EXTRA2` | `VFR_HUD` | 2 Hz |
| `HEARTBEAT` | `HEARTBEAT` | 1 Hz (independent of stream groups) |
| `EXT_SYS_STATE` | `EXTENDED_SYS_STATE` | 1 Hz (defaults to `mavlink_port1_extra3_rate`) |
-| `EXTRA3` | `BATTERY_STATUS`, `SCALED_PRESSURE`, `STATUSTEXT` (when present) | 1 Hz |
+| `EXTRA3` | `BATTERY_STATUS`, `SCALED_PRESSURE`, `SYSTEM_TIME`, `STATUSTEXT` (when present) | 1 Hz |
### Routing, forwarding and local handling
@@ -63,11 +63,13 @@ Ports 2..N use a secondary startup profile (heartbeat at 1 Hz, other streams dis
- Broadcast messages are forwarded to all other MAVLink ports (except `RADIO_STATUS`, which is not forwarded).
- Targeted messages are forwarded only to ports with a learned route for that target.
- Practical caveat: the first targeted message to a never-seen endpoint may not forward until that endpoint has sent at least one MAVLink frame.
+- INAV’s local FC identity is always `(mavlink_sysid, MAV_COMP_ID_AUTOPILOT1)`.
+- Traffic from the local system ID but a different component ID is treated as a remote component and can be learned into the route table.
- Local/system broadcasts (`target_system=0` or local system ID with `target_component=0`) are fanned out to all local ports only for:
- `REQUEST_DATA_STREAM`
- `MAV_CMD_SET_MESSAGE_INTERVAL`
- `MAV_CMD_CONTROL_HIGH_LATENCY`
-- Other incoming commands/messages are handled on one resolved local port, based on local target matching.
+- Other incoming commands/messages are handled once on the resolved local ingress path, but broadcast-targeted control requests still execute locally.
## Supported Outgoing Messages
@@ -84,6 +86,7 @@ Messages are organized into MAVLink datastream groups. Each group sends **one me
- `EXTENDED_SYS_STATE`: publishes landed state.
- `BATTERY_STATUS`: with per-cell voltages (cells 11‑14 in `voltages_ext`), current draw, consumed mAh/Wh, and remaining percentage when available.
- `SCALED_PRESSURE`: for IMU/baro temperature.
+- `SYSTEM_TIME`: with `time_boot_ms = millis()` and `time_unix_usec = 0`.
- `STATUSTEXT`: when the OSD has a pending system message; severity follows OSD attributes (notice/warning/critical).
- On-demand (command-triggered) messages: `AUTOPILOT_VERSION`, `PROTOCOL_VERSION`, `MESSAGE_INTERVAL`, `HOME_POSITION`, `AVAILABLE_MODES`, and `CURRENT_MODE`.
@@ -111,9 +114,9 @@ Limited implementation of the Command protocol.
- `MAV_CMD_DO_REPOSITION`: sets the Follow Me/GCS Nav waypoint when GCS NAV is valid. Accepts `MAV_FRAME_GLOBAL`, `MAV_FRAME_GLOBAL_INT`, `MAV_FRAME_GLOBAL_RELATIVE_ALT`, `MAV_FRAME_GLOBAL_RELATIVE_ALT_INT`; otherwise `UNSUPPORTED`.
- `MAV_CMD_CONDITION_YAW`: changes the current heading target when the active navigation state has yaw control. Accepts absolute heading (`param4=0`) and relative turns (`param4!=0`); turn-rate is ignored.
-- `MAV_CMD_SET_MESSAGE_INTERVAL` / `MAV_CMD_GET_MESSAGE_INTERVAL`: adjust or query telemetry stream output for supported message IDs (streamed messages only; intervals slower than 1 Hz are not accepted).
+- `MAV_CMD_SET_MESSAGE_INTERVAL` / `MAV_CMD_GET_MESSAGE_INTERVAL`: adjust or query per-message periodic output for `HEARTBEAT`, `SYS_STATUS`, `EXTENDED_SYS_STATE`, RC channels, `GPS_RAW_INT`, `GLOBAL_POSITION_INT`, `GPS_GLOBAL_ORIGIN`, `ATTITUDE`, `VFR_HUD`, `BATTERY_STATUS`, `SCALED_PRESSURE`, and `SYSTEM_TIME`. `REQUEST_DATA_STREAM` still controls the legacy base stream groups; `SET_MESSAGE_INTERVAL` overrides individual messages on top.
- `MAV_CMD_GET_HOME_POSITION`: replies with `HOME_POSITION` when home fix exists.
-- `MAV_CMD_REQUEST_MESSAGE`: emits one selected message (`HEARTBEAT`, `SYS_STATUS`, `ATTITUDE`, `VFR_HUD`, `AVAILABLE_MODES`, `CURRENT_MODE`, `EXTENDED_SYS_STATE`, RC channels, GPS/global/origin, battery/pressure, and `HOME_POSITION` when available) or `UNSUPPORTED`.
+- `MAV_CMD_REQUEST_MESSAGE`: emits one selected message (`HEARTBEAT`, `SYS_STATUS`, `ATTITUDE`, `VFR_HUD`, `AVAILABLE_MODES`, `CURRENT_MODE`, `EXTENDED_SYS_STATE`, RC channels, `GPS_RAW_INT`, `GLOBAL_POSITION_INT`, `GPS_GLOBAL_ORIGIN`, `BATTERY_STATUS`, `SCALED_PRESSURE`, `SYSTEM_TIME`, and `HOME_POSITION` when available) or `UNSUPPORTED`.
- `MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES`: returns stub `AUTOPILOT_VERSION` (v2 only; v1 returns `UNSUPPORTED`) advertising `SET_POSITION_TARGET_GLOBAL_INT` and `SET_POSITION_TARGET_LOCAL_NED`.
- `MAV_CMD_REQUEST_PROTOCOL_VERSION`: returns stub `PROTOCOL_VERSION` (v2 only; v1 returns `UNSUPPORTED`).
@@ -169,7 +172,7 @@ CLI mode is unavailable in MSP-over-MAVLink.
- INAV accepts `TUNNEL` messages with private payload type `0x8001` as an MSP byte stream carried over MAVLink2.
- `target_system` must match `mavlink_sysid`.
-- `target_component` may be `0` or the local port `mavlink_port{1-4}_compid`.
+- `target_component` may be `0` or `MAV_COMP_ID_AUTOPILOT1`.
- `target_component=0` is handled on the ingress MAVLink port only; it is not fanned out to other local MAVLink ports.
- MSP replies are sent back to the requester as one or more `TUNNEL` messages on that same ingress port.
- MSP framing is preserved end-to-end: MSPv1 requests get MSPv1 replies, and MSPv2 requests get MSPv2 replies.
diff --git a/docs/Settings.md b/docs/Settings.md
index 31e8095d34e..23c5da33457 100644
--- a/docs/Settings.md
+++ b/docs/Settings.md
@@ -2652,16 +2652,6 @@ Autopilot type to advertise for MAVLink telemetry
---
-### mavlink_port1_compid
-
-MAVLink Component ID for MAVLink port 1
-
-| Default | Min | Max |
-| --- | --- | --- |
-| 1 | 1 | 255 |
-
----
-
### mavlink_port1_ext_status_rate
Rate of the extended status message for MAVLink telemetry on port 1
@@ -2752,16 +2742,6 @@ Rate of the RC channels message for MAVLink telemetry on port 1
---
-### mavlink_port2_compid
-
-MAVLink Component ID for MAVLink port 2
-
-| Default | Min | Max |
-| --- | --- | --- |
-| 1 | 1 | 255 |
-
----
-
### mavlink_port2_high_latency
Enable MAVLink high-latency mode on port 2
@@ -2792,16 +2772,6 @@ MAVLink radio type for port 2. Affects RSSI and LQ reporting on OSD.
---
-### mavlink_port3_compid
-
-MAVLink Component ID for MAVLink port 3
-
-| Default | Min | Max |
-| --- | --- | --- |
-| 1 | 1 | 255 |
-
----
-
### mavlink_port3_high_latency
Enable MAVLink high-latency mode on port 3
@@ -2832,16 +2802,6 @@ MAVLink radio type for port 3. Affects RSSI and LQ reporting on OSD.
---
-### mavlink_port4_compid
-
-MAVLink Component ID for MAVLink port 4
-
-| Default | Min | Max |
-| --- | --- | --- |
-| 1 | 1 | 255 |
-
----
-
### mavlink_port4_high_latency
Enable MAVLink high-latency mode on port 4
diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml
index b9d09980455..118582e8071 100644
--- a/src/main/fc/settings.yaml
+++ b/src/main/fc/settings.yaml
@@ -3298,13 +3298,6 @@ groups:
min: 1
max: 255
default_value: 1
- - name: mavlink_port1_compid
- field: mavlink[0].compid
- description: "MAVLink Component ID for MAVLink port 1"
- type: uint8_t
- min: 1
- max: 255
- default_value: 1
- name: mavlink_port1_high_latency
field: mavlink[0].high_latency
description: "Enable MAVLink high-latency mode on port 1"
@@ -3322,13 +3315,6 @@ groups:
table: mavlink_radio_type
default_value: "GENERIC"
type: uint8_t
- - name: mavlink_port2_compid
- field: mavlink[1].compid
- description: "MAVLink Component ID for MAVLink port 2"
- type: uint8_t
- min: 1
- max: 255
- default_value: 1
- name: mavlink_port2_high_latency
field: mavlink[1].high_latency
description: "Enable MAVLink high-latency mode on port 2"
@@ -3346,13 +3332,6 @@ groups:
table: mavlink_radio_type
default_value: "GENERIC"
type: uint8_t
- - name: mavlink_port3_compid
- field: mavlink[2].compid
- description: "MAVLink Component ID for MAVLink port 3"
- type: uint8_t
- min: 1
- max: 255
- default_value: 1
- name: mavlink_port3_high_latency
field: mavlink[2].high_latency
description: "Enable MAVLink high-latency mode on port 3"
@@ -3370,13 +3349,6 @@ groups:
table: mavlink_radio_type
default_value: "GENERIC"
type: uint8_t
- - name: mavlink_port4_compid
- field: mavlink[3].compid
- description: "MAVLink Component ID for MAVLink port 4"
- type: uint8_t
- min: 1
- max: 255
- default_value: 1
- name: mavlink_port4_high_latency
field: mavlink[3].high_latency
description: "Enable MAVLink high-latency mode on port 4"
diff --git a/src/main/io/serial.c b/src/main/io/serial.c
index e7865f3fac2..d6b82da02b8 100644
--- a/src/main/io/serial.c
+++ b/src/main/io/serial.c
@@ -296,8 +296,10 @@ bool isSerialConfigValid(const serialConfig_t *serialConfigToCheck)
if ((portConfig->functionMask & FUNCTION_MSP) && (portConfig->functionMask & ALL_FUNCTIONS_SHARABLE_WITH_MSP)) {
// MSP & telemetry
+#ifdef USE_TELEMETRY
} else if (telemetryCheckRxPortShared(portConfig)) {
// serial RX & telemetry
+#endif
} else {
// some other combination
return false;
diff --git a/src/main/telemetry/mavlink.c b/src/main/telemetry/mavlink.c
index 6b7e5496475..29fe90f58f9 100644
--- a/src/main/telemetry/mavlink.c
+++ b/src/main/telemetry/mavlink.c
@@ -119,7 +119,7 @@ static const mavlinkTelemetryPortConfig_t *mavActiveConfig = NULL;
static mavlink_message_t mavSendMsg;
static mavlink_message_t mavRecvMsg;
-// Set active MAV identity from active port settings.
+// Set active MAV identity from global MAVLink settings.
static uint8_t mavSystemId = 1;
static uint8_t mavAutopilotType;
static uint8_t mavComponentId = MAV_COMP_ID_AUTOPILOT1;
@@ -277,7 +277,7 @@ static void mavlinkSetActivePortContext(uint8_t portIndex)
const mavlinkTelemetryCommonConfig_t *commonConfig = mavlinkGetCommonConfig();
mavAutopilotType = commonConfig->autopilot_type;
mavSystemId = commonConfig->sysid;
- mavComponentId = mavActiveConfig->compid;
+ mavComponentId = MAV_COMP_ID_AUTOPILOT1;
mavlinkApplyActivePortOutputVersion();
}
@@ -290,6 +290,145 @@ static uint8_t mavlinkClampStreamRate(uint8_t rate)
return rate;
}
+static int32_t mavlinkRateToIntervalUs(uint8_t rate)
+{
+ rate = mavlinkClampStreamRate(rate);
+ if (rate == 0) {
+ return -1;
+ }
+
+ return 1000000 / rate;
+}
+
+static bool mavlinkPeriodicMessageFromMessageId(uint16_t messageId, mavlinkPeriodicMessage_e *periodicMessage)
+{
+ switch (messageId) {
+ case MAVLINK_MSG_ID_HEARTBEAT:
+ *periodicMessage = MAVLINK_PERIODIC_MESSAGE_HEARTBEAT;
+ return true;
+ case MAVLINK_MSG_ID_SYS_STATUS:
+ *periodicMessage = MAVLINK_PERIODIC_MESSAGE_SYS_STATUS;
+ return true;
+ case MAVLINK_MSG_ID_EXTENDED_SYS_STATE:
+ *periodicMessage = MAVLINK_PERIODIC_MESSAGE_EXTENDED_SYS_STATE;
+ return true;
+ case MAVLINK_MSG_ID_RC_CHANNELS:
+ case MAVLINK_MSG_ID_RC_CHANNELS_RAW:
+ case MAVLINK_MSG_ID_RC_CHANNELS_SCALED:
+ *periodicMessage = MAVLINK_PERIODIC_MESSAGE_RC_CHANNELS;
+ return true;
+ case MAVLINK_MSG_ID_GPS_RAW_INT:
+ *periodicMessage = MAVLINK_PERIODIC_MESSAGE_GPS_RAW_INT;
+ return true;
+ case MAVLINK_MSG_ID_GLOBAL_POSITION_INT:
+ *periodicMessage = MAVLINK_PERIODIC_MESSAGE_GLOBAL_POSITION_INT;
+ return true;
+ case MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN:
+ *periodicMessage = MAVLINK_PERIODIC_MESSAGE_GPS_GLOBAL_ORIGIN;
+ return true;
+ case MAVLINK_MSG_ID_ATTITUDE:
+ *periodicMessage = MAVLINK_PERIODIC_MESSAGE_ATTITUDE;
+ return true;
+ case MAVLINK_MSG_ID_VFR_HUD:
+ *periodicMessage = MAVLINK_PERIODIC_MESSAGE_VFR_HUD;
+ return true;
+ case MAVLINK_MSG_ID_BATTERY_STATUS:
+ *periodicMessage = MAVLINK_PERIODIC_MESSAGE_BATTERY_STATUS;
+ return true;
+ case MAVLINK_MSG_ID_SCALED_PRESSURE:
+ *periodicMessage = MAVLINK_PERIODIC_MESSAGE_SCALED_PRESSURE;
+ return true;
+ case MAVLINK_MSG_ID_SYSTEM_TIME:
+ *periodicMessage = MAVLINK_PERIODIC_MESSAGE_SYSTEM_TIME;
+ return true;
+ default:
+ return false;
+ }
+}
+
+static uint8_t mavlinkPeriodicMessageBaseStream(mavlinkPeriodicMessage_e periodicMessage)
+{
+ switch (periodicMessage) {
+ case MAVLINK_PERIODIC_MESSAGE_HEARTBEAT:
+ return MAV_DATA_STREAM_HEARTBEAT;
+ case MAVLINK_PERIODIC_MESSAGE_SYS_STATUS:
+ return MAV_DATA_STREAM_EXTENDED_STATUS;
+ case MAVLINK_PERIODIC_MESSAGE_EXTENDED_SYS_STATE:
+ return MAV_DATA_STREAM_EXTENDED_SYS_STATE;
+ case MAVLINK_PERIODIC_MESSAGE_RC_CHANNELS:
+ return MAV_DATA_STREAM_RC_CHANNELS;
+ case MAVLINK_PERIODIC_MESSAGE_GPS_RAW_INT:
+ case MAVLINK_PERIODIC_MESSAGE_GLOBAL_POSITION_INT:
+ case MAVLINK_PERIODIC_MESSAGE_GPS_GLOBAL_ORIGIN:
+ return MAV_DATA_STREAM_POSITION;
+ case MAVLINK_PERIODIC_MESSAGE_ATTITUDE:
+ return MAV_DATA_STREAM_EXTRA1;
+ case MAVLINK_PERIODIC_MESSAGE_VFR_HUD:
+ return MAV_DATA_STREAM_EXTRA2;
+ case MAVLINK_PERIODIC_MESSAGE_BATTERY_STATUS:
+ case MAVLINK_PERIODIC_MESSAGE_SCALED_PRESSURE:
+ case MAVLINK_PERIODIC_MESSAGE_SYSTEM_TIME:
+ return MAV_DATA_STREAM_EXTRA3;
+ default:
+ return MAV_DATA_STREAM_ALL;
+ }
+}
+
+static void mavlinkResetMessageSchedule(mavlinkPeriodicMessage_e periodicMessage)
+{
+ if (!mavActivePort) {
+ return;
+ }
+
+ mavActivePort->mavMessageNextDue[periodicMessage] = 0;
+}
+
+static void mavlinkResetMessagesForStream(uint8_t streamNum)
+{
+ if (!mavActivePort) {
+ return;
+ }
+
+ for (uint8_t messageIndex = 0; messageIndex < MAVLINK_PERIODIC_MESSAGE_COUNT; messageIndex++) {
+ if (mavlinkPeriodicMessageBaseStream((mavlinkPeriodicMessage_e)messageIndex) == streamNum) {
+ mavActivePort->mavMessageNextDue[messageIndex] = 0;
+ }
+ }
+}
+
+static int32_t mavlinkMessageBaseIntervalUs(mavlinkPeriodicMessage_e periodicMessage)
+{
+ if (!mavActivePort) {
+ return -1;
+ }
+
+ return mavlinkRateToIntervalUs(mavActivePort->mavRates[mavlinkPeriodicMessageBaseStream(periodicMessage)]);
+}
+
+static int32_t mavlinkMessageIntervalUs(mavlinkPeriodicMessage_e periodicMessage)
+{
+ if (!mavActivePort) {
+ return -1;
+ }
+
+ const int32_t overrideIntervalUs = mavActivePort->mavMessageOverrideIntervalsUs[periodicMessage];
+ if (overrideIntervalUs != 0) {
+ return overrideIntervalUs;
+ }
+
+ return mavlinkMessageBaseIntervalUs(periodicMessage);
+}
+
+static void mavlinkSetMessageOverrideIntervalUs(mavlinkPeriodicMessage_e periodicMessage, int32_t intervalUs)
+{
+ if (!mavActivePort) {
+ return;
+ }
+
+ mavActivePort->mavMessageOverrideIntervalsUs[periodicMessage] = intervalUs;
+ mavlinkResetMessageSchedule(periodicMessage);
+}
+
static int mavlinkStreamTrigger(enum MAV_DATA_STREAM streamNum, timeUs_t currentTimeUs)
{
if (!mavActivePort || streamNum >= MAXSTREAMS) {
@@ -317,20 +456,26 @@ static void mavlinkSetStreamRate(uint8_t streamNum, uint8_t rate)
}
mavActivePort->mavRates[streamNum] = mavlinkClampStreamRate(rate);
mavActivePort->mavStreamNextDue[streamNum] = 0;
+ mavlinkResetMessagesForStream(streamNum);
}
-static int32_t mavlinkStreamIntervalUs(uint8_t streamNum)
+static int mavlinkMessageTrigger(mavlinkPeriodicMessage_e periodicMessage, timeUs_t currentTimeUs)
{
- if (!mavActivePort || streamNum >= MAXSTREAMS) {
- return -1;
+ if (!mavActivePort) {
+ return 0;
}
- uint8_t rate = mavlinkClampStreamRate(mavActivePort->mavRates[streamNum]);
- if (rate == 0) {
- return -1;
+ const int32_t intervalUs = mavlinkMessageIntervalUs(periodicMessage);
+ if (intervalUs <= 0) {
+ return 0;
}
- return 1000000 / rate;
+ if ((mavActivePort->mavMessageNextDue[periodicMessage] == 0) || (cmpTimeUs(currentTimeUs, mavActivePort->mavMessageNextDue[periodicMessage]) >= 0)) {
+ mavActivePort->mavMessageNextDue[periodicMessage] = currentTimeUs + intervalUs;
+ return 1;
+ }
+
+ return 0;
}
static void configureMAVLinkStreamRates(uint8_t portIndex)
@@ -375,6 +520,8 @@ static void freeMAVLinkTelemetryPortByIndex(uint8_t portIndex)
state->txSeq = 0;
state->txDroppedFrames = 0;
memset(state->mavStreamNextDue, 0, sizeof(state->mavStreamNextDue));
+ memset(state->mavMessageOverrideIntervalsUs, 0, sizeof(state->mavMessageOverrideIntervalsUs));
+ memset(state->mavMessageNextDue, 0, sizeof(state->mavMessageNextDue));
memset(&state->mavRecvStatus, 0, sizeof(state->mavRecvStatus));
memset(&state->mavRecvMsg, 0, sizeof(state->mavRecvMsg));
resetMspPort(&mavTunnelMspPorts[portIndex], NULL);
@@ -448,6 +595,8 @@ static void configureMAVLinkTelemetryPort(uint8_t portIndex)
state->txSeq = 0;
state->txDroppedFrames = 0;
memset(state->mavStreamNextDue, 0, sizeof(state->mavStreamNextDue));
+ memset(state->mavMessageOverrideIntervalsUs, 0, sizeof(state->mavMessageOverrideIntervalsUs));
+ memset(state->mavMessageNextDue, 0, sizeof(state->mavMessageNextDue));
memset(&state->mavRecvStatus, 0, sizeof(state->mavRecvStatus));
memset(&state->mavRecvMsg, 0, sizeof(state->mavRecvMsg));
resetMspPort(&mavTunnelMspPorts[portIndex], NULL);
@@ -1301,7 +1450,7 @@ static void mavlinkSendHomePosition(void)
mavlinkSendMessage();
}
-void mavlinkSendPosition(timeUs_t currentTimeUs)
+static void mavlinkSendGpsRawInt(timeUs_t currentTimeUs)
{
uint8_t gpsFixType = 0;
@@ -1354,8 +1503,18 @@ void mavlinkSendPosition(timeUs_t currentTimeUs)
0);
mavlinkSendMessage();
+}
+
+static void mavlinkSendGlobalPositionInt(timeUs_t currentTimeUs)
+{
+ if (!(sensors(SENSOR_GPS)
+#ifdef USE_GPS_FIX_ESTIMATION
+ || STATE(GPS_ESTIMATED_FIX)
+#endif
+ )) {
+ return;
+ }
- // Global position
mavlink_msg_global_position_int_pack(mavSystemId, mavComponentId, &mavSendMsg,
// time_boot_ms Timestamp (milliseconds since system boot)
currentTimeUs / 1000,
@@ -1378,7 +1537,10 @@ void mavlinkSendPosition(timeUs_t currentTimeUs)
);
mavlinkSendMessage();
+}
+static void mavlinkSendGpsGlobalOrigin(void)
+{
mavlink_msg_gps_global_origin_pack(mavSystemId, mavComponentId, &mavSendMsg,
// latitude Latitude (WGS84), expressed as * 1E7
GPS_home.lat,
@@ -1392,6 +1554,13 @@ void mavlinkSendPosition(timeUs_t currentTimeUs)
mavlinkSendMessage();
}
+
+void mavlinkSendPosition(timeUs_t currentTimeUs)
+{
+ mavlinkSendGpsRawInt(currentTimeUs);
+ mavlinkSendGlobalPositionInt(currentTimeUs);
+ mavlinkSendGpsGlobalOrigin();
+}
#endif
void mavlinkSendAttitude(void)
@@ -1599,6 +1768,18 @@ static void mavlinkSendScaledPressure(void)
mavlinkSendMessage();
}
+static void mavlinkSendSystemTime(void)
+{
+ mavlink_msg_system_time_pack(
+ mavSystemId,
+ mavComponentId,
+ &mavSendMsg,
+ 0,
+ millis());
+
+ mavlinkSendMessage();
+}
+
static bool mavlinkSendStatusText(void)
{
// FIXME - Status text is limited to boards with USE_OSD
@@ -1828,38 +2009,58 @@ void processMAVLinkTelemetry(timeUs_t currentTimeUs)
}
// is executed @ TELEMETRY_MAVLINK_MAXRATE rate
- if (mavlinkStreamTrigger(MAV_DATA_STREAM_EXTENDED_STATUS, currentTimeUs)) {
+ if (mavlinkMessageTrigger(MAVLINK_PERIODIC_MESSAGE_SYS_STATUS, currentTimeUs)) {
mavlinkSendSystemStatus();
}
- if (mavlinkStreamTrigger(MAV_DATA_STREAM_RC_CHANNELS, currentTimeUs)) {
+ if (mavlinkMessageTrigger(MAVLINK_PERIODIC_MESSAGE_RC_CHANNELS, currentTimeUs)) {
mavlinkSendRCChannelsAndRSSI();
}
#ifdef USE_GPS
- if (mavlinkStreamTrigger(MAV_DATA_STREAM_POSITION, currentTimeUs)) {
- mavlinkSendPosition(currentTimeUs);
+ if (mavlinkMessageTrigger(MAVLINK_PERIODIC_MESSAGE_GPS_RAW_INT, currentTimeUs)) {
+ mavlinkSendGpsRawInt(currentTimeUs);
+ }
+
+ if (mavlinkMessageTrigger(MAVLINK_PERIODIC_MESSAGE_GLOBAL_POSITION_INT, currentTimeUs)) {
+ mavlinkSendGlobalPositionInt(currentTimeUs);
+ }
+
+ if (mavlinkMessageTrigger(MAVLINK_PERIODIC_MESSAGE_GPS_GLOBAL_ORIGIN, currentTimeUs)) {
+ mavlinkSendGpsGlobalOrigin();
}
#endif
- if (mavlinkStreamTrigger(MAV_DATA_STREAM_EXTRA1, currentTimeUs)) {
+ if (mavlinkMessageTrigger(MAVLINK_PERIODIC_MESSAGE_ATTITUDE, currentTimeUs)) {
mavlinkSendAttitude();
}
- if (mavlinkStreamTrigger(MAV_DATA_STREAM_EXTRA2, currentTimeUs)) {
+ if (mavlinkMessageTrigger(MAVLINK_PERIODIC_MESSAGE_VFR_HUD, currentTimeUs)) {
mavlinkSendVfrHud();
}
- if (mavlinkStreamTrigger(MAV_DATA_STREAM_HEARTBEAT, currentTimeUs)) {
+ if (mavlinkMessageTrigger(MAVLINK_PERIODIC_MESSAGE_HEARTBEAT, currentTimeUs)) {
mavlinkSendHeartbeat();
}
- if (mavlinkStreamTrigger(MAV_DATA_STREAM_EXTENDED_SYS_STATE, currentTimeUs)) {
+ if (mavlinkMessageTrigger(MAVLINK_PERIODIC_MESSAGE_EXTENDED_SYS_STATE, currentTimeUs)) {
mavlinkSendExtendedSysState();
}
+ if (mavlinkMessageTrigger(MAVLINK_PERIODIC_MESSAGE_BATTERY_STATUS, currentTimeUs)) {
+ mavlinkSendBatteryStatus();
+ }
+
+ if (mavlinkMessageTrigger(MAVLINK_PERIODIC_MESSAGE_SCALED_PRESSURE, currentTimeUs)) {
+ mavlinkSendScaledPressure();
+ }
+
+ if (mavlinkMessageTrigger(MAVLINK_PERIODIC_MESSAGE_SYSTEM_TIME, currentTimeUs)) {
+ mavlinkSendSystemTime();
+ }
+
if (mavlinkStreamTrigger(MAV_DATA_STREAM_EXTRA3, currentTimeUs)) {
- mavlinkSendBatteryTemperatureStatusText();
+ mavlinkSendStatusText();
}
}
@@ -2325,43 +2526,18 @@ static bool handleIncoming_MISSION_REQUEST(void)
return true;
}
-static bool mavlinkMessageToStream(uint16_t messageId, uint8_t *streamNum)
+static bool mavlinkIsLocalTarget(uint8_t targetSystem, uint8_t targetComponent)
{
- switch (messageId) {
- case MAVLINK_MSG_ID_HEARTBEAT:
- *streamNum = MAV_DATA_STREAM_HEARTBEAT;
- return true;
- case MAVLINK_MSG_ID_VFR_HUD:
- *streamNum = MAV_DATA_STREAM_EXTRA2;
- return true;
- case MAVLINK_MSG_ID_ATTITUDE:
- *streamNum = MAV_DATA_STREAM_EXTRA1;
- return true;
- case MAVLINK_MSG_ID_SYS_STATUS:
- *streamNum = MAV_DATA_STREAM_EXTENDED_STATUS;
- return true;
- case MAVLINK_MSG_ID_EXTENDED_SYS_STATE:
- *streamNum = MAV_DATA_STREAM_EXTENDED_SYS_STATE;
- return true;
- case MAVLINK_MSG_ID_RC_CHANNELS:
- case MAVLINK_MSG_ID_RC_CHANNELS_RAW:
- case MAVLINK_MSG_ID_RC_CHANNELS_SCALED:
- *streamNum = MAV_DATA_STREAM_RC_CHANNELS;
- return true;
- case MAVLINK_MSG_ID_GPS_RAW_INT:
- case MAVLINK_MSG_ID_GLOBAL_POSITION_INT:
- case MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN:
- *streamNum = MAV_DATA_STREAM_POSITION;
- return true;
- case MAVLINK_MSG_ID_BATTERY_STATUS:
- case MAVLINK_MSG_ID_SCALED_PRESSURE:
- *streamNum = MAV_DATA_STREAM_EXTRA3;
- return true;
- default:
- return false;
+ if (targetSystem != 0 && targetSystem != mavSystemId) {
+ return false;
+ }
+
+ if (targetComponent != 0 && targetComponent != mavComponentId) {
+ return false;
}
-}
+ return true;
+}
static void mavlinkSendCommandAck(uint16_t command, MAV_RESULT result, uint8_t ackTargetSystem, uint8_t ackTargetComponent)
{
@@ -2377,10 +2553,7 @@ static void mavlinkSendCommandAck(uint16_t command, MAV_RESULT result, uint8_t a
static bool handleIncoming_COMMAND(uint8_t targetSystem, uint8_t targetComponent, uint8_t ackTargetSystem, uint8_t ackTargetComponent, uint16_t command, uint8_t frame, float param1, float param2, float param3, float param4, float latitudeDeg, float longitudeDeg, float altitudeMeters)
{
- if (targetSystem != mavSystemId) {
- return false;
- }
- if (targetComponent != 0 && targetComponent != mavComponentId) {
+ if (!mavlinkIsLocalTarget(targetSystem, targetComponent)) {
return false;
}
UNUSED(param3);
@@ -2459,27 +2632,26 @@ static bool handleIncoming_COMMAND(uint8_t targetSystem, uint8_t targetComponent
}
case MAV_CMD_SET_MESSAGE_INTERVAL:
{
- uint8_t stream;
+ mavlinkPeriodicMessage_e periodicMessage;
MAV_RESULT result = MAV_RESULT_UNSUPPORTED;
- if (mavlinkMessageToStream((uint16_t)param1, &stream)) {
+ if (mavlinkPeriodicMessageFromMessageId((uint16_t)param1, &periodicMessage)) {
if (param2 == 0.0f) {
- mavlinkSetStreamRate(stream, mavActivePort->mavRatesConfigured[stream]);
+ mavlinkSetMessageOverrideIntervalUs(periodicMessage, 0);
result = MAV_RESULT_ACCEPTED;
} else if (param2 < 0.0f) {
- mavlinkSetStreamRate(stream, 0);
+ mavlinkSetMessageOverrideIntervalUs(periodicMessage, -1);
result = MAV_RESULT_ACCEPTED;
} else {
uint32_t intervalUs = (uint32_t)param2;
if (intervalUs > 0) {
- uint32_t rate = 1000000UL / intervalUs;
- if (rate > 0) {
- if (rate > TELEMETRY_MAVLINK_MAXRATE) {
- rate = TELEMETRY_MAVLINK_MAXRATE;
- }
- mavlinkSetStreamRate(stream, rate);
- result = MAV_RESULT_ACCEPTED;
+ const uint32_t minIntervalUs = 1000000UL / TELEMETRY_MAVLINK_MAXRATE;
+ if (intervalUs < minIntervalUs) {
+ intervalUs = minIntervalUs;
}
+
+ mavlinkSetMessageOverrideIntervalUs(periodicMessage, (int32_t)intervalUs);
+ result = MAV_RESULT_ACCEPTED;
}
}
}
@@ -2489,19 +2661,19 @@ static bool handleIncoming_COMMAND(uint8_t targetSystem, uint8_t targetComponent
}
case MAV_CMD_GET_MESSAGE_INTERVAL:
{
- uint8_t stream;
- if (!mavlinkMessageToStream((uint16_t)param1, &stream)) {
+ mavlinkPeriodicMessage_e periodicMessage;
+ if (!mavlinkPeriodicMessageFromMessageId((uint16_t)param1, &periodicMessage)) {
mavlinkSendCommandAck(command, MAV_RESULT_UNSUPPORTED, ackTargetSystem, ackTargetComponent);
return true;
}
- mavlink_msg_message_interval_pack(
- mavSystemId,
- mavComponentId,
- &mavSendMsg,
- (uint16_t)param1,
- mavlinkStreamIntervalUs(stream));
- mavlinkSendMessage();
+ mavlink_msg_message_interval_pack(
+ mavSystemId,
+ mavComponentId,
+ &mavSendMsg,
+ (uint16_t)param1,
+ mavlinkMessageIntervalUs(periodicMessage));
+ mavlinkSendMessage();
mavlinkSendCommandAck(command, MAV_RESULT_ACCEPTED, ackTargetSystem, ackTargetComponent);
return true;
@@ -2610,10 +2782,20 @@ static bool handleIncoming_COMMAND(uint8_t targetSystem, uint8_t targetComponent
sent = true;
break;
case MAVLINK_MSG_ID_GPS_RAW_INT:
+ #ifdef USE_GPS
+ mavlinkSendGpsRawInt(micros());
+ sent = true;
+ #endif
+ break;
case MAVLINK_MSG_ID_GLOBAL_POSITION_INT:
+ #ifdef USE_GPS
+ mavlinkSendGlobalPositionInt(micros());
+ sent = true;
+ #endif
+ break;
case MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN:
#ifdef USE_GPS
- mavlinkSendPosition(micros());
+ mavlinkSendGpsGlobalOrigin();
sent = true;
#endif
break;
@@ -2625,6 +2807,10 @@ static bool handleIncoming_COMMAND(uint8_t targetSystem, uint8_t targetComponent
mavlinkSendScaledPressure();
sent = true;
break;
+ case MAVLINK_MSG_ID_SYSTEM_TIME:
+ mavlinkSendSystemTime();
+ sent = true;
+ break;
case MAVLINK_MSG_ID_STATUSTEXT:
sent = mavlinkSendStatusText();
break;
@@ -2747,10 +2933,7 @@ static bool handleIncoming_REQUEST_DATA_STREAM(void)
mavlink_request_data_stream_t msg;
mavlink_msg_request_data_stream_decode(&mavRecvMsg, &msg);
- if (msg.target_system != mavSystemId) {
- return false;
- }
- if (msg.target_component != 0 && msg.target_component != mavComponentId) {
+ if (!mavlinkIsLocalTarget(msg.target_system, msg.target_component)) {
return false;
}
@@ -2782,10 +2965,7 @@ static bool handleIncoming_SET_POSITION_TARGET_GLOBAL_INT(void)
mavlink_set_position_target_global_int_t msg;
mavlink_msg_set_position_target_global_int_decode(&mavRecvMsg, &msg);
- if (msg.target_system != mavSystemId) {
- return false;
- }
- if (msg.target_component != 0 && msg.target_component != mavComponentId) {
+ if (!mavlinkIsLocalTarget(msg.target_system, msg.target_component)) {
return false;
}
@@ -2837,10 +3017,7 @@ static bool handleIncoming_SET_POSITION_TARGET_LOCAL_NED(void)
mavlink_set_position_target_local_ned_t msg;
mavlink_msg_set_position_target_local_ned_decode(&mavRecvMsg, &msg);
- if (msg.target_system != mavSystemId) {
- return false;
- }
- if (msg.target_component != 0 && msg.target_component != mavComponentId) {
+ if (!mavlinkIsLocalTarget(msg.target_system, msg.target_component)) {
return false;
}
@@ -2880,7 +3057,7 @@ static bool handleIncoming_PARAM_REQUEST_LIST(void) {
mavlink_msg_param_request_list_decode(&mavRecvMsg, &msg);
// Respond that we don't have any parameters to force Mission Planner to give up quickly
- if (msg.target_system == mavSystemId) {
+ if (mavlinkIsLocalTarget(msg.target_system, msg.target_component)) {
// mavlink_msg_param_value_pack(system_id, component_id, msg, param_value->param_id, param_value->param_value, param_value->param_type, param_value->param_count, param_value->param_index);
mavlink_msg_param_value_pack(mavSystemId, mavComponentId, &mavSendMsg, 0, 0, 0, 0, 0);
mavlinkSendMessage();
@@ -2975,19 +3152,7 @@ static bool handleIncoming_ADSB_VEHICLE(void) {
static bool mavlinkIsFromLocalIdentity(uint8_t sysid, uint8_t compid)
{
- const uint8_t localSystemId = mavlinkGetCommonConfig()->sysid;
- if (sysid != localSystemId) {
- return false;
- }
-
- for (uint8_t portIndex = 0; portIndex < mavPortCount; portIndex++) {
- const mavlinkTelemetryPortConfig_t *cfg = mavlinkGetPortConfig(portIndex);
- if (cfg->compid == compid) {
- return true;
- }
- }
-
- return false;
+ return sysid == mavlinkGetCommonConfig()->sysid && compid == MAV_COMP_ID_AUTOPILOT1;
}
static void mavlinkLearnRoute(uint8_t ingressPortIndex)
@@ -3117,21 +3282,15 @@ static int8_t mavlinkResolveLocalPortForTarget(int16_t targetSystem, int16_t tar
return -1;
}
- if (ingressPortIndex < mavPortCount) {
- const mavlinkTelemetryPortConfig_t *ingressCfg = mavlinkGetPortConfig(ingressPortIndex);
- if (targetComponent <= 0 || ingressCfg->compid == targetComponent) {
- return ingressPortIndex;
- }
+ if (targetComponent > 0 && (uint8_t)targetComponent != MAV_COMP_ID_AUTOPILOT1) {
+ return -1;
}
- for (uint8_t portIndex = 0; portIndex < mavPortCount; portIndex++) {
- const mavlinkTelemetryPortConfig_t *cfg = mavlinkGetPortConfig(portIndex);
- if (targetComponent <= 0 || cfg->compid == targetComponent) {
- return portIndex;
- }
+ if (ingressPortIndex < mavPortCount) {
+ return ingressPortIndex;
}
- return -1;
+ return mavPortCount > 0 ? 0 : -1;
}
static bool mavlinkShouldFanOutLocalBroadcast(const mavlink_message_t *msg)
diff --git a/src/main/telemetry/mavlink.h b/src/main/telemetry/mavlink.h
index 38aface2d5f..c732f6c3fff 100755
--- a/src/main/telemetry/mavlink.h
+++ b/src/main/telemetry/mavlink.h
@@ -45,6 +45,22 @@
#define MAVLINK_PORT_MASK(portIndex) (1U << (portIndex))
#define MAXSTREAMS MAVLINK_STREAM_COUNT
+typedef enum {
+ MAVLINK_PERIODIC_MESSAGE_HEARTBEAT,
+ MAVLINK_PERIODIC_MESSAGE_SYS_STATUS,
+ MAVLINK_PERIODIC_MESSAGE_EXTENDED_SYS_STATE,
+ MAVLINK_PERIODIC_MESSAGE_RC_CHANNELS,
+ MAVLINK_PERIODIC_MESSAGE_GPS_RAW_INT,
+ MAVLINK_PERIODIC_MESSAGE_GLOBAL_POSITION_INT,
+ MAVLINK_PERIODIC_MESSAGE_GPS_GLOBAL_ORIGIN,
+ MAVLINK_PERIODIC_MESSAGE_ATTITUDE,
+ MAVLINK_PERIODIC_MESSAGE_VFR_HUD,
+ MAVLINK_PERIODIC_MESSAGE_BATTERY_STATUS,
+ MAVLINK_PERIODIC_MESSAGE_SCALED_PRESSURE,
+ MAVLINK_PERIODIC_MESSAGE_SYSTEM_TIME,
+ MAVLINK_PERIODIC_MESSAGE_COUNT
+} mavlinkPeriodicMessage_e;
+
typedef enum {
MAV_FRAME_SUPPORTED_NONE = 0,
MAV_FRAME_SUPPORTED_GLOBAL = (1 << 0),
@@ -142,6 +158,8 @@ typedef struct mavlinkPortRuntime_s {
uint8_t mavRates[MAVLINK_STREAM_COUNT];
uint8_t mavRatesConfigured[MAVLINK_STREAM_COUNT];
timeUs_t mavStreamNextDue[MAVLINK_STREAM_COUNT];
+ int32_t mavMessageOverrideIntervalsUs[MAVLINK_PERIODIC_MESSAGE_COUNT];
+ timeUs_t mavMessageNextDue[MAVLINK_PERIODIC_MESSAGE_COUNT];
uint8_t txSeq;
uint32_t txDroppedFrames;
mavlink_message_t mavRecvMsg;
diff --git a/src/main/telemetry/telemetry.c b/src/main/telemetry/telemetry.c
index dba8709e6e9..4288b213bc1 100644
--- a/src/main/telemetry/telemetry.c
+++ b/src/main/telemetry/telemetry.c
@@ -102,7 +102,6 @@ PG_RESET_TEMPLATE(telemetryConfig_t, telemetryConfig,
.extra3_rate = SETTING_MAVLINK_PORT1_EXTRA3_RATE_DEFAULT,
.min_txbuff = SETTING_MAVLINK_PORT1_MIN_TXBUFFER_DEFAULT,
.radio_type = SETTING_MAVLINK_PORT1_RADIO_TYPE_DEFAULT,
- .compid = SETTING_MAVLINK_PORT1_COMPID_DEFAULT,
.high_latency = SETTING_MAVLINK_PORT1_HIGH_LATENCY_DEFAULT
},
{
@@ -114,7 +113,6 @@ PG_RESET_TEMPLATE(telemetryConfig_t, telemetryConfig,
.extra3_rate = 0,
.min_txbuff = SETTING_MAVLINK_PORT2_MIN_TXBUFFER_DEFAULT,
.radio_type = SETTING_MAVLINK_PORT2_RADIO_TYPE_DEFAULT,
- .compid = SETTING_MAVLINK_PORT2_COMPID_DEFAULT,
.high_latency = SETTING_MAVLINK_PORT2_HIGH_LATENCY_DEFAULT
},
{
@@ -126,7 +124,6 @@ PG_RESET_TEMPLATE(telemetryConfig_t, telemetryConfig,
.extra3_rate = 0,
.min_txbuff = SETTING_MAVLINK_PORT3_MIN_TXBUFFER_DEFAULT,
.radio_type = SETTING_MAVLINK_PORT3_RADIO_TYPE_DEFAULT,
- .compid = SETTING_MAVLINK_PORT3_COMPID_DEFAULT,
.high_latency = SETTING_MAVLINK_PORT3_HIGH_LATENCY_DEFAULT
},
{
@@ -138,7 +135,6 @@ PG_RESET_TEMPLATE(telemetryConfig_t, telemetryConfig,
.extra3_rate = 0,
.min_txbuff = SETTING_MAVLINK_PORT4_MIN_TXBUFFER_DEFAULT,
.radio_type = SETTING_MAVLINK_PORT4_RADIO_TYPE_DEFAULT,
- .compid = SETTING_MAVLINK_PORT4_COMPID_DEFAULT,
.high_latency = SETTING_MAVLINK_PORT4_HIGH_LATENCY_DEFAULT
}
}
diff --git a/src/main/telemetry/telemetry.h b/src/main/telemetry/telemetry.h
index f2686c5dcac..9b1f0a6bca0 100644
--- a/src/main/telemetry/telemetry.h
+++ b/src/main/telemetry/telemetry.h
@@ -70,7 +70,6 @@ typedef struct mavlinkTelemetryPortConfig_s {
uint8_t extra3_rate;
uint8_t min_txbuff;
uint8_t radio_type;
- uint8_t compid;
bool high_latency;
} mavlinkTelemetryPortConfig_t;
diff --git a/src/test/unit/mavlink_unittest.cc b/src/test/unit/mavlink_unittest.cc
index a60b72357b2..7b579dcfa9f 100644
--- a/src/test/unit/mavlink_unittest.cc
+++ b/src/test/unit/mavlink_unittest.cc
@@ -221,6 +221,22 @@ static bool popTxMessage(mavlink_message_t *msg)
return false;
}
+static bool findTxMessageById(uint32_t msgid, mavlink_message_t *match)
+{
+ mavlink_status_t status;
+ memset(&status, 0, sizeof(status));
+
+ mavlink_message_t msg;
+ for (size_t i = 0; i < serialTxLen; i++) {
+ if (mavlink_parse_char(0, serialTxBuffer[i], &msg, &status) == MAVLINK_FRAMING_OK && msg.msgid == msgid) {
+ *match = msg;
+ return true;
+ }
+ }
+
+ return false;
+}
+
static std::vector parseTxMessages(void)
{
std::vector messages;
@@ -287,8 +303,13 @@ static void initMavlinkTestState(void)
telemetryConfigMutable()->mavlink_common.sysid = 1;
telemetryConfigMutable()->mavlink_common.autopilot_type = MAVLINK_AUTOPILOT_ARDUPILOT;
telemetryConfigMutable()->mavlink_common.version = 2;
+ telemetryConfigMutable()->mavlink[0].extended_status_rate = 2;
+ telemetryConfigMutable()->mavlink[0].rc_channels_rate = 1;
+ telemetryConfigMutable()->mavlink[0].position_rate = 2;
+ telemetryConfigMutable()->mavlink[0].extra1_rate = 2;
+ telemetryConfigMutable()->mavlink[0].extra2_rate = 2;
+ telemetryConfigMutable()->mavlink[0].extra3_rate = 1;
telemetryConfigMutable()->mavlink[0].min_txbuff = 0;
- telemetryConfigMutable()->mavlink[0].compid = MAV_COMP_ID_AUTOPILOT1;
telemetryConfigMutable()->halfDuplex = 0;
rxConfigMutable()->receiverType = RX_TYPE_NONE;
@@ -455,6 +476,60 @@ TEST(MavlinkTelemetryTest, CommandLongRepositionUsesGlobalFrameAndParams)
EXPECT_EQ(lastWaypoint.p1, 123);
}
+TEST(MavlinkTelemetryTest, BroadcastCommandLongRepositionExecutesLocally)
+{
+ initMavlinkTestState();
+
+ mavlink_message_t cmd;
+ mavlink_msg_command_long_pack(
+ 42, 200, &cmd,
+ 0, 0,
+ MAV_CMD_DO_REPOSITION,
+ 0,
+ 0, 0, 0, 123.4f,
+ 37.5f, -122.25f, 12.3f);
+
+ pushRxMessage(&cmd);
+ handleMAVLinkTelemetry(1000);
+
+ mavlink_message_t ackMsg;
+ ASSERT_TRUE(findTxMessageById(MAVLINK_MSG_ID_COMMAND_ACK, &ackMsg));
+
+ mavlink_command_ack_t ack;
+ mavlink_msg_command_ack_decode(&ackMsg, &ack);
+
+ EXPECT_EQ(ack.command, MAV_CMD_DO_REPOSITION);
+ EXPECT_EQ(ack.result, MAV_RESULT_ACCEPTED);
+ EXPECT_EQ(setWaypointCalls, 1);
+}
+
+TEST(MavlinkTelemetryTest, SameSystemDifferentComponentIsNotDroppedAsLocalIdentity)
+{
+ initMavlinkTestState();
+
+ mavlink_message_t cmd;
+ mavlink_msg_command_long_pack(
+ 1, 42, &cmd,
+ 1, testTargetComponent,
+ MAV_CMD_DO_REPOSITION,
+ 0,
+ 0, 0, 0, 0,
+ 37.5f, -122.25f, 12.3f);
+
+ pushRxMessage(&cmd);
+ handleMAVLinkTelemetry(1000);
+
+ mavlink_message_t ackMsg;
+ ASSERT_TRUE(findTxMessageById(MAVLINK_MSG_ID_COMMAND_ACK, &ackMsg));
+
+ mavlink_command_ack_t ack;
+ mavlink_msg_command_ack_decode(&ackMsg, &ack);
+
+ EXPECT_EQ(ack.command, MAV_CMD_DO_REPOSITION);
+ EXPECT_EQ(ack.result, MAV_RESULT_ACCEPTED);
+ EXPECT_EQ(setWaypointCalls, 1);
+}
+
TEST(MavlinkTelemetryTest, CommandIntUnsupportedFrameIsRejected)
{
initMavlinkTestState();
@@ -876,6 +951,28 @@ TEST(MavlinkTelemetryTest, ParamRequestListRespondsWithEmptyParam)
EXPECT_EQ(param.param_index, 0);
}
+TEST(MavlinkTelemetryTest, BroadcastParamRequestListRespondsWithEmptyParam)
+{
+ initMavlinkTestState();
+
+ mavlink_message_t msg;
+ mavlink_msg_param_request_list_pack(
+ 42, 200, &msg,
+ 0, 0);
+
+ pushRxMessage(&msg);
+ handleMAVLinkTelemetry(1000);
+
+ mavlink_message_t paramMsg;
+ ASSERT_TRUE(findTxMessageById(MAVLINK_MSG_ID_PARAM_VALUE, ¶mMsg));
+
+ mavlink_param_value_t param;
+ mavlink_msg_param_value_decode(¶mMsg, ¶m);
+
+ EXPECT_EQ(param.param_count, 0);
+ EXPECT_EQ(param.param_index, 0);
+}
+
TEST(MavlinkTelemetryTest, SetPositionTargetGlobalIntSetsWaypoint)
{
initMavlinkTestState();
@@ -898,6 +995,26 @@ TEST(MavlinkTelemetryTest, SetPositionTargetGlobalIntSetsWaypoint)
EXPECT_EQ(lastWaypoint.p3, 0);
}
+TEST(MavlinkTelemetryTest, BroadcastSetPositionTargetGlobalIntSetsWaypoint)
+{
+ initMavlinkTestState();
+
+ mavlink_message_t msg;
+ mavlink_msg_set_position_target_global_int_pack(
+ 42, 200, &msg,
+ 0, 0, 0,
+ MAV_FRAME_GLOBAL_RELATIVE_ALT_INT, 0,
+ 375000000, -1222500000, 12.3f,
+ 0, 0, 0, 0, 0, 0, 0, 0);
+
+ pushRxMessage(&msg);
+ handleMAVLinkTelemetry(1000);
+
+ EXPECT_EQ(setWaypointCalls, 1);
+ EXPECT_EQ(lastWaypoint.lat, 375000000);
+ EXPECT_EQ(lastWaypoint.lon, -1222500000);
+}
+
TEST(MavlinkTelemetryTest, SetPositionTargetGlobalIntUsesAbsoluteAltitude)
{
initMavlinkTestState();
@@ -977,6 +1094,36 @@ TEST(MavlinkTelemetryTest, SetPositionTargetLocalNedAltitudeOnlySetsAltitudeTarg
EXPECT_EQ(lastAltitudeTargetCm, 1250);
}
+TEST(MavlinkTelemetryTest, BroadcastSetPositionTargetLocalNedAltitudeOnlySetsAltitudeTarget)
+{
+ initMavlinkTestState();
+ estimatedPosition[Z] = 1000.0f;
+
+ mavlink_message_t msg;
+ mavlink_msg_set_position_target_local_ned_pack(
+ 42, 200, &msg,
+ 0, 0, 0,
+ MAV_FRAME_LOCAL_OFFSET_NED,
+ POSITION_TARGET_TYPEMASK_X_IGNORE |
+ POSITION_TARGET_TYPEMASK_Y_IGNORE |
+ POSITION_TARGET_TYPEMASK_VX_IGNORE |
+ POSITION_TARGET_TYPEMASK_VY_IGNORE |
+ POSITION_TARGET_TYPEMASK_VZ_IGNORE |
+ POSITION_TARGET_TYPEMASK_AX_IGNORE |
+ POSITION_TARGET_TYPEMASK_AY_IGNORE |
+ POSITION_TARGET_TYPEMASK_AZ_IGNORE |
+ POSITION_TARGET_TYPEMASK_YAW_IGNORE |
+ POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE,
+ 0.0f, 0.0f, -2.5f,
+ 0, 0, 0, 0, 0, 0, 0, 0);
+
+ pushRxMessage(&msg);
+ handleMAVLinkTelemetry(1000);
+
+ EXPECT_EQ(altitudeTargetSetCalls, 1);
+ EXPECT_EQ(lastAltitudeTargetCm, 1250);
+}
+
TEST(MavlinkTelemetryTest, SetPositionTargetLocalNedIgnoresXyMotionRequests)
{
initMavlinkTestState();
@@ -1066,6 +1213,212 @@ TEST(MavlinkTelemetryTest, RequestDataStreamStopsStream)
EXPECT_EQ(interval.interval_us, -1);
}
+TEST(MavlinkTelemetryTest, BroadcastRequestDataStreamAdjustsBaseInterval)
+{
+ initMavlinkTestState();
+
+ mavlink_message_t setMsg;
+ mavlink_msg_request_data_stream_pack(
+ 42, 200, &setMsg,
+ 0, 0,
+ MAV_DATA_STREAM_RC_CHANNELS, 10, 1);
+
+ pushRxMessage(&setMsg);
+ handleMAVLinkTelemetry(1000);
+
+ serialTxLen = 0;
+
+ mavlink_message_t getMsg;
+ mavlink_msg_command_long_pack(
+ 42, 200, &getMsg,
+ 1, testTargetComponent,
+ MAV_CMD_GET_MESSAGE_INTERVAL,
+ 0,
+ (float)MAVLINK_MSG_ID_RC_CHANNELS,
+ 0, 0, 0, 0, 0, 0);
+
+ pushRxMessage(&getMsg);
+ handleMAVLinkTelemetry(1000);
+
+ mavlink_message_t intervalMsg;
+ ASSERT_TRUE(findTxMessageById(MAVLINK_MSG_ID_MESSAGE_INTERVAL, &intervalMsg));
+
+ mavlink_message_interval_t interval;
+ mavlink_msg_message_interval_decode(&intervalMsg, &interval);
+
+ EXPECT_EQ(interval.message_id, MAVLINK_MSG_ID_RC_CHANNELS);
+ EXPECT_EQ(interval.interval_us, 100000);
+}
+
+TEST(MavlinkTelemetryTest, SetMessageIntervalOverridesOnlyRequestedPositionMessage)
+{
+ initMavlinkTestState();
+
+ mavlink_message_t setMsg;
+ mavlink_msg_command_long_pack(
+ 42, 200, &setMsg,
+ 1, testTargetComponent,
+ MAV_CMD_SET_MESSAGE_INTERVAL,
+ 0,
+ (float)MAVLINK_MSG_ID_GLOBAL_POSITION_INT,
+ 200000.0f, 0, 0, 0, 0, 0);
+
+ pushRxMessage(&setMsg);
+ handleMAVLinkTelemetry(1000);
+
+ const uint16_t messageIds[] = {
+ MAVLINK_MSG_ID_GLOBAL_POSITION_INT,
+ MAVLINK_MSG_ID_GPS_RAW_INT,
+ MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN
+ };
+ const int32_t expectedIntervals[] = {
+ 200000,
+ 500000,
+ 500000
+ };
+
+ for (size_t i = 0; i < ARRAYLEN(messageIds); i++) {
+ serialTxLen = 0;
+
+ mavlink_message_t getMsg;
+ mavlink_msg_command_long_pack(
+ 42, 200, &getMsg,
+ 1, testTargetComponent,
+ MAV_CMD_GET_MESSAGE_INTERVAL,
+ 0,
+ (float)messageIds[i],
+ 0, 0, 0, 0, 0, 0);
+
+ pushRxMessage(&getMsg);
+ handleMAVLinkTelemetry(1000);
+
+ mavlink_message_t intervalMsg;
+ ASSERT_TRUE(findTxMessageById(MAVLINK_MSG_ID_MESSAGE_INTERVAL, &intervalMsg));
+
+ mavlink_message_interval_t interval;
+ mavlink_msg_message_interval_decode(&intervalMsg, &interval);
+
+ EXPECT_EQ(interval.message_id, messageIds[i]);
+ EXPECT_EQ(interval.interval_us, expectedIntervals[i]);
+ }
+}
+
+TEST(MavlinkTelemetryTest, SetMessageIntervalCanDisableBatteryStatusWithoutAffectingScaledPressure)
+{
+ initMavlinkTestState();
+
+ mavlink_message_t setMsg;
+ mavlink_msg_command_long_pack(
+ 42, 200, &setMsg,
+ 1, testTargetComponent,
+ MAV_CMD_SET_MESSAGE_INTERVAL,
+ 0,
+ (float)MAVLINK_MSG_ID_BATTERY_STATUS,
+ -1.0f, 0, 0, 0, 0, 0);
+
+ pushRxMessage(&setMsg);
+ handleMAVLinkTelemetry(1000);
+
+ const uint16_t messageIds[] = {
+ MAVLINK_MSG_ID_BATTERY_STATUS,
+ MAVLINK_MSG_ID_SCALED_PRESSURE
+ };
+ const int32_t expectedIntervals[] = {
+ -1,
+ 1000000
+ };
+
+ for (size_t i = 0; i < ARRAYLEN(messageIds); i++) {
+ serialTxLen = 0;
+
+ mavlink_message_t getMsg;
+ mavlink_msg_command_long_pack(
+ 42, 200, &getMsg,
+ 1, testTargetComponent,
+ MAV_CMD_GET_MESSAGE_INTERVAL,
+ 0,
+ (float)messageIds[i],
+ 0, 0, 0, 0, 0, 0);
+
+ pushRxMessage(&getMsg);
+ handleMAVLinkTelemetry(1000);
+
+ mavlink_message_t intervalMsg;
+ ASSERT_TRUE(findTxMessageById(MAVLINK_MSG_ID_MESSAGE_INTERVAL, &intervalMsg));
+
+ mavlink_message_interval_t interval;
+ mavlink_msg_message_interval_decode(&intervalMsg, &interval);
+
+ EXPECT_EQ(interval.message_id, messageIds[i]);
+ EXPECT_EQ(interval.interval_us, expectedIntervals[i]);
+ }
+}
+
+TEST(MavlinkTelemetryTest, SetMessageIntervalResetRevertsToCurrentGroupInterval)
+{
+ initMavlinkTestState();
+
+ mavlink_message_t streamMsg;
+ mavlink_msg_request_data_stream_pack(
+ 42, 200, &streamMsg,
+ 1, testTargetComponent,
+ MAV_DATA_STREAM_POSITION, 10, 1);
+
+ pushRxMessage(&streamMsg);
+ handleMAVLinkTelemetry(1000);
+
+ serialTxLen = 0;
+
+ mavlink_message_t setMsg;
+ mavlink_msg_command_long_pack(
+ 42, 200, &setMsg,
+ 1, testTargetComponent,
+ MAV_CMD_SET_MESSAGE_INTERVAL,
+ 0,
+ (float)MAVLINK_MSG_ID_GLOBAL_POSITION_INT,
+ 250000.0f, 0, 0, 0, 0, 0);
+
+ pushRxMessage(&setMsg);
+ handleMAVLinkTelemetry(1000);
+
+ serialTxLen = 0;
+
+ mavlink_message_t clearMsg;
+ mavlink_msg_command_long_pack(
+ 42, 200, &clearMsg,
+ 1, testTargetComponent,
+ MAV_CMD_SET_MESSAGE_INTERVAL,
+ 0,
+ (float)MAVLINK_MSG_ID_GLOBAL_POSITION_INT,
+ 0.0f, 0, 0, 0, 0, 0);
+
+ pushRxMessage(&clearMsg);
+ handleMAVLinkTelemetry(1000);
+
+ serialTxLen = 0;
+
+ mavlink_message_t getMsg;
+ mavlink_msg_command_long_pack(
+ 42, 200, &getMsg,
+ 1, testTargetComponent,
+ MAV_CMD_GET_MESSAGE_INTERVAL,
+ 0,
+ (float)MAVLINK_MSG_ID_GLOBAL_POSITION_INT,
+ 0, 0, 0, 0, 0, 0);
+
+ pushRxMessage(&getMsg);
+ handleMAVLinkTelemetry(1000);
+
+ mavlink_message_t intervalMsg;
+ ASSERT_TRUE(findTxMessageById(MAVLINK_MSG_ID_MESSAGE_INTERVAL, &intervalMsg));
+
+ mavlink_message_interval_t interval;
+ mavlink_msg_message_interval_decode(&intervalMsg, &interval);
+
+ EXPECT_EQ(interval.message_id, MAVLINK_MSG_ID_GLOBAL_POSITION_INT);
+ EXPECT_EQ(interval.interval_us, 100000);
+}
+
TEST(MavlinkTelemetryTest, HeartbeatIntervalIsIndependentFromExtra2Stream)
{
initMavlinkTestState();
@@ -1131,6 +1484,63 @@ TEST(MavlinkTelemetryTest, RequestProtocolVersionUsesConfiguredVersion)
EXPECT_EQ(version.max_version, 200);
}
+TEST(MavlinkTelemetryTest, SystemTimeSupportsRequestPeriodicOutputAndIntervalQuery)
+{
+ initMavlinkTestState();
+ fakeMillis = 1234;
+
+ mavlink_message_t requestMsg;
+ mavlink_msg_command_long_pack(
+ 42, 200, &requestMsg,
+ 1, testTargetComponent,
+ MAV_CMD_REQUEST_MESSAGE,
+ 0,
+ (float)MAVLINK_MSG_ID_SYSTEM_TIME,
+ 0, 0, 0, 0, 0, 0);
+
+ pushRxMessage(&requestMsg);
+ handleMAVLinkTelemetry(1000);
+
+ mavlink_message_t systemTimeMsg;
+ ASSERT_TRUE(findTxMessageById(MAVLINK_MSG_ID_SYSTEM_TIME, &systemTimeMsg));
+
+ mavlink_system_time_t systemTime;
+ mavlink_msg_system_time_decode(&systemTimeMsg, &systemTime);
+
+ EXPECT_EQ(systemTime.time_unix_usec, 0U);
+ EXPECT_EQ(systemTime.time_boot_ms, 1234U);
+
+ serialTxLen = 0;
+ handleMAVLinkTelemetry(1000000);
+
+ ASSERT_TRUE(findTxMessageById(MAVLINK_MSG_ID_SYSTEM_TIME, &systemTimeMsg));
+ mavlink_msg_system_time_decode(&systemTimeMsg, &systemTime);
+ EXPECT_EQ(systemTime.time_boot_ms, 1234U);
+
+ serialTxLen = 0;
+
+ mavlink_message_t getMsg;
+ mavlink_msg_command_long_pack(
+ 42, 200, &getMsg,
+ 1, testTargetComponent,
+ MAV_CMD_GET_MESSAGE_INTERVAL,
+ 0,
+ (float)MAVLINK_MSG_ID_SYSTEM_TIME,
+ 0, 0, 0, 0, 0, 0);
+
+ pushRxMessage(&getMsg);
+ handleMAVLinkTelemetry(1000);
+
+ mavlink_message_t intervalMsg;
+ ASSERT_TRUE(findTxMessageById(MAVLINK_MSG_ID_MESSAGE_INTERVAL, &intervalMsg));
+
+ mavlink_message_interval_t interval;
+ mavlink_msg_message_interval_decode(&intervalMsg, &interval);
+
+ EXPECT_EQ(interval.message_id, MAVLINK_MSG_ID_SYSTEM_TIME);
+ EXPECT_EQ(interval.interval_us, 1000000);
+}
+
TEST(MavlinkTelemetryTest, RequestAutopilotCapabilitiesReportsLocalNedCapabilityAndPackedVersion)
{
initMavlinkTestState();
From 64c268048e1074bba371c07e2e971fbdbce78a53 Mon Sep 17 00:00:00 2001
From: frogmane <7685285+xznhj8129@users.noreply.github.com>
Date: Fri, 3 Apr 2026 17:38:21 -0400
Subject: [PATCH 34/46] Refactor MAVLink runtime split
---
src/main/CMakeLists.txt | 12 +
src/main/fc/fc_mavlink.c | 2553 ++++++++++++++++++++
src/main/fc/fc_mavlink.h | 29 +
src/main/mavlink/mavlink_internal.h | 131 +
src/main/mavlink/mavlink_ports.c | 73 +
src/main/mavlink/mavlink_ports.h | 4 +
src/main/mavlink/mavlink_routing.c | 172 ++
src/main/mavlink/mavlink_routing.h | 13 +
src/main/mavlink/mavlink_runtime.c | 281 +++
src/main/mavlink/mavlink_runtime.h | 16 +
src/main/mavlink/mavlink_streams.c | 309 +++
src/main/mavlink/mavlink_streams.h | 20 +
src/main/telemetry/mavlink.c | 3452 +--------------------------
src/test/unit/CMakeLists.txt | 3 +-
src/test/unit/mavlink_unittest.cc | 2 +
15 files changed, 3624 insertions(+), 3446 deletions(-)
create mode 100644 src/main/fc/fc_mavlink.c
create mode 100644 src/main/fc/fc_mavlink.h
create mode 100644 src/main/mavlink/mavlink_internal.h
create mode 100644 src/main/mavlink/mavlink_ports.c
create mode 100644 src/main/mavlink/mavlink_ports.h
create mode 100644 src/main/mavlink/mavlink_routing.c
create mode 100644 src/main/mavlink/mavlink_routing.h
create mode 100644 src/main/mavlink/mavlink_runtime.c
create mode 100644 src/main/mavlink/mavlink_runtime.h
create mode 100644 src/main/mavlink/mavlink_streams.c
create mode 100644 src/main/mavlink/mavlink_streams.h
diff --git a/src/main/CMakeLists.txt b/src/main/CMakeLists.txt
index 101c7223372..26ca5b952c6 100755
--- a/src/main/CMakeLists.txt
+++ b/src/main/CMakeLists.txt
@@ -290,6 +290,8 @@ main_sources(COMMON_SRC
fc/fc_tasks.c
fc/fc_tasks.h
fc/fc_hardfaults.c
+ fc/fc_mavlink.c
+ fc/fc_mavlink.h
fc/fc_msp.c
fc/fc_msp.h
fc/fc_msp_box.c
@@ -391,6 +393,16 @@ main_sources(COMMON_SRC
io/osd/custom_elements.c
+ mavlink/mavlink_internal.h
+ mavlink/mavlink_ports.c
+ mavlink/mavlink_ports.h
+ mavlink/mavlink_routing.c
+ mavlink/mavlink_routing.h
+ mavlink/mavlink_runtime.c
+ mavlink/mavlink_runtime.h
+ mavlink/mavlink_streams.c
+ mavlink/mavlink_streams.h
+
msp/msp_serial.c
msp/msp_serial.h
diff --git a/src/main/fc/fc_mavlink.c b/src/main/fc/fc_mavlink.c
new file mode 100644
index 00000000000..bd7f31eed5e
--- /dev/null
+++ b/src/main/fc/fc_mavlink.c
@@ -0,0 +1,2553 @@
+#include "mavlink/mavlink_internal.h"
+
+#include "fc/fc_mavlink.h"
+
+#include "mavlink/mavlink_runtime.h"
+#include "mavlink/mavlink_streams.h"
+
+#if defined(USE_TELEMETRY) && defined(USE_TELEMETRY_MAVLINK)
+
+static uint8_t mavlinkGetVehicleType(void)
+{
+ switch (mixerConfig()->platformType)
+ {
+ case PLATFORM_MULTIROTOR:
+ return MAV_TYPE_QUADROTOR;
+ case PLATFORM_TRICOPTER:
+ return MAV_TYPE_TRICOPTER;
+ case PLATFORM_AIRPLANE:
+ return MAV_TYPE_FIXED_WING;
+ case PLATFORM_ROVER:
+ return MAV_TYPE_GROUND_ROVER;
+ case PLATFORM_BOAT:
+ return MAV_TYPE_SURFACE_BOAT;
+ case PLATFORM_HELICOPTER:
+ return MAV_TYPE_HELICOPTER;
+ default:
+ return MAV_TYPE_GENERIC;
+ }
+}
+
+static APM_COPTER_MODE inavToArduCopterMap(flightModeForTelemetry_e flightMode)
+{
+ switch (flightMode)
+ {
+ case FLM_ACRO: return COPTER_MODE_ACRO;
+ case FLM_ACRO_AIR: return COPTER_MODE_ACRO;
+ case FLM_ANGLE: return COPTER_MODE_STABILIZE;
+ case FLM_HORIZON: return COPTER_MODE_STABILIZE;
+ case FLM_ANGLEHOLD: return COPTER_MODE_STABILIZE;
+ case FLM_ALTITUDE_HOLD: return COPTER_MODE_ALT_HOLD;
+ case FLM_POSITION_HOLD:
+ {
+ if (isGCSValid()) {
+ return COPTER_MODE_GUIDED;
+ } else {
+ return COPTER_MODE_POSHOLD;
+ }
+ }
+ case FLM_RTH: return COPTER_MODE_RTL;
+ case FLM_MISSION: return COPTER_MODE_AUTO;
+ case FLM_LAUNCH: return COPTER_MODE_THROW;
+ case FLM_FAILSAFE:
+ {
+ if (failsafePhase() == FAILSAFE_RETURN_TO_HOME) {
+ return COPTER_MODE_RTL;
+ } else if (failsafePhase() == FAILSAFE_LANDING) {
+ return COPTER_MODE_LAND;
+ } else {
+ return COPTER_MODE_RTL;
+ }
+ }
+ default: return COPTER_MODE_STABILIZE;
+ }
+}
+
+static APM_PLANE_MODE inavToArduPlaneMap(flightModeForTelemetry_e flightMode)
+{
+ switch (flightMode)
+ {
+ case FLM_MANUAL: return PLANE_MODE_MANUAL;
+ case FLM_ACRO: return PLANE_MODE_ACRO;
+ case FLM_ACRO_AIR: return PLANE_MODE_ACRO;
+ case FLM_ANGLE: return PLANE_MODE_FLY_BY_WIRE_A;
+ case FLM_HORIZON: return PLANE_MODE_STABILIZE;
+ case FLM_ANGLEHOLD: return PLANE_MODE_STABILIZE;
+ case FLM_ALTITUDE_HOLD: return PLANE_MODE_FLY_BY_WIRE_B;
+ case FLM_POSITION_HOLD:
+ {
+ if (isGCSValid()) {
+ return PLANE_MODE_GUIDED;
+ } else {
+ return PLANE_MODE_LOITER;
+ }
+ }
+ case FLM_RTH: return PLANE_MODE_RTL;
+ case FLM_MISSION: return PLANE_MODE_AUTO;
+ case FLM_CRUISE: return PLANE_MODE_CRUISE;
+ case FLM_LAUNCH: return PLANE_MODE_TAKEOFF;
+ case FLM_FAILSAFE: //failsafePhase_e
+ {
+ if (failsafePhase() == FAILSAFE_RETURN_TO_HOME) {
+ return PLANE_MODE_RTL;
+ }
+ else if (failsafePhase() == FAILSAFE_LANDING) {
+ return PLANE_MODE_AUTOLAND;
+ }
+ else {
+ return PLANE_MODE_RTL;
+ }
+ }
+ default: return PLANE_MODE_MANUAL;
+ }
+}
+
+typedef struct mavlinkModeSelection_s {
+ flightModeForTelemetry_e flightMode;
+ uint8_t customMode;
+} mavlinkModeSelection_t;
+
+static mavlinkModeSelection_t selectMavlinkMode(bool isPlane)
+{
+ mavlinkModeSelection_t modeSelection;
+ modeSelection.flightMode = getFlightModeForTelemetry();
+
+ if (isPlane) {
+ modeSelection.customMode = (uint8_t)inavToArduPlaneMap(modeSelection.flightMode);
+ } else {
+ modeSelection.customMode = (uint8_t)inavToArduCopterMap(modeSelection.flightMode);
+ }
+
+ return modeSelection;
+}
+
+static void mavlinkResetTunnelState(uint8_t ingressPortIndex)
+{
+ resetMspPort(&mavTunnelMspPorts[ingressPortIndex], NULL);
+ mavTunnelRemoteSystemIds[ingressPortIndex] = 0;
+ mavTunnelRemoteComponentIds[ingressPortIndex] = 0;
+}
+
+static void mavlinkSendTunnelReply(uint8_t targetSystem, uint8_t targetComponent, const uint8_t *payload, uint8_t payloadLength)
+{
+ uint8_t tunnelPayload[MAVLINK_MSG_TUNNEL_FIELD_PAYLOAD_LEN] = { 0 };
+ memcpy(tunnelPayload, payload, payloadLength);
+
+ mavlink_msg_tunnel_pack(
+ mavSystemId,
+ mavComponentId,
+ &mavSendMsg,
+ targetSystem,
+ targetComponent,
+ MAVLINK_TUNNEL_PAYLOAD_TYPE_INAV_MSP,
+ payloadLength,
+ tunnelPayload);
+ mavlinkSendMessage();
+}
+
+static void mavlinkSendTunnelMspReply(uint8_t targetSystem, uint8_t targetComponent, mspPacket_t *reply, uint8_t *replyPayloadHead, mspVersion_e mspVersion)
+{
+ sbufSwitchToReader(&reply->buf, replyPayloadHead);
+
+ const int frameLength = mspSerialEncodePacket(reply, mspVersion, mavTunnelFrameBuf, sizeof(mavTunnelFrameBuf));
+ for (int offset = 0; offset < frameLength; offset += MAVLINK_MSG_TUNNEL_FIELD_PAYLOAD_LEN) {
+ const uint8_t chunkLength = MIN(MAVLINK_MSG_TUNNEL_FIELD_PAYLOAD_LEN, frameLength - offset);
+ mavlinkSendTunnelReply(
+ targetSystem,
+ targetComponent,
+ mavTunnelFrameBuf + offset,
+ chunkLength);
+ }
+}
+
+static bool handleIncoming_TUNNEL(uint8_t ingressPortIndex)
+{
+ if (mavlinkGetProtocolVersion() == 1) {
+ return false;
+ }
+
+ mavlink_tunnel_t msg;
+ mavlink_msg_tunnel_decode(&mavlinkContext.recvMsg, &msg);
+
+ if (msg.payload_type != MAVLINK_TUNNEL_PAYLOAD_TYPE_INAV_MSP) {
+ return false;
+ }
+
+ if (msg.target_system != mavSystemId) {
+ return false;
+ }
+
+ if (msg.target_component != 0 && msg.target_component != mavComponentId) {
+ return false;
+ }
+
+ mspPort_t *mspPort = &mavTunnelMspPorts[ingressPortIndex];
+ const timeMs_t now = millis();
+ if (msg.payload_length > MAVLINK_MSG_TUNNEL_FIELD_PAYLOAD_LEN) {
+ mavlinkResetTunnelState(ingressPortIndex);
+ return false;
+ }
+
+ if (mspPort->c_state != MSP_IDLE &&
+ ((now - mspPort->lastActivityMs) > MAVLINK_TUNNEL_MSP_TIMEOUT_MS ||
+ mavTunnelRemoteSystemIds[ingressPortIndex] != mavlinkContext.recvMsg.sysid ||
+ mavTunnelRemoteComponentIds[ingressPortIndex] != mavlinkContext.recvMsg.compid)) {
+ mavlinkResetTunnelState(ingressPortIndex);
+ }
+
+ mavTunnelRemoteSystemIds[ingressPortIndex] = mavlinkContext.recvMsg.sysid;
+ mavTunnelRemoteComponentIds[ingressPortIndex] = mavlinkContext.recvMsg.compid;
+ mspPort->lastActivityMs = now;
+
+ bool handled = false;
+ for (uint8_t payloadIndex = 0; payloadIndex < msg.payload_length; payloadIndex++) {
+ if (!mspSerialProcessReceivedByte(mspPort, msg.payload[payloadIndex])) {
+ continue;
+ }
+
+ handled = true;
+ if (mspPort->c_state != MSP_COMMAND_RECEIVED) {
+ continue;
+ }
+
+ mspPacket_t reply = {
+ .buf = { .ptr = mavTunnelReplyPayloadBuf, .end = ARRAYEND(mavTunnelReplyPayloadBuf), },
+ .cmd = -1,
+ .flags = 0,
+ .result = 0,
+ };
+ uint8_t *replyPayloadHead = reply.buf.ptr;
+
+ if (mspPort->cmdMSP == MSP_SET_PASSTHROUGH) {
+ reply.cmd = MSP_SET_PASSTHROUGH;
+ reply.result = MSP_RESULT_ERROR;
+ mavlinkSendTunnelMspReply(mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, &reply, replyPayloadHead, mspPort->mspVersion);
+ mavlinkResetTunnelState(ingressPortIndex);
+ break;
+ }
+
+ mspPostProcessFnPtr mspPostProcessFn = NULL;
+ const uint16_t command = mspPort->cmdMSP;
+ mspResult_e status = mspSerialProcessCommand(mspPort, mspFcProcessCommand, &reply, &mspPostProcessFn);
+
+ if (mspPostProcessFn && command != MSP_REBOOT) {
+ sbufInit(&reply.buf, mavTunnelReplyPayloadBuf, ARRAYEND(mavTunnelReplyPayloadBuf));
+ reply.result = MSP_RESULT_ERROR;
+ mspPostProcessFn = NULL;
+ status = MSP_RESULT_ERROR;
+ }
+
+ if (status != MSP_RESULT_NO_REPLY) {
+ mavlinkSendTunnelMspReply(mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, &reply, replyPayloadHead, mspPort->mspVersion);
+ }
+
+ mavlinkResetTunnelState(ingressPortIndex);
+
+ if (mspPostProcessFn) {
+ waitForSerialPortToFinishTransmitting(mavPortStates[ingressPortIndex].port);
+ mspPostProcessFn(mavPortStates[ingressPortIndex].port);
+ }
+
+ break;
+ }
+
+ return handled;
+}
+
+static void mavlinkSendAutopilotVersion(void)
+{
+ if (mavlinkGetProtocolVersion() == 1) return;
+
+ // Capabilities aligned with what we actually support.
+ uint64_t capabilities = 0;
+ capabilities |= MAV_PROTOCOL_CAPABILITY_MAVLINK2;
+ capabilities |= MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT;
+ capabilities |= MAV_PROTOCOL_CAPABILITY_MISSION_INT;
+ capabilities |= MAV_PROTOCOL_CAPABILITY_COMMAND_INT;
+ capabilities |= MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_LOCAL_NED;
+ capabilities |= MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_GLOBAL_INT;
+
+ const uint32_t flightSwVersion =
+ ((uint32_t)ARDUPILOT_VERSION_MAJOR << 24) |
+ ((uint32_t)ARDUPILOT_VERSION_MINOR << 16) |
+ ((uint32_t)ARDUPILOT_VERSION_PATCH << 8);
+
+ // Bare minimum: caps + IDs. Everything else 0 is fine.
+ mavlink_msg_autopilot_version_pack(
+ mavSystemId,
+ mavComponentId,
+ &mavSendMsg,
+ capabilities, // capabilities
+ flightSwVersion, // flight_sw_version
+ 0, // middleware_sw_version
+ 0, // os_sw_version
+ 0, // board_version
+ 0ULL, // flight_custom_version
+ 0ULL, // middleware_custom_version
+ 0ULL, // os_custom_version
+ 0ULL, // vendor_id
+ 0ULL, // product_id
+ (uint64_t)mavSystemId, // uid (any stable nonzero is fine)
+ 0ULL // uid2
+ );
+ mavlinkSendMessage();
+}
+
+static void mavlinkSendProtocolVersion(void)
+{
+ if (mavlinkGetProtocolVersion() == 1) return;
+
+ uint8_t specHash[8] = {0};
+ uint8_t libHash[8] = {0};
+ const uint16_t protocolVersion = (uint16_t)mavlinkGetProtocolVersion() * 100;
+
+ mavlink_msg_protocol_version_pack(
+ mavSystemId,
+ mavComponentId,
+ &mavSendMsg,
+ protocolVersion,
+ protocolVersion,
+ protocolVersion,
+ specHash,
+ libHash);
+
+ mavlinkSendMessage();
+}
+
+static bool mavlinkFrameIsSupported(uint8_t frame, mavFrameSupportMask_e allowedMask)
+{
+ switch (frame) {
+ case MAV_FRAME_GLOBAL:
+ return allowedMask & MAV_FRAME_SUPPORTED_GLOBAL;
+ case MAV_FRAME_GLOBAL_INT:
+ return allowedMask & MAV_FRAME_SUPPORTED_GLOBAL_INT;
+ case MAV_FRAME_GLOBAL_RELATIVE_ALT:
+ return allowedMask & MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT;
+ case MAV_FRAME_GLOBAL_RELATIVE_ALT_INT:
+ return allowedMask & MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT_INT;
+ default:
+ return false;
+ }
+}
+
+static bool mavlinkFrameUsesAbsoluteAltitude(uint8_t frame)
+{
+ return frame == MAV_FRAME_GLOBAL || frame == MAV_FRAME_GLOBAL_INT;
+}
+
+static MAV_RESULT mavlinkSetAltitudeTargetFromFrame(uint8_t frame, float altitudeMeters)
+{
+#ifdef USE_BARO
+ geoAltitudeDatumFlag_e datum;
+
+ switch (frame) {
+ case MAV_FRAME_GLOBAL:
+ case MAV_FRAME_GLOBAL_INT:
+ datum = NAV_WP_MSL_DATUM;
+ break;
+ case MAV_FRAME_GLOBAL_RELATIVE_ALT:
+ case MAV_FRAME_GLOBAL_RELATIVE_ALT_INT:
+ datum = NAV_WP_TAKEOFF_DATUM;
+ break;
+ default:
+ return MAV_RESULT_UNSUPPORTED;
+ }
+
+ const int32_t targetAltitudeCm = (int32_t)lrintf(altitudeMeters * 100.0f);
+ return navigationSetAltitudeTargetWithDatum(datum, targetAltitudeCm) ? MAV_RESULT_ACCEPTED : MAV_RESULT_DENIED;
+#else
+ UNUSED(frame);
+ UNUSED(altitudeMeters);
+ return MAV_RESULT_UNSUPPORTED;
+#endif
+}
+
+static MAV_MISSION_RESULT mavlinkMissionResultFromCommandResult(MAV_RESULT result)
+{
+ switch (result) {
+ case MAV_RESULT_ACCEPTED:
+ return MAV_MISSION_ACCEPTED;
+ case MAV_RESULT_UNSUPPORTED:
+ return MAV_MISSION_UNSUPPORTED;
+ default:
+ return MAV_MISSION_ERROR;
+ }
+}
+
+static bool mavlinkHandleArmedGuidedMissionItem(uint8_t current, uint8_t frame, mavFrameSupportMask_e allowedFrames, int32_t latitudeE7, int32_t longitudeE7, float altitudeMeters)
+{
+ if (!isGCSValid()) {
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg,
+ mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid,
+ MAV_MISSION_ERROR, MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
+ return true;
+ }
+
+ if (!mavlinkFrameIsSupported(frame, allowedFrames)) {
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg,
+ mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid,
+ MAV_MISSION_UNSUPPORTED_FRAME, MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
+ return true;
+ }
+
+ if (current == 2) {
+ navWaypoint_t wp = {0};
+ wp.action = NAV_WP_ACTION_WAYPOINT;
+ wp.lat = latitudeE7;
+ wp.lon = longitudeE7;
+ wp.alt = (int32_t)lrintf(altitudeMeters * 100.0f);
+ wp.p3 = mavlinkFrameUsesAbsoluteAltitude(frame) ? NAV_WP_ALTMODE : 0;
+
+ setWaypoint(255, &wp);
+
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg,
+ mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid,
+ MAV_MISSION_ACCEPTED, MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
+ return true;
+ }
+
+ if (current == 3) {
+ const MAV_RESULT result = mavlinkSetAltitudeTargetFromFrame(frame, altitudeMeters);
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg,
+ mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid,
+ mavlinkMissionResultFromCommandResult(result), MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
+ return true;
+ }
+
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg,
+ mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid,
+ MAV_MISSION_ERROR, MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
+ return true;
+}
+
+static uint8_t navWaypointFrame(const navWaypoint_t *wp, bool useIntMessages)
+{
+ switch (wp->action) {
+ case NAV_WP_ACTION_RTH:
+ case NAV_WP_ACTION_JUMP:
+ case NAV_WP_ACTION_SET_HEAD:
+ return MAV_FRAME_MISSION;
+ default:
+ break;
+ }
+
+ const bool absoluteAltitude = (wp->p3 & NAV_WP_ALTMODE) == NAV_WP_ALTMODE;
+
+ if (absoluteAltitude) {
+ return useIntMessages ? MAV_FRAME_GLOBAL_INT : MAV_FRAME_GLOBAL;
+ }
+
+ return useIntMessages ? MAV_FRAME_GLOBAL_RELATIVE_ALT_INT : MAV_FRAME_GLOBAL_RELATIVE_ALT;
+}
+
+const mavlinkModeDescriptor_t planeModes[] = {
+ { PLANE_MODE_MANUAL, "MANUAL" },
+ { PLANE_MODE_ACRO, "ACRO" },
+ { PLANE_MODE_STABILIZE, "STABILIZE" },
+ { PLANE_MODE_FLY_BY_WIRE_A,"FBWA" },
+ { PLANE_MODE_FLY_BY_WIRE_B,"FBWB" },
+ { PLANE_MODE_CRUISE, "CRUISE" },
+ { PLANE_MODE_AUTO, "AUTO" },
+ { PLANE_MODE_RTL, "RTL" },
+ { PLANE_MODE_LOITER, "LOITER" },
+ { PLANE_MODE_TAKEOFF, "TAKEOFF" },
+ { PLANE_MODE_GUIDED, "GUIDED" },
+};
+const uint8_t planeModesCount = (uint8_t)ARRAYLEN(planeModes);
+
+const mavlinkModeDescriptor_t copterModes[] = {
+ { COPTER_MODE_ACRO, "ACRO" },
+ { COPTER_MODE_STABILIZE, "STABILIZE" },
+ { COPTER_MODE_ALT_HOLD, "ALT_HOLD" },
+ { COPTER_MODE_POSHOLD, "POSHOLD" },
+ { COPTER_MODE_LOITER, "LOITER" },
+ { COPTER_MODE_AUTO, "AUTO" },
+ { COPTER_MODE_GUIDED, "GUIDED" },
+ { COPTER_MODE_RTL, "RTL" },
+ { COPTER_MODE_LAND, "LAND" },
+ { COPTER_MODE_BRAKE, "BRAKE" },
+ { COPTER_MODE_THROW, "THROW" },
+ { COPTER_MODE_SMART_RTL, "SMART_RTL" },
+ { COPTER_MODE_DRIFT, "DRIFT" },
+};
+const uint8_t copterModesCount = (uint8_t)ARRAYLEN(copterModes);
+
+static bool mavlinkPlaneModeIsConfigured(uint8_t customMode)
+{
+ switch ((APM_PLANE_MODE)customMode) {
+ case PLANE_MODE_MANUAL:
+ return isModeActivationConditionPresent(BOXMANUAL);
+ case PLANE_MODE_ACRO:
+ return true;
+ case PLANE_MODE_STABILIZE:
+ return isModeActivationConditionPresent(BOXHORIZON) ||
+ isModeActivationConditionPresent(BOXANGLEHOLD);
+ case PLANE_MODE_FLY_BY_WIRE_A:
+ return isModeActivationConditionPresent(BOXANGLE);
+ case PLANE_MODE_FLY_BY_WIRE_B:
+ return isModeActivationConditionPresent(BOXNAVALTHOLD);
+ case PLANE_MODE_CRUISE:
+ return isModeActivationConditionPresent(BOXNAVCRUISE) ||
+ (isModeActivationConditionPresent(BOXNAVCOURSEHOLD) &&
+ isModeActivationConditionPresent(BOXNAVALTHOLD));
+ case PLANE_MODE_AUTO:
+ return isModeActivationConditionPresent(BOXNAVWP);
+ case PLANE_MODE_RTL:
+ return isModeActivationConditionPresent(BOXNAVRTH);
+ case PLANE_MODE_GUIDED:
+ return isModeActivationConditionPresent(BOXNAVPOSHOLD) &&
+ isModeActivationConditionPresent(BOXGCSNAV);
+ case PLANE_MODE_LOITER:
+ return isModeActivationConditionPresent(BOXNAVPOSHOLD);
+ case PLANE_MODE_TAKEOFF:
+ return isModeActivationConditionPresent(BOXNAVLAUNCH);
+ default:
+ return false;
+ }
+}
+
+static bool mavlinkCopterModeIsConfigured(uint8_t customMode)
+{
+ switch ((APM_COPTER_MODE)customMode) {
+ case COPTER_MODE_ACRO:
+ return true;
+ case COPTER_MODE_STABILIZE:
+ return isModeActivationConditionPresent(BOXANGLE) ||
+ isModeActivationConditionPresent(BOXHORIZON) ||
+ isModeActivationConditionPresent(BOXANGLEHOLD);
+ case COPTER_MODE_ALT_HOLD:
+ return isModeActivationConditionPresent(BOXNAVALTHOLD);
+ case COPTER_MODE_GUIDED:
+ return isModeActivationConditionPresent(BOXNAVPOSHOLD) &&
+ isModeActivationConditionPresent(BOXGCSNAV);
+ case COPTER_MODE_POSHOLD:
+ return isModeActivationConditionPresent(BOXNAVPOSHOLD);
+ case COPTER_MODE_RTL:
+ return isModeActivationConditionPresent(BOXNAVRTH);
+ case COPTER_MODE_AUTO:
+ return isModeActivationConditionPresent(BOXNAVWP);
+ case COPTER_MODE_THROW:
+ return isModeActivationConditionPresent(BOXNAVLAUNCH);
+ case COPTER_MODE_BRAKE:
+ return isModeActivationConditionPresent(BOXBRAKING);
+ default:
+ return false;
+ }
+}
+
+static void mavlinkSendAvailableModes(const mavlinkModeDescriptor_t *modes, uint8_t count, uint8_t currentCustom,
+ bool (*isModeConfigured)(uint8_t customMode))
+{
+ uint8_t availableCount = 0;
+ for (uint8_t i = 0; i < count; i++) {
+ if (isModeConfigured(modes[i].customMode)) {
+ availableCount++;
+ }
+ }
+
+ if (availableCount == 0) {
+ return;
+ }
+
+ uint8_t modeIndex = 0;
+ for (uint8_t i = 0; i < count; i++) {
+ if (!isModeConfigured(modes[i].customMode)) {
+ continue;
+ }
+
+ modeIndex++;
+ const uint8_t stdMode = MAV_STANDARD_MODE_NON_STANDARD;
+ const uint32_t properties = 0;
+
+ mavlink_msg_available_modes_pack(
+ mavSystemId,
+ mavComponentId,
+ &mavSendMsg,
+ availableCount,
+ modeIndex,
+ stdMode,
+ modes[i].customMode,
+ properties,
+ modes[i].name);
+
+ mavlinkSendMessage();
+
+ if (modes[i].customMode == currentCustom) {
+ mavlink_msg_current_mode_pack(
+ mavSystemId,
+ mavComponentId,
+ &mavSendMsg,
+ stdMode,
+ currentCustom,
+ currentCustom);
+ mavlinkSendMessage();
+ }
+ }
+}
+
+void mavlinkSendExtendedSysState(void)
+{
+ uint8_t vtolState = MAV_VTOL_STATE_UNDEFINED;
+ uint8_t landedState;
+
+ switch (NAV_Status.state) {
+ case MW_NAV_STATE_LAND_START:
+ case MW_NAV_STATE_LAND_IN_PROGRESS:
+ case MW_NAV_STATE_LAND_SETTLE:
+ case MW_NAV_STATE_LAND_START_DESCENT:
+ case MW_NAV_STATE_EMERGENCY_LANDING:
+ landedState = MAV_LANDED_STATE_LANDING;
+ break;
+ case MW_NAV_STATE_LANDED:
+ landedState = MAV_LANDED_STATE_ON_GROUND;
+ break;
+ default:
+ if (!ARMING_FLAG(ARMED) || STATE(LANDING_DETECTED)) {
+ landedState = MAV_LANDED_STATE_ON_GROUND;
+ } else {
+ landedState = MAV_LANDED_STATE_IN_AIR;
+ }
+ break;
+ }
+
+ mavlink_msg_extended_sys_state_pack(
+ mavSystemId,
+ mavComponentId,
+ &mavSendMsg,
+ vtolState,
+ landedState);
+
+ mavlinkSendMessage();
+}
+
+void mavlinkSendSystemStatus(void)
+{
+ // Receiver is assumed to be always present
+ uint32_t onboard_control_sensors_present = (MAV_SYS_STATUS_SENSOR_RC_RECEIVER);
+ // GYRO and RC are assumed as minimum requirements
+ uint32_t onboard_control_sensors_enabled = (MAV_SYS_STATUS_SENSOR_3D_GYRO | MAV_SYS_STATUS_SENSOR_RC_RECEIVER);
+ uint32_t onboard_control_sensors_health = 0;
+
+ if (getHwGyroStatus() == HW_SENSOR_OK) {
+ onboard_control_sensors_present |= MAV_SYS_STATUS_SENSOR_3D_GYRO;
+ // Missing presence will report as sensor unhealthy
+ onboard_control_sensors_health |= MAV_SYS_STATUS_SENSOR_3D_GYRO;
+ }
+
+ hardwareSensorStatus_e accStatus = getHwAccelerometerStatus();
+ if (accStatus == HW_SENSOR_OK) {
+ onboard_control_sensors_present |= MAV_SYS_STATUS_SENSOR_3D_ACCEL;
+ onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_3D_ACCEL;
+ onboard_control_sensors_health |= MAV_SYS_STATUS_SENSOR_3D_ACCEL;
+ } else if (accStatus == HW_SENSOR_UNHEALTHY) {
+ onboard_control_sensors_present |= MAV_SYS_STATUS_SENSOR_3D_ACCEL;
+ onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_3D_ACCEL;
+ } else if (accStatus == HW_SENSOR_UNAVAILABLE) {
+ onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_3D_ACCEL;
+ }
+
+ hardwareSensorStatus_e compassStatus = getHwCompassStatus();
+ if (compassStatus == HW_SENSOR_OK) {
+ onboard_control_sensors_present |= MAV_SYS_STATUS_SENSOR_3D_MAG;
+ onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_3D_MAG;
+ onboard_control_sensors_health |= MAV_SYS_STATUS_SENSOR_3D_MAG;
+ } else if (compassStatus == HW_SENSOR_UNHEALTHY) {
+ onboard_control_sensors_present |= MAV_SYS_STATUS_SENSOR_3D_MAG;
+ onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_3D_MAG;
+ } else if (compassStatus == HW_SENSOR_UNAVAILABLE) {
+ onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_3D_MAG;
+ }
+
+ hardwareSensorStatus_e baroStatus = getHwBarometerStatus();
+ if (baroStatus == HW_SENSOR_OK) {
+ onboard_control_sensors_present |= MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE;
+ onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE;
+ onboard_control_sensors_health |= MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE;
+ } else if (baroStatus == HW_SENSOR_UNHEALTHY) {
+ onboard_control_sensors_present |= MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE;
+ onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE;
+ } else if (baroStatus == HW_SENSOR_UNAVAILABLE) {
+ onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE;
+ }
+
+ hardwareSensorStatus_e pitotStatus = getHwPitotmeterStatus();
+ if (pitotStatus == HW_SENSOR_OK) {
+ onboard_control_sensors_present |= MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE;
+ onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE;
+ onboard_control_sensors_health |= MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE;
+ } else if (pitotStatus == HW_SENSOR_UNHEALTHY) {
+ onboard_control_sensors_present |= MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE;
+ onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE;
+ } else if (pitotStatus == HW_SENSOR_UNAVAILABLE) {
+ onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE;
+ }
+
+ hardwareSensorStatus_e gpsStatus = getHwGPSStatus();
+ if (gpsStatus == HW_SENSOR_OK) {
+ onboard_control_sensors_present |= MAV_SYS_STATUS_SENSOR_GPS;
+ onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_GPS;
+ onboard_control_sensors_health |= MAV_SYS_STATUS_SENSOR_GPS;
+ } else if (gpsStatus == HW_SENSOR_UNHEALTHY) {
+ onboard_control_sensors_present |= MAV_SYS_STATUS_SENSOR_GPS;
+ onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_GPS;
+ } else if (gpsStatus == HW_SENSOR_UNAVAILABLE) {
+ onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_GPS;
+ }
+
+ hardwareSensorStatus_e opFlowStatus = getHwOpticalFlowStatus();
+ if (opFlowStatus == HW_SENSOR_OK) {
+ onboard_control_sensors_present |= MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW;
+ onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW;
+ onboard_control_sensors_health |= MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW;
+ } else if (opFlowStatus == HW_SENSOR_UNHEALTHY) {
+ onboard_control_sensors_present |= MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW;
+ onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW;
+ } else if (opFlowStatus == HW_SENSOR_UNAVAILABLE) {
+ onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW;
+ }
+
+ hardwareSensorStatus_e rangefinderStatus = getHwRangefinderStatus();
+ if (rangefinderStatus == HW_SENSOR_OK) {
+ onboard_control_sensors_present |= MAV_SYS_STATUS_SENSOR_LASER_POSITION;
+ onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_LASER_POSITION;
+ onboard_control_sensors_health |= MAV_SYS_STATUS_SENSOR_LASER_POSITION;
+ } else if (rangefinderStatus == HW_SENSOR_UNHEALTHY) {
+ onboard_control_sensors_present |= MAV_SYS_STATUS_SENSOR_LASER_POSITION;
+ onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_LASER_POSITION;
+ } else if (rangefinderStatus == HW_SENSOR_UNAVAILABLE) {
+ onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_LASER_POSITION;
+ }
+
+ if (rxIsReceivingSignal() && rxAreFlightChannelsValid()) {
+ onboard_control_sensors_health |= MAV_SYS_STATUS_SENSOR_RC_RECEIVER;
+ }
+
+#ifdef USE_BLACKBOX
+ // BLACKBOX is assumed enabled and present for boards with capability
+ onboard_control_sensors_present |= MAV_SYS_STATUS_LOGGING;
+ onboard_control_sensors_enabled |= MAV_SYS_STATUS_LOGGING;
+ // Unhealthy only for cases with not enough space to record
+ if (!isBlackboxDeviceFull()) {
+ onboard_control_sensors_health |= MAV_SYS_STATUS_LOGGING;
+ }
+#endif
+
+ mavlink_msg_sys_status_pack(mavSystemId, mavComponentId, &mavSendMsg,
+ // onboard_control_sensors_present Bitmask showing which onboard controllers and sensors are present.
+ //Value of 0: not present. Value of 1: present. Indices according MAV_SYS_STATUS_SENSOR
+ onboard_control_sensors_present,
+ // onboard_control_sensors_enabled Bitmask showing which onboard controllers and sensors are enabled
+ onboard_control_sensors_enabled,
+ // onboard_control_sensors_health Bitmask showing which onboard controllers and sensors are operational or have an error.
+ onboard_control_sensors_health,
+ // load Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000
+ constrain(averageSystemLoadPercent*10, 0, 1000),
+ // voltage_battery Battery voltage, in millivolts (1 = 1 millivolt)
+ feature(FEATURE_VBAT) ? getBatteryVoltage() * 10 : 0,
+ // current_battery Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current
+ isAmperageConfigured() ? getAmperage() : -1,
+ // battery_remaining Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery
+ feature(FEATURE_VBAT) ? calculateBatteryPercentage() : 100,
+ // drop_rate_comm Communication drops in percent, (0%: 0, 100%: 10'000), (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)
+ 0,
+ // errors_comm Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)
+ 0,
+ // errors_count1 Autopilot-specific errors
+ 0,
+ // errors_count2 Autopilot-specific errors
+ 0,
+ // errors_count3 Autopilot-specific errors
+ 0,
+ // errors_count4 Autopilot-specific errors
+ 0, 0, 0, 0);
+
+ mavlinkSendMessage();
+}
+
+void mavlinkSendRCChannelsAndRSSI(void)
+{
+#define GET_CHANNEL_VALUE(x) ((rxRuntimeConfig.channelCount >= (x + 1)) ? rxGetChannelValue(x) : 0)
+ if (mavlinkGetProtocolVersion() == 1) {
+ mavlink_msg_rc_channels_raw_pack(mavSystemId, mavComponentId, &mavSendMsg,
+ // time_boot_ms Timestamp (milliseconds since system boot)
+ millis(),
+ // port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos.
+ 0,
+ // chan1_raw RC channel 1 value, in microseconds
+ GET_CHANNEL_VALUE(0),
+ // chan2_raw RC channel 2 value, in microseconds
+ GET_CHANNEL_VALUE(1),
+ // chan3_raw RC channel 3 value, in microseconds
+ GET_CHANNEL_VALUE(2),
+ // chan4_raw RC channel 4 value, in microseconds
+ GET_CHANNEL_VALUE(3),
+ // chan5_raw RC channel 5 value, in microseconds
+ GET_CHANNEL_VALUE(4),
+ // chan6_raw RC channel 6 value, in microseconds
+ GET_CHANNEL_VALUE(5),
+ // chan7_raw RC channel 7 value, in microseconds
+ GET_CHANNEL_VALUE(6),
+ // chan8_raw RC channel 8 value, in microseconds
+ GET_CHANNEL_VALUE(7),
+ // rssi Receive signal strength indicator, 0: 0%, 254: 100%
+ //https://github.com/mavlink/mavlink/issues/1027
+ scaleRange(getRSSI(), 0, 1023, 0, 254));
+ }
+ else {
+ mavlink_msg_rc_channels_pack(mavSystemId, mavComponentId, &mavSendMsg,
+ // time_boot_ms Timestamp (milliseconds since system boot)
+ millis(),
+ // Total number of RC channels being received.
+ rxRuntimeConfig.channelCount,
+ // chan1_raw RC channel 1 value, in microseconds
+ GET_CHANNEL_VALUE(0),
+ // chan2_raw RC channel 2 value, in microseconds
+ GET_CHANNEL_VALUE(1),
+ // chan3_raw RC channel 3 value, in microseconds
+ GET_CHANNEL_VALUE(2),
+ // chan4_raw RC channel 4 value, in microseconds
+ GET_CHANNEL_VALUE(3),
+ // chan5_raw RC channel 5 value, in microseconds
+ GET_CHANNEL_VALUE(4),
+ // chan6_raw RC channel 6 value, in microseconds
+ GET_CHANNEL_VALUE(5),
+ // chan7_raw RC channel 7 value, in microseconds
+ GET_CHANNEL_VALUE(6),
+ // chan8_raw RC channel 8 value, in microseconds
+ GET_CHANNEL_VALUE(7),
+ // chan9_raw RC channel 9 value, in microseconds
+ GET_CHANNEL_VALUE(8),
+ // chan10_raw RC channel 10 value, in microseconds
+ GET_CHANNEL_VALUE(9),
+ // chan11_raw RC channel 11 value, in microseconds
+ GET_CHANNEL_VALUE(10),
+ // chan12_raw RC channel 12 value, in microseconds
+ GET_CHANNEL_VALUE(11),
+ // chan13_raw RC channel 13 value, in microseconds
+ GET_CHANNEL_VALUE(12),
+ // chan14_raw RC channel 14 value, in microseconds
+ GET_CHANNEL_VALUE(13),
+ // chan15_raw RC channel 15 value, in microseconds
+ GET_CHANNEL_VALUE(14),
+ // chan16_raw RC channel 16 value, in microseconds
+ GET_CHANNEL_VALUE(15),
+ // chan17_raw RC channel 17 value, in microseconds
+ GET_CHANNEL_VALUE(16),
+ // chan18_raw RC channel 18 value, in microseconds
+ GET_CHANNEL_VALUE(17),
+ // rssi Receive signal strength indicator, 0: 0%, 254: 100%
+ //https://github.com/mavlink/mavlink/issues/1027
+ scaleRange(getRSSI(), 0, 1023, 0, 254));
+ }
+#undef GET_CHANNEL_VALUE
+
+ mavlinkSendMessage();
+}
+
+#if defined(USE_GPS)
+static void mavlinkSendHomePosition(void)
+{
+ float q[4] = { 1.0f, 0.0f, 0.0f, 0.0f };
+
+ mavlink_msg_home_position_pack(
+ mavSystemId,
+ mavComponentId,
+ &mavSendMsg,
+ GPS_home.lat,
+ GPS_home.lon,
+ GPS_home.alt * 10,
+ 0.0f,
+ 0.0f,
+ 0.0f,
+ q,
+ 0.0f,
+ 0.0f,
+ 0.0f,
+ ((uint64_t) millis()) * 1000);
+
+ mavlinkSendMessage();
+}
+
+void mavlinkSendGpsRawInt(timeUs_t currentTimeUs)
+{
+ uint8_t gpsFixType = 0;
+
+ if (!(sensors(SENSOR_GPS)
+#ifdef USE_GPS_FIX_ESTIMATION
+ || STATE(GPS_ESTIMATED_FIX)
+#endif
+ ))
+ return;
+
+ if (gpsSol.fixType == GPS_NO_FIX)
+ gpsFixType = 1;
+ else if (gpsSol.fixType == GPS_FIX_2D)
+ gpsFixType = 2;
+ else if (gpsSol.fixType == GPS_FIX_3D)
+ gpsFixType = 3;
+
+ mavlink_msg_gps_raw_int_pack(mavSystemId, mavComponentId, &mavSendMsg,
+ // time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
+ currentTimeUs,
+ // fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
+ gpsFixType,
+ // lat Latitude in 1E7 degrees
+ gpsSol.llh.lat,
+ // lon Longitude in 1E7 degrees
+ gpsSol.llh.lon,
+ // alt Altitude in 1E3 meters (millimeters) above MSL
+ gpsSol.llh.alt * 10,
+ // eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
+ gpsSol.eph,
+ // epv GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
+ gpsSol.epv,
+ // vel GPS ground speed (m/s * 100). If unknown, set to: 65535
+ gpsSol.groundSpeed,
+ // cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535
+ gpsSol.groundCourse * 10,
+ // satellites_visible Number of satellites visible. If unknown, set to 255
+ gpsSol.numSat,
+ // alt_ellipsoid Altitude (above WGS84, EGM96 ellipsoid). Positive for up
+ 0,
+ // h_acc Position uncertainty in mm,
+ gpsSol.eph * 10,
+ // v_acc Altitude uncertainty in mm,
+ gpsSol.epv * 10,
+ // vel_acc Speed uncertainty in mm (??)
+ 0,
+ // hdg_acc Heading uncertainty in degE5
+ 0,
+ // yaw Yaw in earth frame from north. Use 0 if this GPS does not provide yaw. Use 65535 if this GPS is configured to provide yaw and is currently unable to provide it. Use 36000 for north.
+ 0);
+
+ mavlinkSendMessage();
+}
+
+void mavlinkSendGlobalPositionInt(timeUs_t currentTimeUs)
+{
+ if (!(sensors(SENSOR_GPS)
+#ifdef USE_GPS_FIX_ESTIMATION
+ || STATE(GPS_ESTIMATED_FIX)
+#endif
+ )) {
+ return;
+ }
+
+ mavlink_msg_global_position_int_pack(mavSystemId, mavComponentId, &mavSendMsg,
+ // time_boot_ms Timestamp (milliseconds since system boot)
+ currentTimeUs / 1000,
+ // lat Latitude in 1E7 degrees
+ gpsSol.llh.lat,
+ // lon Longitude in 1E7 degrees
+ gpsSol.llh.lon,
+ // alt Altitude in 1E3 meters (millimeters) above MSL
+ gpsSol.llh.alt * 10,
+ // relative_alt Altitude above ground in meters, expressed as * 1000 (millimeters)
+ getEstimatedActualPosition(Z) * 10,
+ // [cm/s] Ground X Speed (Latitude, positive north)
+ getEstimatedActualVelocity(X),
+ // [cm/s] Ground Y Speed (Longitude, positive east)
+ getEstimatedActualVelocity(Y),
+ // [cm/s] Ground Z Speed (Altitude, positive down)
+ -getEstimatedActualVelocity(Z),
+ // [cdeg] Vehicle heading (yaw angle) (0.0..359.99 degrees, 0=north)
+ DECIDEGREES_TO_CENTIDEGREES(attitude.values.yaw)
+ );
+
+ mavlinkSendMessage();
+}
+
+void mavlinkSendGpsGlobalOrigin(void)
+{
+ mavlink_msg_gps_global_origin_pack(mavSystemId, mavComponentId, &mavSendMsg,
+ // latitude Latitude (WGS84), expressed as * 1E7
+ GPS_home.lat,
+ // longitude Longitude (WGS84), expressed as * 1E7
+ GPS_home.lon,
+ // altitude Altitude(WGS84), expressed as * 1000
+ GPS_home.alt * 10, // FIXME
+ // time_usec Timestamp (microseconds since system boot)
+ // Use millis() * 1000 as micros() will overflow after 1.19 hours.
+ ((uint64_t) millis()) * 1000);
+
+ mavlinkSendMessage();
+}
+
+void mavlinkSendPosition(timeUs_t currentTimeUs)
+{
+ mavlinkSendGpsRawInt(currentTimeUs);
+ mavlinkSendGlobalPositionInt(currentTimeUs);
+ mavlinkSendGpsGlobalOrigin();
+}
+#endif
+
+void mavlinkSendAttitude(void)
+{
+ mavlink_msg_attitude_pack(mavSystemId, mavComponentId, &mavSendMsg,
+ // time_boot_ms Timestamp (milliseconds since system boot)
+ millis(),
+ // roll Roll angle (rad)
+ RADIANS_TO_MAVLINK_RANGE(DECIDEGREES_TO_RADIANS(attitude.values.roll)),
+ // pitch Pitch angle (rad)
+ RADIANS_TO_MAVLINK_RANGE(DECIDEGREES_TO_RADIANS(-attitude.values.pitch)),
+ // yaw Yaw angle (rad)
+ RADIANS_TO_MAVLINK_RANGE(DECIDEGREES_TO_RADIANS(attitude.values.yaw)),
+ // rollspeed Roll angular speed (rad/s)
+ DEGREES_TO_RADIANS(gyro.gyroADCf[FD_ROLL]),
+ // pitchspeed Pitch angular speed (rad/s)
+ DEGREES_TO_RADIANS(gyro.gyroADCf[FD_PITCH]),
+ // yawspeed Yaw angular speed (rad/s)
+ DEGREES_TO_RADIANS(gyro.gyroADCf[FD_YAW]));
+
+ mavlinkSendMessage();
+}
+
+void mavlinkSendVfrHud(void)
+{
+ float mavAltitude = 0;
+ float mavGroundSpeed = 0;
+ float mavAirSpeed = 0;
+ float mavClimbRate = 0;
+
+#if defined(USE_GPS)
+ // use ground speed if source available
+ if (sensors(SENSOR_GPS)
+#ifdef USE_GPS_FIX_ESTIMATION
+ || STATE(GPS_ESTIMATED_FIX)
+#endif
+ ) {
+ mavGroundSpeed = gpsSol.groundSpeed / 100.0f;
+ }
+#endif
+
+#if defined(USE_PITOT)
+ if (sensors(SENSOR_PITOT) && pitotIsHealthy()) {
+ mavAirSpeed = getAirspeedEstimate() / 100.0f;
+ }
+#endif
+
+ // select best source for altitude
+ mavAltitude = getEstimatedActualPosition(Z) / 100.0f;
+ mavClimbRate = getEstimatedActualVelocity(Z) / 100.0f;
+
+ int16_t thr = getThrottlePercent(osdUsingScaledThrottle());
+ mavlink_msg_vfr_hud_pack(mavSystemId, mavComponentId, &mavSendMsg,
+ // airspeed Current airspeed in m/s
+ mavAirSpeed,
+ // groundspeed Current ground speed in m/s
+ mavGroundSpeed,
+ // heading Current heading in degrees, in compass units (0..360, 0=north)
+ DECIDEGREES_TO_DEGREES(attitude.values.yaw),
+ // throttle Current throttle setting in integer percent, 0 to 100
+ thr,
+ // alt Current altitude (MSL), in meters, if we have surface or baro use them, otherwise use GPS (less accurate)
+ mavAltitude,
+ // climb Current climb rate in meters/second
+ mavClimbRate);
+
+ mavlinkSendMessage();
+}
+
+static uint8_t mavlinkGetAutopilotEnum(void);
+
+void mavlinkSendHeartbeat(void)
+{
+ uint8_t mavModes = MAV_MODE_FLAG_CUSTOM_MODE_ENABLED;
+
+ const bool isPlane = (STATE(FIXED_WING_LEGACY) || mixerConfig()->platformType == PLATFORM_AIRPLANE);
+ const mavlinkModeSelection_t modeSelection = selectMavlinkMode(isPlane);
+ flightModeForTelemetry_e flm = modeSelection.flightMode;
+ uint8_t mavCustomMode = modeSelection.customMode;
+ uint8_t mavSystemType;
+ if (isPlane) {
+ mavSystemType = MAV_TYPE_FIXED_WING;
+ }
+ else {
+ mavSystemType = mavlinkGetVehicleType();
+ }
+
+ const bool manualInputAllowed = !(flm == FLM_MISSION || flm == FLM_RTH || flm == FLM_FAILSAFE);
+ if (manualInputAllowed) {
+ mavModes |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED;
+ }
+ if (flm == FLM_POSITION_HOLD && isGCSValid()) {
+ mavModes |= MAV_MODE_FLAG_GUIDED_ENABLED;
+ }
+ else if (flm == FLM_MISSION || flm == FLM_RTH ) {
+ mavModes |= MAV_MODE_FLAG_AUTO_ENABLED;
+ }
+ else if (flm != FLM_MANUAL && flm!= FLM_ACRO && flm!=FLM_ACRO_AIR) {
+ mavModes |= MAV_MODE_FLAG_STABILIZE_ENABLED;
+ }
+
+ if (ARMING_FLAG(ARMED))
+ mavModes |= MAV_MODE_FLAG_SAFETY_ARMED;
+
+ uint8_t mavSystemState = 0;
+ if (ARMING_FLAG(ARMED)) {
+ if (failsafeIsActive()) {
+ mavSystemState = MAV_STATE_CRITICAL;
+ }
+ else {
+ mavSystemState = MAV_STATE_ACTIVE;
+ }
+ }
+ else if (areSensorsCalibrating()) {
+ mavSystemState = MAV_STATE_CALIBRATING;
+ }
+ else {
+ mavSystemState = MAV_STATE_STANDBY;
+ }
+
+ mavlink_msg_heartbeat_pack(mavSystemId, mavComponentId, &mavSendMsg,
+ // type Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
+ mavSystemType,
+ // autopilot Autopilot type / class. defined in MAV_AUTOPILOT ENUM
+ mavlinkGetAutopilotEnum(),
+ // base_mode System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h
+ mavModes,
+ // custom_mode A bitfield for use for autopilot-specific flags.
+ mavCustomMode,
+ // system_status System status flag, see MAV_STATE ENUM
+ mavSystemState);
+
+ mavlinkSendMessage();
+}
+
+void mavlinkSendBatteryStatus(void)
+{
+ uint16_t batteryVoltages[MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_LEN];
+ uint16_t batteryVoltagesExt[MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_EXT_LEN];
+ memset(batteryVoltages, UINT16_MAX, sizeof(batteryVoltages));
+ memset(batteryVoltagesExt, 0, sizeof(batteryVoltagesExt));
+ if (feature(FEATURE_VBAT)) {
+ uint8_t batteryCellCount = getBatteryCellCount();
+ if (batteryCellCount > 0) {
+ for (int cell=0; cell < batteryCellCount && cell < MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_LEN + MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_EXT_LEN; cell++) {
+ if (cell < MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_LEN) {
+ batteryVoltages[cell] = getBatteryAverageCellVoltage() * 10;
+ } else {
+ batteryVoltagesExt[cell-MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_LEN] = getBatteryAverageCellVoltage() * 10;
+ }
+ }
+ }
+ else {
+ batteryVoltages[0] = getBatteryVoltage() * 10;
+ }
+ }
+ else {
+ batteryVoltages[0] = 0;
+ }
+
+ mavlink_msg_battery_status_pack(mavSystemId, mavComponentId, &mavSendMsg,
+ // id Battery ID
+ 0,
+ // battery_function Function of the battery
+ MAV_BATTERY_FUNCTION_UNKNOWN,
+ // type Type (chemistry) of the battery
+ MAV_BATTERY_TYPE_UNKNOWN,
+ // temperature Temperature of the battery in centi-degrees celsius. INT16_MAX for unknown temperature
+ INT16_MAX,
+ // voltages Battery voltage of cells, in millivolts (1 = 1 millivolt). Cells above the valid cell count for this battery should have the UINT16_MAX value.
+ batteryVoltages,
+ // current_battery Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current
+ isAmperageConfigured() ? getAmperage() : -1,
+ // current_consumed Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate
+ isAmperageConfigured() ? getMAhDrawn() : -1,
+ // energy_consumed Consumed energy, in 100*Joules (intergrated U*I*dt) (1 = 100 Joule), -1: autopilot does not provide energy consumption estimate
+ isAmperageConfigured() ? getMWhDrawn()*36 : -1,
+ // battery_remaining Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery);
+ feature(FEATURE_VBAT) ? calculateBatteryPercentage() : -1,
+ // time_remaining Remaining battery time, 0: autopilot does not provide remaining battery time estimate
+ 0, // TODO this could easily be implemented
+ // charge_state State for extent of discharge, provided by autopilot for warning or external reactions
+ 0,
+ // voltages_ext Battery voltages for cells 11 to 14. Cells above the valid cell count for this battery should have a value of 0, where zero indicates not supported (note, this is different than for the voltages field and allows empty byte truncation). If the measured value is 0 then 1 should be sent instead.
+ batteryVoltagesExt,
+ // mode Battery mode. Default (0) is that battery mode reporting is not supported or battery is in normal-use mode.
+ 0,
+ // fault_bitmask Fault/health indications. These should be set when charge_state is MAV_BATTERY_CHARGE_STATE_FAILED or MAV_BATTERY_CHARGE_STATE_UNHEALTHY (if not, fault reporting is not supported).
+ 0);
+
+ mavlinkSendMessage();
+}
+
+void mavlinkSendScaledPressure(void)
+{
+ int16_t temperature;
+ sensors(SENSOR_BARO) ? getBaroTemperature(&temperature) : getIMUTemperature(&temperature);
+ mavlink_msg_scaled_pressure_pack(mavSystemId, mavComponentId, &mavSendMsg,
+ millis(),
+ 0,
+ 0,
+ temperature * 10,
+ 0);
+
+ mavlinkSendMessage();
+}
+
+void mavlinkSendSystemTime(void)
+{
+ mavlink_msg_system_time_pack(
+ mavSystemId,
+ mavComponentId,
+ &mavSendMsg,
+ 0,
+ millis());
+
+ mavlinkSendMessage();
+}
+
+bool mavlinkSendStatusText(void)
+{
+// FIXME - Status text is limited to boards with USE_OSD
+#ifdef USE_OSD
+ char buff[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN] = {" "};
+ textAttributes_t elemAttr = osdGetSystemMessage(buff, sizeof(buff), false);
+ if (buff[0] != SYM_BLANK) {
+ MAV_SEVERITY severity = MAV_SEVERITY_NOTICE;
+ if (TEXT_ATTRIBUTES_HAVE_BLINK(elemAttr)) {
+ severity = MAV_SEVERITY_CRITICAL;
+ } else if TEXT_ATTRIBUTES_HAVE_INVERTED(elemAttr) {
+ severity = MAV_SEVERITY_WARNING;
+ }
+
+ mavlink_msg_statustext_pack(mavSystemId, mavComponentId, &mavSendMsg,
+ (uint8_t)severity,
+ buff,
+ 0,
+ 0);
+
+ mavlinkSendMessage();
+ return true;
+ }
+#endif
+ return false;
+}
+
+void mavlinkSendBatteryTemperatureStatusText(void)
+{
+ mavlinkSendBatteryStatus();
+ mavlinkSendScaledPressure();
+ mavlinkSendStatusText();
+}
+
+static uint8_t mavlinkGetAutopilotEnum(void)
+{
+ if (mavAutopilotType == MAVLINK_AUTOPILOT_ARDUPILOT) {
+ return MAV_AUTOPILOT_ARDUPILOTMEGA;
+ }
+
+ return MAV_AUTOPILOT_GENERIC;
+}
+
+static uint8_t mavlinkHeadingDeg2FromCd(int32_t headingCd)
+{
+ return (uint8_t)(wrap_36000(headingCd) / 200);
+}
+
+static uint16_t mavlinkComputeHighLatencyFailures(void)
+{
+ uint16_t flags = 0;
+
+#if defined(USE_GPS)
+ if (!(sensors(SENSOR_GPS)
+#ifdef USE_GPS_FIX_ESTIMATION
+ || STATE(GPS_ESTIMATED_FIX)
+#endif
+ ) || gpsSol.fixType == GPS_NO_FIX) {
+ flags |= HL_FAILURE_FLAG_GPS;
+ }
+#endif
+
+#ifdef USE_PITOT
+ if (getHwPitotmeterStatus() != HW_SENSOR_OK) {
+ flags |= HL_FAILURE_FLAG_DIFFERENTIAL_PRESSURE;
+ }
+#endif
+
+ if (getHwBarometerStatus() != HW_SENSOR_OK) {
+ flags |= HL_FAILURE_FLAG_ABSOLUTE_PRESSURE;
+ }
+
+ if (getHwAccelerometerStatus() != HW_SENSOR_OK) {
+ flags |= HL_FAILURE_FLAG_3D_ACCEL;
+ }
+
+ if (getHwGyroStatus() != HW_SENSOR_OK) {
+ flags |= HL_FAILURE_FLAG_3D_GYRO;
+ }
+
+ if (getHwCompassStatus() != HW_SENSOR_OK) {
+ flags |= HL_FAILURE_FLAG_3D_MAG;
+ }
+
+ if (getHwRangefinderStatus() != HW_SENSOR_OK) {
+ flags |= HL_FAILURE_FLAG_TERRAIN;
+ }
+
+ const batteryState_e batteryState = getBatteryState();
+ if (batteryState == BATTERY_WARNING || batteryState == BATTERY_CRITICAL) {
+ flags |= HL_FAILURE_FLAG_BATTERY;
+ }
+
+ if (!rxIsReceivingSignal() || !rxAreFlightChannelsValid()) {
+ flags |= HL_FAILURE_FLAG_RC_RECEIVER;
+ }
+
+ return flags;
+}
+
+void mavlinkSendHighLatency2(timeUs_t currentTimeUs)
+{
+ const bool isPlane = (STATE(FIXED_WING_LEGACY) || mixerConfig()->platformType == PLATFORM_AIRPLANE);
+ const mavlinkModeSelection_t modeSelection = selectMavlinkMode(isPlane);
+
+ int32_t latitude = 0;
+ int32_t longitude = 0;
+ int16_t altitude = (int16_t)constrain((int32_t)(getEstimatedActualPosition(Z) / 100), INT16_MIN, INT16_MAX);
+ int16_t targetAltitude = (int16_t)constrain((int32_t)(posControl.desiredState.pos.z / 100), INT16_MIN, INT16_MAX);
+ uint16_t targetDistance = 0;
+ uint16_t wpNum = 0;
+ uint8_t heading = mavlinkHeadingDeg2FromCd(DECIDEGREES_TO_CENTIDEGREES(attitude.values.yaw));
+ uint8_t targetHeading = mavlinkHeadingDeg2FromCd(posControl.desiredState.yaw);
+ uint8_t groundspeed = 0;
+ uint8_t airspeed = 0;
+ uint8_t airspeedSp = 0;
+ uint8_t windspeed = 0;
+ uint8_t windHeading = 0;
+ uint8_t eph = UINT8_MAX;
+ uint8_t epv = UINT8_MAX;
+ int8_t temperatureAir = 0;
+ int8_t climbRate = (int8_t)constrain(lrintf(getEstimatedActualVelocity(Z) / 10.0f), INT8_MIN, INT8_MAX);
+ int8_t battery = feature(FEATURE_VBAT) ? (int8_t)calculateBatteryPercentage() : -1;
+
+#if defined(USE_GPS)
+ if (sensors(SENSOR_GPS)
+#ifdef USE_GPS_FIX_ESTIMATION
+ || STATE(GPS_ESTIMATED_FIX)
+#endif
+ ) {
+ latitude = gpsSol.llh.lat;
+ longitude = gpsSol.llh.lon;
+ altitude = (int16_t)constrain((int32_t)(gpsSol.llh.alt / 100), INT16_MIN, INT16_MAX);
+
+ const int32_t desiredAltCm = lrintf(posControl.desiredState.pos.z);
+ const int32_t targetAltCm = GPS_home.alt + desiredAltCm;
+ targetAltitude = (int16_t)constrain(targetAltCm / 100, INT16_MIN, INT16_MAX);
+
+ groundspeed = (uint8_t)constrain(lrintf(gpsSol.groundSpeed / 20.0f), 0, UINT8_MAX);
+
+ if (gpsSol.flags.validEPE) {
+ eph = (uint8_t)constrain((gpsSol.eph + 5) / 10, 0, UINT8_MAX);
+ epv = (uint8_t)constrain((gpsSol.epv + 5) / 10, 0, UINT8_MAX);
+ }
+
+ if (posControl.activeWaypointIndex >= 0) {
+ wpNum = (uint16_t)posControl.activeWaypointIndex;
+ targetDistance = (uint16_t)constrain(lrintf(posControl.wpDistance / 1000.0f), 0, UINT16_MAX);
+ }
+ }
+#endif
+
+#if defined(USE_PITOT)
+ if (sensors(SENSOR_PITOT) && pitotIsHealthy()) {
+ airspeed = (uint8_t)constrain(lrintf(getAirspeedEstimate() / 20.0f), 0, UINT8_MAX);
+ airspeedSp = airspeed;
+ }
+#endif
+
+ if (airspeedSp == 0) {
+ const float desiredVelXY = calc_length_pythagorean_2D(posControl.desiredState.vel.x, posControl.desiredState.vel.y);
+ airspeedSp = (uint8_t)constrain(lrintf(desiredVelXY / 20.0f), 0, UINT8_MAX);
+ }
+
+ if (airspeed == 0) {
+ airspeed = groundspeed;
+ }
+
+#ifdef USE_WIND_ESTIMATOR
+ if (isEstimatedWindSpeedValid()) {
+ uint16_t windAngleCd = 0;
+ const float windHoriz = getEstimatedHorizontalWindSpeed(&windAngleCd);
+ windspeed = (uint8_t)constrain(lrintf(windHoriz / 20.0f), 0, UINT8_MAX);
+ windHeading = mavlinkHeadingDeg2FromCd(windAngleCd);
+ }
+#endif
+
+ int16_t temperature;
+ sensors(SENSOR_BARO) ? getBaroTemperature(&temperature) : getIMUTemperature(&temperature);
+ temperatureAir = (int8_t)constrain(temperature, INT8_MIN, INT8_MAX);
+
+ const uint16_t failureFlags = mavlinkComputeHighLatencyFailures();
+
+ mavlink_msg_high_latency2_pack(
+ mavSystemId,
+ mavComponentId,
+ &mavSendMsg,
+ (uint32_t)(currentTimeUs / 1000),
+ mavlinkGetVehicleType(),
+ mavlinkGetAutopilotEnum(),
+ modeSelection.customMode,
+ latitude,
+ longitude,
+ altitude,
+ targetAltitude,
+ heading,
+ targetHeading,
+ targetDistance,
+ (uint8_t)constrain(getThrottlePercent(osdUsingScaledThrottle()), 0, 100),
+ airspeed,
+ airspeedSp,
+ groundspeed,
+ windspeed,
+ windHeading,
+ eph,
+ epv,
+ temperatureAir,
+ climbRate,
+ battery,
+ wpNum,
+ failureFlags,
+ 0,
+ 0,
+ 0);
+
+ mavlinkSendMessage();
+}
+
+
+static void mavlinkResetIncomingMissionTransaction(void);
+
+static bool handleIncoming_MISSION_CLEAR_ALL(void)
+{
+ mavlink_mission_clear_all_t msg;
+ mavlink_msg_mission_clear_all_decode(&mavlinkContext.recvMsg, &msg);
+
+ // Check if this message is for us
+ if (msg.target_system == mavSystemId) {
+ resetWaypointList();
+ mavlinkResetIncomingMissionTransaction();
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_ACCEPTED, MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
+ return true;
+ }
+
+ return false;
+}
+
+static void mavlinkResetIncomingMissionTransaction(void)
+{
+ incomingMissionWpCount = 0;
+ incomingMissionWpSequence = 0;
+ incomingMissionSourceSystem = 0;
+ incomingMissionSourceComponent = 0;
+ incomingMissionLastActivityMs = 0;
+}
+
+static void mavlinkStartIncomingMissionTransaction(int missionCount)
+{
+ incomingMissionWpCount = missionCount;
+ incomingMissionWpSequence = 0;
+ incomingMissionSourceSystem = mavlinkContext.recvMsg.sysid;
+ incomingMissionSourceComponent = mavlinkContext.recvMsg.compid;
+ incomingMissionLastActivityMs = millis();
+}
+
+static void mavlinkTouchIncomingMissionTransaction(void)
+{
+ incomingMissionLastActivityMs = millis();
+}
+
+static bool mavlinkIsIncomingMissionTransactionActive(void)
+{
+ if (incomingMissionWpCount <= 0) {
+ return false;
+ }
+
+ if ((timeMs_t)(millis() - incomingMissionLastActivityMs) > MAVLINK_MISSION_UPLOAD_TIMEOUT_MS) {
+ mavlinkResetIncomingMissionTransaction();
+ return false;
+ }
+
+ return true;
+}
+
+static bool mavlinkIsIncomingMissionTransactionOwner(void)
+{
+ return mavlinkContext.recvMsg.sysid == incomingMissionSourceSystem &&
+ mavlinkContext.recvMsg.compid == incomingMissionSourceComponent;
+}
+
+static bool mavlinkHandleMissionItemCommon(bool useIntMessages, uint8_t frame, uint16_t command, uint8_t autocontinue, uint16_t seq, float param1, float param2, float param3, float param4, int32_t lat, int32_t lon, float altMeters)
+{
+ if (!mavlinkIsIncomingMissionTransactionActive() || !mavlinkIsIncomingMissionTransactionOwner()) {
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_INVALID_SEQUENCE, MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
+ return true;
+ }
+
+ mavlinkTouchIncomingMissionTransaction();
+
+ const bool lastMissionItem = incomingMissionWpCount > 0 && ((int)seq + 1 >= incomingMissionWpCount);
+
+ if (autocontinue == 0 && !lastMissionItem) {
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_UNSUPPORTED, MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
+ return true;
+ }
+
+ UNUSED(param3);
+
+ navWaypoint_t wp;
+ memset(&wp, 0, sizeof(wp));
+
+ switch (command) {
+ case MAV_CMD_NAV_WAYPOINT:
+ if (!mavlinkFrameIsSupported(frame,
+ MAV_FRAME_SUPPORTED_GLOBAL |
+ MAV_FRAME_SUPPORTED_GLOBAL_INT |
+ MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT |
+ MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT_INT)) {
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_UNSUPPORTED_FRAME, MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
+ return true;
+ }
+ wp.action = NAV_WP_ACTION_WAYPOINT;
+ wp.lat = lat;
+ wp.lon = lon;
+ wp.alt = (int32_t)(altMeters * 100.0f);
+ wp.p1 = 0;
+ wp.p2 = 0;
+ wp.p3 = mavlinkFrameUsesAbsoluteAltitude(frame) ? NAV_WP_ALTMODE : 0;
+ break;
+
+ case MAV_CMD_NAV_LOITER_TIME:
+ if (!mavlinkFrameIsSupported(frame,
+ MAV_FRAME_SUPPORTED_GLOBAL |
+ MAV_FRAME_SUPPORTED_GLOBAL_INT |
+ MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT |
+ MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT_INT)) {
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_UNSUPPORTED_FRAME, MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
+ return true;
+ }
+ wp.action = NAV_WP_ACTION_HOLD_TIME;
+ wp.lat = lat;
+ wp.lon = lon;
+ wp.alt = (int32_t)(altMeters * 100.0f);
+ wp.p1 = (int16_t)lrintf(param1);
+ wp.p2 = 0;
+ wp.p3 = mavlinkFrameUsesAbsoluteAltitude(frame) ? NAV_WP_ALTMODE : 0;
+ break;
+
+ case MAV_CMD_NAV_RETURN_TO_LAUNCH:
+ {
+ const bool coordinateFrame = mavlinkFrameIsSupported(frame,
+ MAV_FRAME_SUPPORTED_GLOBAL |
+ MAV_FRAME_SUPPORTED_GLOBAL_INT |
+ MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT |
+ MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT_INT);
+
+ if (!coordinateFrame && frame != MAV_FRAME_MISSION) {
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_UNSUPPORTED_FRAME, MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
+ return true;
+ }
+ wp.action = NAV_WP_ACTION_RTH;
+ wp.lat = 0;
+ wp.lon = 0;
+ wp.alt = coordinateFrame ? (int32_t)(altMeters * 100.0f) : 0;
+ wp.p1 = 0; // Land if non-zero
+ wp.p2 = 0;
+ wp.p3 = mavlinkFrameUsesAbsoluteAltitude(frame) ? NAV_WP_ALTMODE : 0;
+ break;
+ }
+
+ case MAV_CMD_NAV_LAND:
+ if (!mavlinkFrameIsSupported(frame,
+ MAV_FRAME_SUPPORTED_GLOBAL |
+ MAV_FRAME_SUPPORTED_GLOBAL_INT |
+ MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT |
+ MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT_INT)) {
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_UNSUPPORTED_FRAME, MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
+ return true;
+ }
+ wp.action = NAV_WP_ACTION_LAND;
+ wp.lat = lat;
+ wp.lon = lon;
+ wp.alt = (int32_t)(altMeters * 100.0f);
+ wp.p1 = 0; // Speed (cm/s)
+ wp.p2 = 0; // Elevation Adjustment (m): P2 defines the ground elevation (in metres) for the LAND WP. If the altitude mode is absolute, this is also absolute; for relative altitude, then it is the difference between the assumed home location and the LAND WP.
+ wp.p3 = mavlinkFrameUsesAbsoluteAltitude(frame) ? NAV_WP_ALTMODE : 0; // Altitude Mode & Actions, P3 defines the altitude mode. 0 (default, legacy) = Relative to Home, 1 = Absolute (AMSL).
+ break;
+
+ case MAV_CMD_DO_JUMP:
+ if (frame != MAV_FRAME_MISSION) {
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_UNSUPPORTED_FRAME, MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
+ return true;
+ }
+ if (param1 < 0.0f) {
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_UNSUPPORTED, MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
+ return true;
+ }
+ wp.lat = 0;
+ wp.lon = 0;
+ wp.alt = 0;
+ wp.action = NAV_WP_ACTION_JUMP;
+ wp.p1 = (int16_t)lrintf(param1 + 1.0f);
+ wp.p2 = (int16_t)lrintf(param2);
+ wp.p3 = 0;
+ break;
+
+ case MAV_CMD_DO_SET_ROI:
+ if (param1 != MAV_ROI_LOCATION ||
+ !mavlinkFrameIsSupported(frame,
+ MAV_FRAME_SUPPORTED_GLOBAL |
+ MAV_FRAME_SUPPORTED_GLOBAL_INT |
+ MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT |
+ MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT_INT)) {
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_UNSUPPORTED, MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
+ return true;
+ }
+ wp.action = NAV_WP_ACTION_SET_POI;
+ wp.lat = lat;
+ wp.lon = lon;
+ wp.alt = (int32_t)(altMeters * 100.0f);
+ wp.p1 = 0;
+ wp.p2 = 0;
+ wp.p3 = mavlinkFrameUsesAbsoluteAltitude(frame) ? NAV_WP_ALTMODE : 0;
+ break;
+
+ case MAV_CMD_CONDITION_YAW:
+ if (frame != MAV_FRAME_MISSION) {
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_UNSUPPORTED_FRAME, MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
+ return true;
+ }
+ if (param4 != 0.0f) {
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_UNSUPPORTED, MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
+ return true;
+ }
+ wp.lat = 0;
+ wp.lon = 0;
+ wp.alt = 0;
+ wp.action = NAV_WP_ACTION_SET_HEAD;
+ wp.p1 = (int16_t)lrintf(param1);
+ wp.p2 = 0;
+ wp.p3 = 0;
+ break;
+
+ default:
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_UNSUPPORTED, MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
+ return true;
+ }
+
+ if (seq == incomingMissionWpSequence) {
+ incomingMissionWpSequence++;
+
+ wp.flag = (incomingMissionWpSequence >= incomingMissionWpCount) ? NAV_WP_FLAG_LAST : 0;
+
+ setWaypoint(incomingMissionWpSequence, &wp);
+
+ if (incomingMissionWpSequence >= incomingMissionWpCount) {
+ if (isWaypointListValid()) {
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_ACCEPTED, MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
+ }
+ else {
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_INVALID, MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
+ }
+ mavlinkResetIncomingMissionTransaction();
+ }
+ else {
+ if (useIntMessages) {
+ mavlink_msg_mission_request_int_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, incomingMissionWpSequence, MAV_MISSION_TYPE_MISSION);
+ } else {
+ mavlink_msg_mission_request_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, incomingMissionWpSequence, MAV_MISSION_TYPE_MISSION);
+ }
+ mavlinkSendMessage();
+ }
+ }
+ else {
+ // If we get a duplicate of the last accepted item, re-request the next one instead of aborting.
+ if (seq + 1 == incomingMissionWpSequence) {
+ mavlinkTouchIncomingMissionTransaction();
+ if (useIntMessages) {
+ mavlink_msg_mission_request_int_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, incomingMissionWpSequence, MAV_MISSION_TYPE_MISSION);
+ } else {
+ mavlink_msg_mission_request_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, incomingMissionWpSequence, MAV_MISSION_TYPE_MISSION);
+ }
+ mavlinkSendMessage();
+ } else {
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_INVALID_SEQUENCE, MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
+ }
+ }
+
+ return true;
+}
+
+static bool handleIncoming_MISSION_COUNT(void)
+{
+ mavlink_mission_count_t msg;
+ mavlink_msg_mission_count_decode(&mavlinkContext.recvMsg, &msg);
+
+ // Check if this message is for us
+ if (msg.target_system == mavSystemId) {
+ mavlinkResetIncomingMissionTransaction();
+ if (ARMING_FLAG(ARMED)) {
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_ERROR, MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
+ return true;
+ }
+ if (msg.count == 0) {
+ resetWaypointList();
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_ACCEPTED, MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
+ return true;
+ }
+ if (msg.count <= NAV_MAX_WAYPOINTS) {
+ mavlinkStartIncomingMissionTransaction(msg.count);
+ mavlink_msg_mission_request_int_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, incomingMissionWpSequence, MAV_MISSION_TYPE_MISSION);
+ mavlinkSendMessage();
+ return true;
+ } else {
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_NO_SPACE, MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
+ return true;
+ }
+ }
+
+ return false;
+}
+
+static bool handleIncoming_MISSION_ITEM(void)
+{
+ mavlink_mission_item_t msg;
+ mavlink_msg_mission_item_decode(&mavlinkContext.recvMsg, &msg);
+
+ if (msg.target_system != mavSystemId) {
+ return false;
+ }
+
+ if (ARMING_FLAG(ARMED)) {
+ if (msg.command == MAV_CMD_NAV_WAYPOINT) {
+ return mavlinkHandleArmedGuidedMissionItem(msg.current, msg.frame,
+ MAV_FRAME_SUPPORTED_GLOBAL | MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT,
+ (int32_t)lrintf(msg.x * 1e7f), (int32_t)lrintf(msg.y * 1e7f), msg.z);
+ }
+
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_ERROR, MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
+ return true;
+ }
+
+ return mavlinkHandleMissionItemCommon(false, msg.frame, msg.command, msg.autocontinue, msg.seq, msg.param1, msg.param2, msg.param3, msg.param4, (int32_t)(msg.x * 1e7f), (int32_t)(msg.y * 1e7f), msg.z);
+}
+
+static bool handleIncoming_MISSION_REQUEST_LIST(void)
+{
+ mavlink_mission_request_list_t msg;
+ mavlink_msg_mission_request_list_decode(&mavlinkContext.recvMsg, &msg);
+
+ // Check if this message is for us
+ if (msg.target_system == mavSystemId) {
+ mavlink_msg_mission_count_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, getWaypointCount(), MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
+ return true;
+ }
+
+ return false;
+}
+
+static bool fillMavlinkMissionItemFromWaypoint(const navWaypoint_t *wp, bool useIntMessages, mavlinkMissionItemData_t *item)
+{
+ mavlinkMissionItemData_t data = {0};
+
+ data.frame = navWaypointFrame(wp, useIntMessages);
+
+ switch (wp->action) {
+ case NAV_WP_ACTION_WAYPOINT:
+ data.command = MAV_CMD_NAV_WAYPOINT;
+ data.lat = wp->lat;
+ data.lon = wp->lon;
+ data.alt = wp->alt / 100.0f;
+ break;
+
+ case NAV_WP_ACTION_HOLD_TIME:
+ data.command = MAV_CMD_NAV_LOITER_TIME;
+ data.param1 = wp->p1;
+ data.lat = wp->lat;
+ data.lon = wp->lon;
+ data.alt = wp->alt / 100.0f;
+ break;
+
+ case NAV_WP_ACTION_RTH:
+ data.command = MAV_CMD_NAV_RETURN_TO_LAUNCH;
+ break;
+
+ case NAV_WP_ACTION_LAND:
+ data.command = MAV_CMD_NAV_LAND;
+ data.lat = wp->lat;
+ data.lon = wp->lon;
+ data.alt = wp->alt / 100.0f;
+ break;
+
+ case NAV_WP_ACTION_JUMP:
+ data.command = MAV_CMD_DO_JUMP;
+ data.param1 = (wp->p1 > 0) ? (float)(wp->p1 - 1) : 0.0f;
+ data.param2 = wp->p2;
+ break;
+
+ case NAV_WP_ACTION_SET_POI:
+ data.command = MAV_CMD_DO_SET_ROI;
+ data.param1 = MAV_ROI_LOCATION;
+ data.lat = wp->lat;
+ data.lon = wp->lon;
+ data.alt = wp->alt / 100.0f;
+ break;
+
+ case NAV_WP_ACTION_SET_HEAD:
+ data.command = MAV_CMD_CONDITION_YAW;
+ data.param1 = wp->p1;
+ break;
+
+ default:
+ return false;
+ }
+
+ *item = data;
+ return true;
+}
+
+static bool handleIncoming_MISSION_REQUEST(void)
+{
+ mavlink_mission_request_t msg;
+ mavlink_msg_mission_request_decode(&mavlinkContext.recvMsg, &msg);
+
+ if (msg.target_system != mavSystemId) {
+ return false;
+ }
+
+ int wpCount = getWaypointCount();
+
+ if (msg.seq < wpCount) {
+ navWaypoint_t wp;
+ getWaypoint(msg.seq + 1, &wp);
+
+ mavlinkMissionItemData_t item;
+ if (fillMavlinkMissionItemFromWaypoint(&wp, false, &item)) {
+ mavlink_msg_mission_item_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid,
+ msg.seq,
+ item.frame,
+ item.command,
+ 0,
+ 1,
+ item.param1, item.param2, item.param3, item.param4,
+ item.lat / 1e7f,
+ item.lon / 1e7f,
+ item.alt,
+ MAV_MISSION_TYPE_MISSION);
+ mavlinkSendMessage();
+ } else {
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_ERROR, MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
+ }
+ }
+ else {
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_INVALID_SEQUENCE, MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
+ }
+
+ return true;
+}
+
+static bool mavlinkIsLocalTarget(uint8_t targetSystem, uint8_t targetComponent)
+{
+ if (targetSystem != 0 && targetSystem != mavSystemId) {
+ return false;
+ }
+
+ if (targetComponent != 0 && targetComponent != mavComponentId) {
+ return false;
+ }
+
+ return true;
+}
+
+static void mavlinkSendCommandAck(uint16_t command, MAV_RESULT result, uint8_t ackTargetSystem, uint8_t ackTargetComponent)
+{
+ mavlink_msg_command_ack_pack(mavSystemId, mavComponentId, &mavSendMsg,
+ command,
+ result,
+ 0,
+ 0,
+ ackTargetSystem,
+ ackTargetComponent);
+ mavlinkSendMessage();
+}
+
+static bool handleIncoming_COMMAND(uint8_t targetSystem, uint8_t targetComponent, uint8_t ackTargetSystem, uint8_t ackTargetComponent, uint16_t command, uint8_t frame, float param1, float param2, float param3, float param4, float latitudeDeg, float longitudeDeg, float altitudeMeters)
+{
+ if (!mavlinkIsLocalTarget(targetSystem, targetComponent)) {
+ return false;
+ }
+ UNUSED(param3);
+
+ switch (command) {
+ case MAV_CMD_DO_REPOSITION:
+ if (!mavlinkFrameIsSupported(frame,
+ MAV_FRAME_SUPPORTED_GLOBAL |
+ MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT |
+ MAV_FRAME_SUPPORTED_GLOBAL_INT |
+ MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT_INT)) {
+ mavlinkSendCommandAck(command, MAV_RESULT_UNSUPPORTED, ackTargetSystem, ackTargetComponent);
+ return true;
+ }
+
+ if (isnan(latitudeDeg) || isnan(longitudeDeg)) {
+ mavlinkSendCommandAck(command, MAV_RESULT_FAILED, ackTargetSystem, ackTargetComponent);
+ return true;
+ }
+
+ if (isGCSValid()) {
+ navWaypoint_t wp = {0};
+ wp.action = NAV_WP_ACTION_WAYPOINT;
+ wp.lat = (int32_t)(latitudeDeg * 1e7f);
+ wp.lon = (int32_t)(longitudeDeg * 1e7f);
+ wp.alt = (int32_t)(altitudeMeters * 100.0f);
+ if (!isnan(param4) && param4 >= 0.0f && param4 < 360.0f) {
+ wp.p1 = (int16_t)param4;
+ } else {
+ wp.p1 = 0;
+ }
+ wp.p2 = 0;
+ wp.p3 = mavlinkFrameUsesAbsoluteAltitude(frame) ? NAV_WP_ALTMODE : 0;
+ wp.flag = 0;
+
+ setWaypoint(255, &wp);
+
+ mavlinkSendCommandAck(command, MAV_RESULT_ACCEPTED, ackTargetSystem, ackTargetComponent);
+ } else {
+ mavlinkSendCommandAck(command, MAV_RESULT_DENIED, ackTargetSystem, ackTargetComponent);
+ }
+ return true;
+ case MAV_CMD_DO_CHANGE_ALTITUDE:
+ {
+ const MAV_RESULT result = mavlinkSetAltitudeTargetFromFrame((uint8_t)lrintf(param2), param1);
+ mavlinkSendCommandAck(command, result, ackTargetSystem, ackTargetComponent);
+ return true;
+ }
+ case MAV_CMD_CONDITION_YAW:
+ {
+ if (!(navGetCurrentStateFlags() & NAV_CTL_YAW)) {
+ mavlinkSendCommandAck(command, MAV_RESULT_DENIED, ackTargetSystem, ackTargetComponent);
+ return true;
+ }
+
+ int32_t targetHeadingCd = wrap_36000((int32_t)lrintf(param1 * 100.0f));
+
+ if (param4 != 0.0f) {
+ const int32_t currentHeadingCd = STATE(AIRPLANE) ? posControl.actualState.cog : posControl.actualState.yaw;
+ const int32_t headingChangeCd = (int32_t)lrintf(fabsf(param1) * 100.0f);
+
+ if (param3 < 0.0f) {
+ targetHeadingCd = wrap_36000(currentHeadingCd - headingChangeCd);
+ } else {
+ targetHeadingCd = wrap_36000(currentHeadingCd + headingChangeCd);
+ }
+ }
+
+ updateHeadingHoldTarget(CENTIDEGREES_TO_DEGREES(targetHeadingCd));
+ posControl.desiredState.yaw = targetHeadingCd;
+ posControl.cruise.course = targetHeadingCd;
+ posControl.cruise.previousCourse = targetHeadingCd;
+
+ mavlinkSendCommandAck(command, MAV_RESULT_ACCEPTED, ackTargetSystem, ackTargetComponent);
+ return true;
+ }
+ case MAV_CMD_SET_MESSAGE_INTERVAL:
+ {
+ mavlinkPeriodicMessage_e periodicMessage;
+ MAV_RESULT result = MAV_RESULT_UNSUPPORTED;
+
+ if (mavlinkPeriodicMessageFromMessageId((uint16_t)param1, &periodicMessage)) {
+ if (param2 == 0.0f) {
+ mavlinkSetMessageOverrideIntervalUs(periodicMessage, 0);
+ result = MAV_RESULT_ACCEPTED;
+ } else if (param2 < 0.0f) {
+ mavlinkSetMessageOverrideIntervalUs(periodicMessage, -1);
+ result = MAV_RESULT_ACCEPTED;
+ } else {
+ uint32_t intervalUs = (uint32_t)param2;
+ if (intervalUs > 0) {
+ const uint32_t minIntervalUs = 1000000UL / TELEMETRY_MAVLINK_MAXRATE;
+ if (intervalUs < minIntervalUs) {
+ intervalUs = minIntervalUs;
+ }
+
+ mavlinkSetMessageOverrideIntervalUs(periodicMessage, (int32_t)intervalUs);
+ result = MAV_RESULT_ACCEPTED;
+ }
+ }
+ }
+
+ mavlinkSendCommandAck(command, result, ackTargetSystem, ackTargetComponent);
+ return true;
+ }
+ case MAV_CMD_GET_MESSAGE_INTERVAL:
+ {
+ mavlinkPeriodicMessage_e periodicMessage;
+ if (!mavlinkPeriodicMessageFromMessageId((uint16_t)param1, &periodicMessage)) {
+ mavlinkSendCommandAck(command, MAV_RESULT_UNSUPPORTED, ackTargetSystem, ackTargetComponent);
+ return true;
+ }
+
+ mavlink_msg_message_interval_pack(
+ mavSystemId,
+ mavComponentId,
+ &mavSendMsg,
+ (uint16_t)param1,
+ mavlinkMessageIntervalUs(periodicMessage));
+ mavlinkSendMessage();
+
+ mavlinkSendCommandAck(command, MAV_RESULT_ACCEPTED, ackTargetSystem, ackTargetComponent);
+ return true;
+ }
+ case MAV_CMD_CONTROL_HIGH_LATENCY:
+ if (param1 == 0.0f || param1 == 1.0f) {
+ if (mavlinkGetProtocolVersion() == 1 && param1 > 0.5f) {
+ mavlinkSendCommandAck(command, MAV_RESULT_UNSUPPORTED, ackTargetSystem, ackTargetComponent);
+ return true;
+ }
+
+ mavActivePort->highLatencyEnabled = param1 > 0.5f;
+ if (mavActivePort->highLatencyEnabled) {
+ mavActivePort->lastHighLatencyMessageUs = 0;
+ }
+ mavlinkSendCommandAck(command, MAV_RESULT_ACCEPTED, ackTargetSystem, ackTargetComponent);
+ } else {
+ mavlinkSendCommandAck(command, MAV_RESULT_FAILED, ackTargetSystem, ackTargetComponent);
+ }
+ return true;
+ case MAV_CMD_REQUEST_PROTOCOL_VERSION:
+ if (mavlinkGetProtocolVersion() == 1) {
+ mavlinkSendCommandAck(command, MAV_RESULT_UNSUPPORTED, ackTargetSystem, ackTargetComponent);
+ } else {
+ mavlinkSendProtocolVersion();
+ mavlinkSendCommandAck(command, MAV_RESULT_ACCEPTED, ackTargetSystem, ackTargetComponent);
+ }
+ return true;
+ case MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES:
+ if (mavlinkGetProtocolVersion() == 1) {
+ mavlinkSendCommandAck(command, MAV_RESULT_UNSUPPORTED, ackTargetSystem, ackTargetComponent);
+ } else {
+ mavlinkSendAutopilotVersion();
+ mavlinkSendCommandAck(command, MAV_RESULT_ACCEPTED, ackTargetSystem, ackTargetComponent);
+ }
+ return true;
+ case MAV_CMD_REQUEST_MESSAGE:
+ {
+ bool sent = false;
+ uint16_t messageId = (uint16_t)param1;
+
+ switch (messageId) {
+ case MAVLINK_MSG_ID_HEARTBEAT:
+ mavlinkSendHeartbeat();
+ sent = true;
+ break;
+ case MAVLINK_MSG_ID_AUTOPILOT_VERSION:
+ if (mavlinkGetProtocolVersion() != 1) {
+ mavlinkSendAutopilotVersion();
+ sent = true;
+ }
+ break;
+ case MAVLINK_MSG_ID_PROTOCOL_VERSION:
+ if (mavlinkGetProtocolVersion() != 1) {
+ mavlinkSendProtocolVersion();
+ sent = true;
+ }
+ break;
+ case MAVLINK_MSG_ID_SYS_STATUS:
+ mavlinkSendSystemStatus();
+ sent = true;
+ break;
+ case MAVLINK_MSG_ID_ATTITUDE:
+ mavlinkSendAttitude();
+ sent = true;
+ break;
+ case MAVLINK_MSG_ID_VFR_HUD:
+ mavlinkSendVfrHud();
+ sent = true;
+ break;
+ case MAVLINK_MSG_ID_AVAILABLE_MODES:
+ {
+ const bool isPlane = mixerConfig()->platformType == PLATFORM_AIRPLANE || STATE(FIXED_WING_LEGACY);
+ const mavlinkModeSelection_t modeSelection = selectMavlinkMode(isPlane);
+ if (isPlane) {
+ mavlinkSendAvailableModes(planeModes, planeModesCount, modeSelection.customMode, mavlinkPlaneModeIsConfigured);
+ } else {
+ mavlinkSendAvailableModes(copterModes, copterModesCount, modeSelection.customMode, mavlinkCopterModeIsConfigured);
+ }
+ sent = true;
+ }
+ break;
+ case MAVLINK_MSG_ID_CURRENT_MODE:
+ {
+ const bool isPlane = mixerConfig()->platformType == PLATFORM_AIRPLANE || STATE(FIXED_WING_LEGACY);
+ const mavlinkModeSelection_t modeSelection = selectMavlinkMode(isPlane);
+ mavlink_msg_current_mode_pack(
+ mavSystemId,
+ mavComponentId,
+ &mavSendMsg,
+ MAV_STANDARD_MODE_NON_STANDARD,
+ modeSelection.customMode,
+ modeSelection.customMode);
+ mavlinkSendMessage();
+ sent = true;
+ }
+ break;
+ case MAVLINK_MSG_ID_EXTENDED_SYS_STATE:
+ mavlinkSendExtendedSysState();
+ sent = true;
+ break;
+ case MAVLINK_MSG_ID_RC_CHANNELS:
+ case MAVLINK_MSG_ID_RC_CHANNELS_RAW:
+ case MAVLINK_MSG_ID_RC_CHANNELS_SCALED:
+ mavlinkSendRCChannelsAndRSSI();
+ sent = true;
+ break;
+ case MAVLINK_MSG_ID_GPS_RAW_INT:
+ #ifdef USE_GPS
+ mavlinkSendGpsRawInt(micros());
+ sent = true;
+ #endif
+ break;
+ case MAVLINK_MSG_ID_GLOBAL_POSITION_INT:
+ #ifdef USE_GPS
+ mavlinkSendGlobalPositionInt(micros());
+ sent = true;
+ #endif
+ break;
+ case MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN:
+ #ifdef USE_GPS
+ mavlinkSendGpsGlobalOrigin();
+ sent = true;
+ #endif
+ break;
+ case MAVLINK_MSG_ID_BATTERY_STATUS:
+ mavlinkSendBatteryStatus();
+ sent = true;
+ break;
+ case MAVLINK_MSG_ID_SCALED_PRESSURE:
+ mavlinkSendScaledPressure();
+ sent = true;
+ break;
+ case MAVLINK_MSG_ID_SYSTEM_TIME:
+ mavlinkSendSystemTime();
+ sent = true;
+ break;
+ case MAVLINK_MSG_ID_STATUSTEXT:
+ sent = mavlinkSendStatusText();
+ break;
+ case MAVLINK_MSG_ID_HOME_POSITION:
+ #ifdef USE_GPS
+ if (STATE(GPS_FIX_HOME)) {
+ mavlinkSendHomePosition();
+ sent = true;
+ }
+ #endif
+ break;
+ default:
+ break;
+ }
+
+ mavlinkSendCommandAck(command, sent ? MAV_RESULT_ACCEPTED : MAV_RESULT_UNSUPPORTED, ackTargetSystem, ackTargetComponent);
+ return true;
+ }
+#ifdef USE_GPS
+ case MAV_CMD_GET_HOME_POSITION:
+ if (STATE(GPS_FIX_HOME)) {
+ mavlinkSendHomePosition();
+ mavlinkSendCommandAck(command, MAV_RESULT_ACCEPTED, ackTargetSystem, ackTargetComponent);
+ } else {
+ mavlinkSendCommandAck(command, MAV_RESULT_FAILED, ackTargetSystem, ackTargetComponent);
+ }
+ return true;
+#endif
+ default:
+ mavlinkSendCommandAck(command, MAV_RESULT_UNSUPPORTED, ackTargetSystem, ackTargetComponent);
+ return true;
+ }
+}
+
+static bool handleIncoming_COMMAND_INT(void)
+{
+ mavlink_command_int_t msg;
+ mavlink_msg_command_int_decode(&mavlinkContext.recvMsg, &msg);
+
+ return handleIncoming_COMMAND(msg.target_system, msg.target_component, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, msg.command, msg.frame, msg.param1, msg.param2, msg.param3, msg.param4, (float)msg.x / 1e7f, (float)msg.y / 1e7f, msg.z);
+}
+
+static bool handleIncoming_COMMAND_LONG(void)
+{
+ mavlink_command_long_t msg;
+ mavlink_msg_command_long_decode(&mavlinkContext.recvMsg, &msg);
+
+ // COMMAND_LONG has no frame field; location commands are WGS84 global by definition.
+ return handleIncoming_COMMAND(msg.target_system, msg.target_component, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, msg.command, MAV_FRAME_GLOBAL, msg.param1, msg.param2, msg.param3, msg.param4, msg.param5, msg.param6, msg.param7);
+}
+
+static bool handleIncoming_MISSION_ITEM_INT(void)
+{
+ mavlink_mission_item_int_t msg;
+ mavlink_msg_mission_item_int_decode(&mavlinkContext.recvMsg, &msg);
+
+ if (msg.target_system != mavSystemId) {
+ return false;
+ }
+
+ if (ARMING_FLAG(ARMED)) {
+ if (msg.command == MAV_CMD_NAV_WAYPOINT) {
+ return mavlinkHandleArmedGuidedMissionItem(msg.current, msg.frame,
+ MAV_FRAME_SUPPORTED_GLOBAL_INT | MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT_INT,
+ msg.x, msg.y, msg.z);
+ }
+
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_ERROR, MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
+ return true;
+ }
+
+ return mavlinkHandleMissionItemCommon(true, msg.frame, msg.command, msg.autocontinue, msg.seq, msg.param1, msg.param2, msg.param3, msg.param4, msg.x, msg.y, msg.z);
+}
+
+static bool handleIncoming_MISSION_REQUEST_INT(void)
+{
+ mavlink_mission_request_int_t msg;
+ mavlink_msg_mission_request_int_decode(&mavlinkContext.recvMsg, &msg);
+
+ if (msg.target_system != mavSystemId) {
+ return false;
+ }
+
+ int wpCount = getWaypointCount();
+
+ if (msg.seq < wpCount) {
+ navWaypoint_t wp;
+ getWaypoint(msg.seq + 1, &wp);
+
+ mavlinkMissionItemData_t item;
+ if (fillMavlinkMissionItemFromWaypoint(&wp, true, &item)) {
+ mavlink_msg_mission_item_int_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid,
+ msg.seq,
+ item.frame,
+ item.command,
+ 0,
+ 1,
+ item.param1, item.param2, item.param3, item.param4,
+ item.lat,
+ item.lon,
+ item.alt,
+ MAV_MISSION_TYPE_MISSION);
+ mavlinkSendMessage();
+ } else {
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_ERROR, MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
+ }
+ }
+ else {
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_INVALID_SEQUENCE, MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
+ }
+
+ return true;
+}
+
+static bool handleIncoming_REQUEST_DATA_STREAM(void)
+{
+ mavlink_request_data_stream_t msg;
+ mavlink_msg_request_data_stream_decode(&mavlinkContext.recvMsg, &msg);
+
+ if (!mavlinkIsLocalTarget(msg.target_system, msg.target_component)) {
+ return false;
+ }
+
+ uint8_t rate = 0;
+ if (msg.start_stop != 0) {
+ rate = (uint8_t)msg.req_message_rate;
+ if (rate > TELEMETRY_MAVLINK_MAXRATE) {
+ rate = TELEMETRY_MAVLINK_MAXRATE;
+ }
+ }
+
+ if (msg.req_stream_id == MAV_DATA_STREAM_ALL) {
+ mavlinkSetStreamRate(MAV_DATA_STREAM_EXTENDED_STATUS, rate);
+ mavlinkSetStreamRate(MAV_DATA_STREAM_RC_CHANNELS, rate);
+ mavlinkSetStreamRate(MAV_DATA_STREAM_POSITION, rate);
+ mavlinkSetStreamRate(MAV_DATA_STREAM_EXTRA1, rate);
+ mavlinkSetStreamRate(MAV_DATA_STREAM_EXTRA2, rate);
+ mavlinkSetStreamRate(MAV_DATA_STREAM_EXTRA3, rate);
+ mavlinkSetStreamRate(MAV_DATA_STREAM_EXTENDED_SYS_STATE, rate);
+ return true;
+ }
+
+ mavlinkSetStreamRate(msg.req_stream_id, rate);
+ return true;
+}
+
+static bool handleIncoming_SET_POSITION_TARGET_GLOBAL_INT(void)
+{
+ mavlink_set_position_target_global_int_t msg;
+ mavlink_msg_set_position_target_global_int_decode(&mavlinkContext.recvMsg, &msg);
+
+ if (!mavlinkIsLocalTarget(msg.target_system, msg.target_component)) {
+ return false;
+ }
+
+ uint8_t frame = msg.coordinate_frame;
+ if (!mavlinkFrameIsSupported(frame,
+ MAV_FRAME_SUPPORTED_GLOBAL |
+ MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT |
+ MAV_FRAME_SUPPORTED_GLOBAL_INT |
+ MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT_INT)) {
+ return true;
+ }
+
+ const uint16_t typeMask = msg.type_mask;
+ const bool xIgnored = (typeMask & POSITION_TARGET_TYPEMASK_X_IGNORE) != 0;
+ const bool yIgnored = (typeMask & POSITION_TARGET_TYPEMASK_Y_IGNORE) != 0;
+ const bool zIgnored = (typeMask & POSITION_TARGET_TYPEMASK_Z_IGNORE) != 0;
+
+ // Altitude-only SET_POSITION_TARGET_GLOBAL_INT mirrors MAV_CMD_DO_CHANGE_ALTITUDE semantics.
+ if (xIgnored && yIgnored && !zIgnored) {
+ if (isGCSValid()) {
+ mavlinkSetAltitudeTargetFromFrame(frame, msg.alt);
+ }
+ return true;
+ }
+
+ if (xIgnored || yIgnored) {
+ return true;
+ }
+
+ if (isGCSValid()) {
+ navWaypoint_t wp = {0};
+ wp.action = NAV_WP_ACTION_WAYPOINT;
+ wp.lat = msg.lat_int;
+ wp.lon = msg.lon_int;
+ wp.alt = zIgnored ? 0 : (int32_t)(msg.alt * 100.0f);
+ wp.p1 = 0;
+ wp.p2 = 0;
+ wp.p3 = mavlinkFrameUsesAbsoluteAltitude(frame) ? NAV_WP_ALTMODE : 0;
+ wp.flag = 0;
+
+ setWaypoint(255, &wp);
+ }
+
+ return true;
+}
+
+static bool handleIncoming_SET_POSITION_TARGET_LOCAL_NED(void)
+{
+ mavlink_set_position_target_local_ned_t msg;
+ mavlink_msg_set_position_target_local_ned_decode(&mavlinkContext.recvMsg, &msg);
+
+ if (!mavlinkIsLocalTarget(msg.target_system, msg.target_component)) {
+ return false;
+ }
+
+ if (msg.coordinate_frame != MAV_FRAME_LOCAL_OFFSET_NED) {
+ return true;
+ }
+
+ const uint16_t typeMask = msg.type_mask;
+ const bool xIgnored = (typeMask & POSITION_TARGET_TYPEMASK_X_IGNORE) != 0;
+ const bool yIgnored = (typeMask & POSITION_TARGET_TYPEMASK_Y_IGNORE) != 0;
+ const bool zIgnored = (typeMask & POSITION_TARGET_TYPEMASK_Z_IGNORE) != 0;
+
+ if (!isGCSValid() || zIgnored) {
+ return true;
+ }
+
+ if ((!xIgnored && fabsf(msg.x) > 0.01f) || (!yIgnored && fabsf(msg.y) > 0.01f)) {
+ return true;
+ }
+
+ const int32_t targetAltitudeCm = (int32_t)lrintf((float)getEstimatedActualPosition(Z) - (msg.z * 100.0f));
+ navigationSetAltitudeTargetWithDatum(NAV_WP_TAKEOFF_DATUM, targetAltitudeCm);
+
+ return true;
+}
+
+
+static bool handleIncoming_RC_CHANNELS_OVERRIDE(void) {
+ mavlink_rc_channels_override_t msg;
+ mavlink_msg_rc_channels_override_decode(&mavlinkContext.recvMsg, &msg);
+ mavlinkRxHandleMessage(&msg);
+ return true;
+}
+
+static bool handleIncoming_PARAM_REQUEST_LIST(void) {
+ mavlink_param_request_list_t msg;
+ mavlink_msg_param_request_list_decode(&mavlinkContext.recvMsg, &msg);
+
+ // Respond that we don't have any parameters to force Mission Planner to give up quickly
+ if (mavlinkIsLocalTarget(msg.target_system, msg.target_component)) {
+ // mavlink_msg_param_value_pack(system_id, component_id, msg, param_value->param_id, param_value->param_value, param_value->param_type, param_value->param_count, param_value->param_index);
+ mavlink_msg_param_value_pack(mavSystemId, mavComponentId, &mavSendMsg, 0, 0, 0, 0, 0);
+ mavlinkSendMessage();
+ }
+ return true;
+}
+
+static void mavlinkParseRxStats(const mavlink_radio_status_t *msg) {
+ switch(mavActiveConfig->radio_type) {
+ case MAVLINK_RADIO_NONE:
+ break;
+ case MAVLINK_RADIO_SIK:
+ // rssi scaling info from: https://ardupilot.org/rover/docs/common-3dr-radio-advanced-configuration-and-technical-information.html
+ rxLinkStatistics.uplinkRSSI = (msg->rssi / 1.9) - 127;
+ rxLinkStatistics.uplinkSNR = msg->noise / 1.9;
+ rxLinkStatistics.uplinkLQ = msg->rssi != 255 ? scaleRange(msg->rssi, 0, 254, 0, 100) : 0;
+ break;
+ case MAVLINK_RADIO_ELRS:
+ rxLinkStatistics.uplinkRSSI = -msg->remrssi;
+ rxLinkStatistics.uplinkSNR = msg->noise;
+ rxLinkStatistics.uplinkLQ = scaleRange(msg->rssi, 0, 255, 0, 100);
+ break;
+ case MAVLINK_RADIO_GENERIC:
+ default:
+ rxLinkStatistics.uplinkRSSI = msg->rssi;
+ rxLinkStatistics.uplinkSNR = msg->noise;
+ rxLinkStatistics.uplinkLQ = msg->rssi != 255 ? scaleRange(msg->rssi, 0, 254, 0, 100) : 0;
+ break;
+ }
+}
+
+static bool handleIncoming_RADIO_STATUS(void) {
+ mavlink_radio_status_t msg;
+ mavlink_msg_radio_status_decode(&mavlinkContext.recvMsg, &msg);
+ if (msg.txbuf > 0) {
+ mavActivePort->txbuffValid = true;
+ mavActivePort->txbuffFree = msg.txbuf;
+ } else {
+ mavActivePort->txbuffValid = false;
+ mavActivePort->txbuffFree = 100;
+ }
+
+ if (rxConfig()->receiverType == RX_TYPE_SERIAL &&
+ rxConfig()->serialrx_provider == SERIALRX_MAVLINK) {
+ mavlinkParseRxStats(&msg);
+ }
+
+ return true;
+}
+
+static bool handleIncoming_HEARTBEAT(void) {
+ mavlink_heartbeat_t msg;
+ mavlink_msg_heartbeat_decode(&mavlinkContext.recvMsg, &msg);
+
+ switch (msg.type) {
+#ifdef USE_ADSB
+ case MAV_TYPE_ADSB:
+ return adsbHeartbeat();
+#endif
+ default:
+ break;
+ }
+
+ return false;
+}
+
+#ifdef USE_ADSB
+static bool handleIncoming_ADSB_VEHICLE(void) {
+ mavlink_adsb_vehicle_t msg;
+ mavlink_msg_adsb_vehicle_decode(&mavlinkContext.recvMsg, &msg);
+
+ adsbVehicleValues_t* vehicle = getVehicleForFill();
+ if(vehicle != NULL){
+ vehicle->icao = msg.ICAO_address;
+ vehicle->gps.lat = msg.lat;
+ vehicle->gps.lon = msg.lon;
+ vehicle->alt = (int32_t)(msg.altitude / 10);
+ vehicle->horVelocity = msg.hor_velocity;
+ vehicle->heading = msg.heading;
+ vehicle->flags = msg.flags;
+ vehicle->altitudeType = msg.altitude_type;
+ memcpy(&(vehicle->callsign), msg.callsign, sizeof(vehicle->callsign));
+ vehicle->emitterType = msg.emitter_type;
+ vehicle->tslc = msg.tslc;
+
+ adsbNewVehicle(vehicle);
+ }
+
+ return true;
+}
+#endif
+
+mavlinkFcDispatchResult_e mavlinkFcDispatchIncomingMessage(uint8_t ingressPortIndex)
+{
+ UNUSED(ingressPortIndex);
+
+ switch (mavlinkContext.recvMsg.msgid) {
+ case MAVLINK_MSG_ID_HEARTBEAT:
+ return handleIncoming_HEARTBEAT() ? MAVLINK_FC_DISPATCH_HANDLED_ACTIVITY : MAVLINK_FC_DISPATCH_NOT_HANDLED;
+ case MAVLINK_MSG_ID_PARAM_REQUEST_LIST:
+ return handleIncoming_PARAM_REQUEST_LIST() ? MAVLINK_FC_DISPATCH_HANDLED_ACTIVITY : MAVLINK_FC_DISPATCH_NOT_HANDLED;
+ case MAVLINK_MSG_ID_MISSION_CLEAR_ALL:
+ return handleIncoming_MISSION_CLEAR_ALL() ? MAVLINK_FC_DISPATCH_HANDLED_ACTIVITY : MAVLINK_FC_DISPATCH_NOT_HANDLED;
+ case MAVLINK_MSG_ID_MISSION_COUNT:
+ return handleIncoming_MISSION_COUNT() ? MAVLINK_FC_DISPATCH_HANDLED_ACTIVITY : MAVLINK_FC_DISPATCH_NOT_HANDLED;
+ case MAVLINK_MSG_ID_MISSION_ITEM:
+ return handleIncoming_MISSION_ITEM() ? MAVLINK_FC_DISPATCH_HANDLED_ACTIVITY : MAVLINK_FC_DISPATCH_NOT_HANDLED;
+ case MAVLINK_MSG_ID_MISSION_ITEM_INT:
+ return handleIncoming_MISSION_ITEM_INT() ? MAVLINK_FC_DISPATCH_HANDLED_ACTIVITY : MAVLINK_FC_DISPATCH_NOT_HANDLED;
+ case MAVLINK_MSG_ID_MISSION_REQUEST_LIST:
+ return handleIncoming_MISSION_REQUEST_LIST() ? MAVLINK_FC_DISPATCH_HANDLED_ACTIVITY : MAVLINK_FC_DISPATCH_NOT_HANDLED;
+ case MAVLINK_MSG_ID_COMMAND_LONG:
+ return handleIncoming_COMMAND_LONG() ? MAVLINK_FC_DISPATCH_HANDLED_ACTIVITY : MAVLINK_FC_DISPATCH_NOT_HANDLED;
+ case MAVLINK_MSG_ID_COMMAND_INT:
+ return handleIncoming_COMMAND_INT() ? MAVLINK_FC_DISPATCH_HANDLED_ACTIVITY : MAVLINK_FC_DISPATCH_NOT_HANDLED;
+ case MAVLINK_MSG_ID_MISSION_REQUEST:
+ return handleIncoming_MISSION_REQUEST() ? MAVLINK_FC_DISPATCH_HANDLED_ACTIVITY : MAVLINK_FC_DISPATCH_NOT_HANDLED;
+ case MAVLINK_MSG_ID_MISSION_REQUEST_INT:
+ return handleIncoming_MISSION_REQUEST_INT() ? MAVLINK_FC_DISPATCH_HANDLED_ACTIVITY : MAVLINK_FC_DISPATCH_NOT_HANDLED;
+ case MAVLINK_MSG_ID_REQUEST_DATA_STREAM:
+ return handleIncoming_REQUEST_DATA_STREAM() ? MAVLINK_FC_DISPATCH_HANDLED_ACTIVITY : MAVLINK_FC_DISPATCH_NOT_HANDLED;
+ case MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE:
+ handleIncoming_RC_CHANNELS_OVERRIDE();
+ return MAVLINK_FC_DISPATCH_HANDLED_NO_ACTIVITY;
+ case MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED:
+ return handleIncoming_SET_POSITION_TARGET_LOCAL_NED() ? MAVLINK_FC_DISPATCH_HANDLED_ACTIVITY : MAVLINK_FC_DISPATCH_NOT_HANDLED;
+ case MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT:
+ return handleIncoming_SET_POSITION_TARGET_GLOBAL_INT() ? MAVLINK_FC_DISPATCH_HANDLED_ACTIVITY : MAVLINK_FC_DISPATCH_NOT_HANDLED;
+#ifdef USE_ADSB
+ case MAVLINK_MSG_ID_ADSB_VEHICLE:
+ return handleIncoming_ADSB_VEHICLE() ? MAVLINK_FC_DISPATCH_HANDLED_ACTIVITY : MAVLINK_FC_DISPATCH_NOT_HANDLED;
+#endif
+ case MAVLINK_MSG_ID_RADIO_STATUS:
+ handleIncoming_RADIO_STATUS();
+ return MAVLINK_FC_DISPATCH_HANDLED_NO_ACTIVITY;
+ case MAVLINK_MSG_ID_TUNNEL:
+ return handleIncoming_TUNNEL(ingressPortIndex) ? MAVLINK_FC_DISPATCH_HANDLED_ACTIVITY : MAVLINK_FC_DISPATCH_NOT_HANDLED;
+ default:
+ return MAVLINK_FC_DISPATCH_NOT_HANDLED;
+ }
+}
+
+
+#endif
diff --git a/src/main/fc/fc_mavlink.h b/src/main/fc/fc_mavlink.h
new file mode 100644
index 00000000000..29be4363157
--- /dev/null
+++ b/src/main/fc/fc_mavlink.h
@@ -0,0 +1,29 @@
+#pragma once
+
+#include "common/time.h"
+
+#include "telemetry/mavlink.h"
+
+typedef enum {
+ MAVLINK_FC_DISPATCH_NOT_HANDLED = 0,
+ MAVLINK_FC_DISPATCH_HANDLED_NO_ACTIVITY,
+ MAVLINK_FC_DISPATCH_HANDLED_ACTIVITY,
+} mavlinkFcDispatchResult_e;
+
+void mavlinkSendSystemStatus(void);
+void mavlinkSendRCChannelsAndRSSI(void);
+void mavlinkSendPosition(timeUs_t currentTimeUs);
+void mavlinkSendGpsRawInt(timeUs_t currentTimeUs);
+void mavlinkSendGlobalPositionInt(timeUs_t currentTimeUs);
+void mavlinkSendGpsGlobalOrigin(void);
+void mavlinkSendAttitude(void);
+void mavlinkSendVfrHud(void);
+void mavlinkSendHeartbeat(void);
+void mavlinkSendBatteryTemperatureStatusText(void);
+void mavlinkSendExtendedSysState(void);
+void mavlinkSendBatteryStatus(void);
+void mavlinkSendScaledPressure(void);
+void mavlinkSendSystemTime(void);
+bool mavlinkSendStatusText(void);
+void mavlinkSendHighLatency2(timeUs_t currentTimeUs);
+mavlinkFcDispatchResult_e mavlinkFcDispatchIncomingMessage(uint8_t ingressPortIndex);
diff --git a/src/main/mavlink/mavlink_internal.h b/src/main/mavlink/mavlink_internal.h
new file mode 100644
index 00000000000..4c365f364db
--- /dev/null
+++ b/src/main/mavlink/mavlink_internal.h
@@ -0,0 +1,131 @@
+#pragma once
+
+#include "platform.h"
+
+#if defined(USE_TELEMETRY) && defined(USE_TELEMETRY_MAVLINK)
+
+#include
+#include
+#include
+#include
+
+#include "build/build_config.h"
+#include "build/debug.h"
+#include "build/version.h"
+
+#include "common/axis.h"
+#include "common/color.h"
+#include "common/maths.h"
+#include "common/utils.h"
+#include "common/string_light.h"
+
+#include "config/feature.h"
+
+#include "drivers/serial.h"
+#include "drivers/time.h"
+#include "drivers/display.h"
+#include "drivers/osd_symbols.h"
+
+#include "fc/config.h"
+#include "fc/fc_core.h"
+#include "fc/fc_msp.h"
+#include "fc/rc_controls.h"
+#include "fc/rc_modes.h"
+#include "fc/runtime_config.h"
+#include "fc/settings.h"
+
+#include "flight/failsafe.h"
+#include "flight/imu.h"
+#include "flight/mixer_profile.h"
+#include "flight/pid.h"
+#include "flight/servos.h"
+#include "flight/wind_estimator.h"
+
+#include "io/adsb.h"
+#include "io/gps.h"
+#include "io/ledstrip.h"
+#include "io/serial.h"
+#include "io/osd.h"
+
+#include "msp/msp_protocol.h"
+#include "msp/msp_serial.h"
+
+#include "navigation/navigation.h"
+#include "navigation/navigation_private.h"
+
+#include "rx/rx.h"
+#include "rx/mavlink.h"
+
+#include "sensors/acceleration.h"
+#include "sensors/barometer.h"
+#include "sensors/battery.h"
+#include "sensors/boardalignment.h"
+#include "sensors/gyro.h"
+#include "sensors/pitotmeter.h"
+#include "sensors/diagnostics.h"
+#include "sensors/sensors.h"
+#include "sensors/temperature.h"
+#include "sensors/esc_sensor.h"
+
+#include "telemetry/mavlink.h"
+#include "telemetry/telemetry.h"
+
+#include "blackbox/blackbox_io.h"
+
+#include "scheduler/scheduler.h"
+
+#define MAVLINK_TUNNEL_PAYLOAD_TYPE_INAV_MSP 0x8001
+#define MAVLINK_TUNNEL_MSP_TIMEOUT_MS 1000
+#define MAVLINK_TUNNEL_MSP_FRAMEBUF_SIZE (MSP_PORT_OUTBUF_SIZE + 16)
+#define MAVLINK_MISSION_UPLOAD_TIMEOUT_MS 10000
+
+typedef struct mavlinkContext_s {
+ mavlinkPortRuntime_t portStates[MAX_MAVLINK_PORTS];
+ uint8_t portCount;
+ mavlinkRouteEntry_t routeTable[MAVLINK_MAX_ROUTES];
+ uint8_t routeCount;
+ mspPort_t tunnelMspPorts[MAX_MAVLINK_PORTS];
+ uint8_t tunnelRemoteSystemIds[MAX_MAVLINK_PORTS];
+ uint8_t tunnelRemoteComponentIds[MAX_MAVLINK_PORTS];
+ uint8_t sendMask;
+ mavlinkPortRuntime_t *activePort;
+ const mavlinkTelemetryPortConfig_t *activeConfig;
+ mavlink_message_t sendMsg;
+ mavlink_message_t recvMsg;
+ uint8_t systemId;
+ uint8_t autopilotType;
+ uint8_t componentId;
+ uint8_t tunnelReplyPayloadBuf[MSP_PORT_OUTBUF_SIZE];
+ uint8_t tunnelFrameBuf[MAVLINK_TUNNEL_MSP_FRAMEBUF_SIZE];
+ int incomingMissionWpCount;
+ int incomingMissionWpSequence;
+ uint8_t incomingMissionSourceSystem;
+ uint8_t incomingMissionSourceComponent;
+ timeMs_t incomingMissionLastActivityMs;
+} mavlinkContext_t;
+
+extern mavlinkContext_t mavlinkContext;
+
+#define mavPortStates (mavlinkContext.portStates)
+#define mavPortCount (mavlinkContext.portCount)
+#define mavRouteTable (mavlinkContext.routeTable)
+#define mavRouteCount (mavlinkContext.routeCount)
+#define mavTunnelMspPorts (mavlinkContext.tunnelMspPorts)
+#define mavTunnelRemoteSystemIds (mavlinkContext.tunnelRemoteSystemIds)
+#define mavTunnelRemoteComponentIds (mavlinkContext.tunnelRemoteComponentIds)
+#define mavSendMask (mavlinkContext.sendMask)
+#define mavActivePort (mavlinkContext.activePort)
+#define mavActiveConfig (mavlinkContext.activeConfig)
+#define mavSendMsg (mavlinkContext.sendMsg)
+#define mavSystemId (mavlinkContext.systemId)
+#define mavAutopilotType (mavlinkContext.autopilotType)
+#define mavComponentId (mavlinkContext.componentId)
+#define mavTunnelReplyPayloadBuf (mavlinkContext.tunnelReplyPayloadBuf)
+#define mavTunnelFrameBuf (mavlinkContext.tunnelFrameBuf)
+#define incomingMissionWpCount (mavlinkContext.incomingMissionWpCount)
+#define incomingMissionWpSequence (mavlinkContext.incomingMissionWpSequence)
+#define incomingMissionSourceSystem (mavlinkContext.incomingMissionSourceSystem)
+#define incomingMissionSourceComponent (mavlinkContext.incomingMissionSourceComponent)
+#define incomingMissionLastActivityMs (mavlinkContext.incomingMissionLastActivityMs)
+
+#endif
diff --git a/src/main/mavlink/mavlink_ports.c b/src/main/mavlink/mavlink_ports.c
new file mode 100644
index 00000000000..9d499071a51
--- /dev/null
+++ b/src/main/mavlink/mavlink_ports.c
@@ -0,0 +1,73 @@
+#include "mavlink/mavlink_internal.h"
+
+#include "mavlink/mavlink_ports.h"
+#include "mavlink/mavlink_runtime.h"
+#include "mavlink/mavlink_streams.h"
+
+#if defined(USE_TELEMETRY) && defined(USE_TELEMETRY_MAVLINK)
+
+void freeMAVLinkTelemetryPortByIndex(uint8_t portIndex)
+{
+ mavlinkPortRuntime_t *state = &mavPortStates[portIndex];
+
+ if (state->port) {
+ closeSerialPort(state->port);
+ }
+
+ state->port = NULL;
+ state->telemetryEnabled = false;
+ state->txbuffValid = false;
+ state->txbuffFree = 100;
+ state->lastMavlinkMessageUs = 0;
+ state->lastHighLatencyMessageUs = 0;
+ state->highLatencyEnabled = mavlinkGetPortConfig(portIndex)->high_latency;
+ state->txSeq = 0;
+ state->txDroppedFrames = 0;
+ memset(state->mavStreamNextDue, 0, sizeof(state->mavStreamNextDue));
+ memset(state->mavMessageOverrideIntervalsUs, 0, sizeof(state->mavMessageOverrideIntervalsUs));
+ memset(state->mavMessageNextDue, 0, sizeof(state->mavMessageNextDue));
+ memset(&state->mavRecvStatus, 0, sizeof(state->mavRecvStatus));
+ memset(&state->mavRecvMsg, 0, sizeof(state->mavRecvMsg));
+ resetMspPort(&mavTunnelMspPorts[portIndex], NULL);
+ mavTunnelRemoteSystemIds[portIndex] = 0;
+ mavTunnelRemoteComponentIds[portIndex] = 0;
+}
+
+void configureMAVLinkTelemetryPort(uint8_t portIndex)
+{
+ mavlinkPortRuntime_t *state = &mavPortStates[portIndex];
+
+ if (!state->portConfig) {
+ return;
+ }
+
+ baudRate_e baudRateIndex = state->portConfig->telemetry_baudrateIndex;
+ if (baudRateIndex == BAUD_AUTO) {
+ // default rate for minimOSD
+ baudRateIndex = BAUD_57600;
+ }
+
+ state->port = openSerialPort(state->portConfig->identifier, FUNCTION_TELEMETRY_MAVLINK, NULL, NULL, baudRates[baudRateIndex], TELEMETRY_MAVLINK_PORT_MODE, SERIAL_NOT_INVERTED);
+ if (!state->port) {
+ return;
+ }
+
+ state->telemetryEnabled = true;
+ state->txbuffValid = false;
+ state->txbuffFree = 100;
+ state->lastMavlinkMessageUs = 0;
+ state->lastHighLatencyMessageUs = 0;
+ state->highLatencyEnabled = mavlinkGetPortConfig(portIndex)->high_latency;
+ state->txSeq = 0;
+ state->txDroppedFrames = 0;
+ memset(state->mavStreamNextDue, 0, sizeof(state->mavStreamNextDue));
+ memset(state->mavMessageOverrideIntervalsUs, 0, sizeof(state->mavMessageOverrideIntervalsUs));
+ memset(state->mavMessageNextDue, 0, sizeof(state->mavMessageNextDue));
+ memset(&state->mavRecvStatus, 0, sizeof(state->mavRecvStatus));
+ memset(&state->mavRecvMsg, 0, sizeof(state->mavRecvMsg));
+ resetMspPort(&mavTunnelMspPorts[portIndex], NULL);
+ mavTunnelRemoteSystemIds[portIndex] = 0;
+ mavTunnelRemoteComponentIds[portIndex] = 0;
+}
+
+#endif
diff --git a/src/main/mavlink/mavlink_ports.h b/src/main/mavlink/mavlink_ports.h
new file mode 100644
index 00000000000..c0b325a354c
--- /dev/null
+++ b/src/main/mavlink/mavlink_ports.h
@@ -0,0 +1,4 @@
+#pragma once
+
+void configureMAVLinkTelemetryPort(uint8_t portIndex);
+void freeMAVLinkTelemetryPortByIndex(uint8_t portIndex);
diff --git a/src/main/mavlink/mavlink_routing.c b/src/main/mavlink/mavlink_routing.c
new file mode 100644
index 00000000000..f0b0b373d11
--- /dev/null
+++ b/src/main/mavlink/mavlink_routing.c
@@ -0,0 +1,172 @@
+#include "mavlink/mavlink_internal.h"
+
+#include "mavlink/mavlink_routing.h"
+#include "mavlink/mavlink_runtime.h"
+
+#if defined(USE_TELEMETRY) && defined(USE_TELEMETRY_MAVLINK)
+
+bool mavlinkIsFromLocalIdentity(uint8_t sysid, uint8_t compid)
+{
+ return sysid == mavlinkGetCommonConfig()->sysid && compid == MAV_COMP_ID_AUTOPILOT1;
+}
+
+void mavlinkLearnRoute(uint8_t ingressPortIndex)
+{
+ if (mavlinkContext.recvMsg.sysid == 0 || mavlinkIsFromLocalIdentity(mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid)) {
+ return;
+ }
+
+ for (uint8_t routeIndex = 0; routeIndex < mavRouteCount; routeIndex++) {
+ mavlinkRouteEntry_t *route = &mavRouteTable[routeIndex];
+ if (route->sysid == mavlinkContext.recvMsg.sysid && route->compid == mavlinkContext.recvMsg.compid) {
+ route->ingressPortIndex = ingressPortIndex;
+ return;
+ }
+ }
+
+ if (mavRouteCount >= MAVLINK_MAX_ROUTES) {
+ return;
+ }
+
+ mavRouteTable[mavRouteCount].sysid = mavlinkContext.recvMsg.sysid;
+ mavRouteTable[mavRouteCount].compid = mavlinkContext.recvMsg.compid;
+ mavRouteTable[mavRouteCount].ingressPortIndex = ingressPortIndex;
+ mavRouteCount++;
+}
+
+void mavlinkExtractTargets(const mavlink_message_t *msg, int16_t *targetSystem, int16_t *targetComponent)
+{
+ *targetSystem = -1;
+ *targetComponent = -1;
+
+ const mavlink_msg_entry_t *msgEntry = mavlink_get_msg_entry(msg->msgid);
+ if (!msgEntry) {
+ return;
+ }
+
+ if (msgEntry->flags & MAV_MSG_ENTRY_FLAG_HAVE_TARGET_SYSTEM) {
+ *targetSystem = _MAV_RETURN_uint8_t(msg, msgEntry->target_system_ofs);
+ }
+
+ if (msgEntry->flags & MAV_MSG_ENTRY_FLAG_HAVE_TARGET_COMPONENT) {
+ *targetComponent = _MAV_RETURN_uint8_t(msg, msgEntry->target_component_ofs);
+ }
+}
+
+static uint8_t mavlinkComputeForwardMask(uint8_t ingressPortIndex, int16_t targetSystem, int16_t targetComponent)
+{
+ uint8_t mask = 0;
+
+ if (targetSystem <= 0) {
+ for (uint8_t portIndex = 0; portIndex < mavPortCount; portIndex++) {
+ if (portIndex == ingressPortIndex) {
+ continue;
+ }
+
+ const mavlinkPortRuntime_t *state = &mavPortStates[portIndex];
+ if (!state->telemetryEnabled || !state->port) {
+ continue;
+ }
+
+ mask |= MAVLINK_PORT_MASK(portIndex);
+ }
+ return mask;
+ }
+
+ for (uint8_t routeIndex = 0; routeIndex < mavRouteCount; routeIndex++) {
+ const mavlinkRouteEntry_t *route = &mavRouteTable[routeIndex];
+
+ if (route->sysid != targetSystem) {
+ continue;
+ }
+ if (targetComponent > 0 && route->compid != targetComponent) {
+ continue;
+ }
+ if (route->ingressPortIndex == ingressPortIndex || route->ingressPortIndex >= mavPortCount) {
+ continue;
+ }
+
+ const mavlinkPortRuntime_t *state = &mavPortStates[route->ingressPortIndex];
+ if (!state->telemetryEnabled || !state->port) {
+ continue;
+ }
+
+ mask |= MAVLINK_PORT_MASK(route->ingressPortIndex);
+ }
+
+ return mask;
+}
+
+void mavlinkForwardMessage(uint8_t ingressPortIndex, int16_t targetSystem, int16_t targetComponent)
+{
+ if (mavlinkContext.recvMsg.msgid == MAVLINK_MSG_ID_RADIO_STATUS) {
+ return;
+ }
+
+ uint8_t mavBuffer[MAVLINK_MAX_PACKET_LEN];
+ const int msgLength = mavlink_msg_to_send_buffer(mavBuffer, &mavlinkContext.recvMsg);
+ if (msgLength <= 0) {
+ return;
+ }
+
+ const uint8_t forwardMask = mavlinkComputeForwardMask(ingressPortIndex, targetSystem, targetComponent);
+ for (uint8_t portIndex = 0; portIndex < mavPortCount; portIndex++) {
+ if ((forwardMask & MAVLINK_PORT_MASK(portIndex)) == 0) {
+ continue;
+ }
+
+ mavlinkPortRuntime_t *state = &mavPortStates[portIndex];
+ if (serialTxBytesFree(state->port) < (uint32_t)msgLength) {
+ state->txDroppedFrames++;
+ continue;
+ }
+
+ serialBeginWrite(state->port);
+ serialWriteBuf(state->port, mavBuffer, msgLength);
+ serialEndWrite(state->port);
+ }
+}
+
+int8_t mavlinkResolveLocalPortForTarget(int16_t targetSystem, int16_t targetComponent, uint8_t ingressPortIndex)
+{
+ if (targetSystem <= 0) {
+ return ingressPortIndex;
+ }
+
+ if ((uint8_t)targetSystem != mavlinkGetCommonConfig()->sysid) {
+ return -1;
+ }
+
+ if (targetComponent > 0 && (uint8_t)targetComponent != MAV_COMP_ID_AUTOPILOT1) {
+ return -1;
+ }
+
+ if (ingressPortIndex < mavPortCount) {
+ return ingressPortIndex;
+ }
+
+ return mavPortCount > 0 ? 0 : -1;
+}
+
+bool mavlinkShouldFanOutLocalBroadcast(const mavlink_message_t *msg)
+{
+ if (msg->msgid == MAVLINK_MSG_ID_REQUEST_DATA_STREAM) {
+ return true;
+ }
+
+ if (msg->msgid == MAVLINK_MSG_ID_COMMAND_LONG) {
+ mavlink_command_long_t cmd;
+ mavlink_msg_command_long_decode(msg, &cmd);
+ return cmd.command == MAV_CMD_SET_MESSAGE_INTERVAL || cmd.command == MAV_CMD_CONTROL_HIGH_LATENCY;
+ }
+
+ if (msg->msgid == MAVLINK_MSG_ID_COMMAND_INT) {
+ mavlink_command_int_t cmd;
+ mavlink_msg_command_int_decode(msg, &cmd);
+ return cmd.command == MAV_CMD_SET_MESSAGE_INTERVAL || cmd.command == MAV_CMD_CONTROL_HIGH_LATENCY;
+ }
+
+ return false;
+}
+
+#endif
diff --git a/src/main/mavlink/mavlink_routing.h b/src/main/mavlink/mavlink_routing.h
new file mode 100644
index 00000000000..1aa472e0f8c
--- /dev/null
+++ b/src/main/mavlink/mavlink_routing.h
@@ -0,0 +1,13 @@
+#pragma once
+
+#include
+#include
+
+#include "telemetry/mavlink.h"
+
+bool mavlinkIsFromLocalIdentity(uint8_t sysid, uint8_t compid);
+void mavlinkLearnRoute(uint8_t ingressPortIndex);
+void mavlinkExtractTargets(const mavlink_message_t *msg, int16_t *targetSystem, int16_t *targetComponent);
+void mavlinkForwardMessage(uint8_t ingressPortIndex, int16_t targetSystem, int16_t targetComponent);
+int8_t mavlinkResolveLocalPortForTarget(int16_t targetSystem, int16_t targetComponent, uint8_t ingressPortIndex);
+bool mavlinkShouldFanOutLocalBroadcast(const mavlink_message_t *msg);
diff --git a/src/main/mavlink/mavlink_runtime.c b/src/main/mavlink/mavlink_runtime.c
new file mode 100644
index 00000000000..0c780e0f7f3
--- /dev/null
+++ b/src/main/mavlink/mavlink_runtime.c
@@ -0,0 +1,281 @@
+#include "mavlink/mavlink_internal.h"
+
+#include "fc/fc_mavlink.h"
+
+#include "mavlink/mavlink_ports.h"
+#include "mavlink/mavlink_routing.h"
+#include "mavlink/mavlink_runtime.h"
+#include "mavlink/mavlink_streams.h"
+
+#if defined(USE_TELEMETRY) && defined(USE_TELEMETRY_MAVLINK)
+
+mavlinkContext_t mavlinkContext;
+
+const mavlinkTelemetryPortConfig_t *mavlinkGetPortConfig(uint8_t portIndex)
+{
+ return &telemetryConfig()->mavlink[portIndex];
+}
+
+const mavlinkTelemetryCommonConfig_t *mavlinkGetCommonConfig(void)
+{
+ return &telemetryConfig()->mavlink_common;
+}
+
+uint8_t mavlinkGetProtocolVersion(void)
+{
+ return mavlinkGetCommonConfig()->version;
+}
+
+static void mavlinkApplyActivePortOutputVersion(void)
+{
+ mavlink_status_t *chanState = mavlink_get_channel_status(MAVLINK_COMM_0);
+ if (mavlinkGetProtocolVersion() == 1) {
+ chanState->flags |= MAVLINK_STATUS_FLAG_OUT_MAVLINK1;
+ } else {
+ chanState->flags &= ~MAVLINK_STATUS_FLAG_OUT_MAVLINK1;
+ }
+}
+
+void mavlinkSetActivePortContext(uint8_t portIndex)
+{
+ mavActivePort = &mavPortStates[portIndex];
+ mavActiveConfig = mavlinkGetPortConfig(portIndex);
+ const mavlinkTelemetryCommonConfig_t *commonConfig = mavlinkGetCommonConfig();
+ mavAutopilotType = commonConfig->autopilot_type;
+ mavSystemId = commonConfig->sysid;
+ mavComponentId = MAV_COMP_ID_AUTOPILOT1;
+ mavlinkApplyActivePortOutputVersion();
+}
+
+void mavlinkRuntimeFreePorts(void)
+{
+ for (uint8_t portIndex = 0; portIndex < mavPortCount; portIndex++) {
+ freeMAVLinkTelemetryPortByIndex(portIndex);
+ }
+
+ mavSendMask = 0;
+ mavRouteCount = 0;
+}
+
+void mavlinkRuntimeInit(void)
+{
+ memset(&mavlinkContext, 0, sizeof(mavlinkContext));
+ mavSystemId = 1;
+ mavComponentId = MAV_COMP_ID_AUTOPILOT1;
+
+ const serialPortConfig_t *serialPortConfig = findSerialPortConfig(FUNCTION_TELEMETRY_MAVLINK);
+ while (serialPortConfig && mavPortCount < MAX_MAVLINK_PORTS) {
+ mavlinkPortRuntime_t *state = &mavPortStates[mavPortCount];
+ state->portConfig = serialPortConfig;
+ state->portSharing = determinePortSharing(serialPortConfig, FUNCTION_TELEMETRY_MAVLINK);
+ state->txbuffFree = 100;
+ state->highLatencyEnabled = mavlinkGetPortConfig(mavPortCount)->high_latency;
+ configureMAVLinkStreamRates(mavPortCount);
+
+ mavPortCount++;
+ serialPortConfig = findNextSerialPortConfig(FUNCTION_TELEMETRY_MAVLINK);
+ }
+}
+
+void mavlinkRuntimeCheckState(void)
+{
+ for (uint8_t portIndex = 0; portIndex < mavPortCount; portIndex++) {
+ mavlinkPortRuntime_t *state = &mavPortStates[portIndex];
+
+ bool newTelemetryEnabledValue = telemetryDetermineEnabledState(state->portSharing);
+ if ((state->portConfig->functionMask & FUNCTION_RX_SERIAL) &&
+ rxConfig()->receiverType == RX_TYPE_SERIAL &&
+ rxConfig()->serialrx_provider == SERIALRX_MAVLINK) {
+ newTelemetryEnabledValue = true;
+ }
+
+ if (newTelemetryEnabledValue == state->telemetryEnabled) {
+ continue;
+ }
+
+ if (newTelemetryEnabledValue) {
+ configureMAVLinkTelemetryPort(portIndex);
+ if (state->telemetryEnabled) {
+ configureMAVLinkStreamRates(portIndex);
+ }
+ } else {
+ freeMAVLinkTelemetryPortByIndex(portIndex);
+ }
+ }
+}
+
+void mavlinkSendMessage(void)
+{
+ const mavlink_msg_entry_t *msgEntry = mavlink_get_msg_entry(mavSendMsg.msgid);
+ if (!msgEntry) {
+ return;
+ }
+
+ uint8_t sendMask = mavSendMask;
+ if (sendMask == 0) {
+ if (mavActivePort) {
+ for (uint8_t portIndex = 0; portIndex < mavPortCount; portIndex++) {
+ if (&mavPortStates[portIndex] == mavActivePort) {
+ sendMask = MAVLINK_PORT_MASK(portIndex);
+ break;
+ }
+ }
+ } else if (mavPortCount == 1 && mavPortStates[0].telemetryEnabled && mavPortStates[0].port) {
+ sendMask = MAVLINK_PORT_MASK(0);
+ }
+ }
+
+ for (uint8_t portIndex = 0; portIndex < mavPortCount; portIndex++) {
+ if ((sendMask & MAVLINK_PORT_MASK(portIndex)) == 0) {
+ continue;
+ }
+
+ mavlinkPortRuntime_t *state = &mavPortStates[portIndex];
+ if (!state->telemetryEnabled || !state->port) {
+ continue;
+ }
+
+ mavlink_status_t txStatus = { 0 };
+ txStatus.current_tx_seq = state->txSeq;
+ if (mavlinkGetProtocolVersion() == 1) {
+ txStatus.flags |= MAVLINK_STATUS_FLAG_OUT_MAVLINK1;
+ }
+
+ mavlink_message_t txMsg = mavSendMsg;
+ mavlink_finalize_message_buffer(
+ &txMsg,
+ txMsg.sysid,
+ txMsg.compid,
+ &txStatus,
+ msgEntry->min_msg_len,
+ txMsg.len,
+ msgEntry->crc_extra
+ );
+ state->txSeq = txStatus.current_tx_seq;
+
+ uint8_t mavBuffer[MAVLINK_MAX_PACKET_LEN];
+ const int msgLength = mavlink_msg_to_send_buffer(mavBuffer, &txMsg);
+ if (msgLength <= 0) {
+ continue;
+ }
+
+ // Drop the frame on this port if there is no room; do not block telemetry task.
+ if (serialTxBytesFree(state->port) < (uint32_t)msgLength) {
+ state->txDroppedFrames++;
+ continue;
+ }
+
+ serialBeginWrite(state->port);
+ serialWriteBuf(state->port, mavBuffer, msgLength);
+ serialEndWrite(state->port);
+ }
+}
+
+static bool processMAVLinkIncomingTelemetry(uint8_t ingressPortIndex)
+{
+ mavlinkPortRuntime_t *state = &mavPortStates[ingressPortIndex];
+
+ while (serialRxBytesWaiting(state->port) > 0) {
+ // Limit handling to one message per cycle
+ const char c = serialRead(state->port);
+ const uint8_t result = mavlink_parse_char(ingressPortIndex, c, &state->mavRecvMsg, &state->mavRecvStatus);
+ if (result == MAVLINK_FRAMING_OK) {
+ mavlinkContext.recvMsg = state->mavRecvMsg;
+
+ if (mavlinkIsFromLocalIdentity(mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid)) {
+ return false;
+ }
+
+ mavlinkLearnRoute(ingressPortIndex);
+
+ int16_t targetSystem;
+ int16_t targetComponent;
+ mavlinkExtractTargets(&mavlinkContext.recvMsg, &targetSystem, &targetComponent);
+ mavlinkForwardMessage(ingressPortIndex, targetSystem, targetComponent);
+
+ if (mavlinkContext.recvMsg.msgid == MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE) {
+ mavlinkSetActivePortContext(ingressPortIndex);
+ mavSendMask = MAVLINK_PORT_MASK(ingressPortIndex);
+ const mavlinkFcDispatchResult_e dispatchResult = mavlinkFcDispatchIncomingMessage(ingressPortIndex);
+ return dispatchResult == MAVLINK_FC_DISPATCH_HANDLED_ACTIVITY;
+ }
+
+ const int8_t localPortIndex = mavlinkResolveLocalPortForTarget(targetSystem, targetComponent, ingressPortIndex);
+ if (localPortIndex < 0) {
+ return false;
+ }
+
+ uint8_t localPortMask = MAVLINK_PORT_MASK((uint8_t)localPortIndex);
+ const bool isLocalOrSystemBroadcast = targetSystem == 0 || ((targetSystem > 0) && ((uint8_t)targetSystem == mavlinkGetCommonConfig()->sysid));
+ if (targetComponent == 0 && isLocalOrSystemBroadcast && mavlinkShouldFanOutLocalBroadcast(&mavlinkContext.recvMsg)) {
+ localPortMask = 0;
+ for (uint8_t portIndex = 0; portIndex < mavPortCount; portIndex++) {
+ localPortMask |= MAVLINK_PORT_MASK(portIndex);
+ }
+ }
+
+ bool handled = false;
+ for (uint8_t localIndex = 0; localIndex < mavPortCount; localIndex++) {
+ if (!(localPortMask & MAVLINK_PORT_MASK(localIndex))) {
+ continue;
+ }
+
+ mavlinkSetActivePortContext(localIndex);
+ mavSendMask = MAVLINK_PORT_MASK(ingressPortIndex);
+
+ const mavlinkFcDispatchResult_e dispatchResult = mavlinkFcDispatchIncomingMessage(ingressPortIndex);
+ handled = handled || dispatchResult == MAVLINK_FC_DISPATCH_HANDLED_ACTIVITY;
+ }
+
+ return handled;
+ }
+ }
+
+ return false;
+}
+
+static bool isMAVLinkTelemetryHalfDuplex(void)
+{
+ return telemetryConfig()->halfDuplex ||
+ (rxConfig()->receiverType == RX_TYPE_SERIAL && rxConfig()->serialrx_provider == SERIALRX_MAVLINK && tristateWithDefaultOffIsActive(rxConfig()->halfDuplex));
+}
+
+void mavlinkRuntimeHandle(timeUs_t currentTimeUs)
+{
+ for (uint8_t portIndex = 0; portIndex < mavPortCount; portIndex++) {
+ mavlinkPortRuntime_t *state = &mavPortStates[portIndex];
+ if (!state->telemetryEnabled || !state->port) {
+ continue;
+ }
+
+ mavlinkSetActivePortContext(portIndex);
+
+ // Process incoming MAVLink on this port and forward when needed.
+ const bool receivedMessage = processMAVLinkIncomingTelemetry(portIndex);
+
+ // Restore context back to this port before periodic send decisions.
+ mavlinkSetActivePortContext(portIndex);
+ bool shouldSendTelemetry = false;
+
+ if (state->txbuffValid) {
+ // Use flow control if available.
+ shouldSendTelemetry = state->txbuffFree >= mavActiveConfig->min_txbuff;
+ } else {
+ // If not, use blind frame pacing and half-duplex backoff after RX activity.
+ const bool halfDuplexBackoff = isMAVLinkTelemetryHalfDuplex() && receivedMessage;
+ shouldSendTelemetry = ((currentTimeUs - state->lastMavlinkMessageUs) >= TELEMETRY_MAVLINK_DELAY) && !halfDuplexBackoff;
+ }
+
+ if (!shouldSendTelemetry) {
+ continue;
+ }
+
+ mavSendMask = MAVLINK_PORT_MASK(portIndex);
+ processMAVLinkTelemetry(currentTimeUs);
+ state->lastMavlinkMessageUs = currentTimeUs;
+ }
+
+ mavSendMask = 0;
+}
+
+#endif
diff --git a/src/main/mavlink/mavlink_runtime.h b/src/main/mavlink/mavlink_runtime.h
new file mode 100644
index 00000000000..da5e1394eac
--- /dev/null
+++ b/src/main/mavlink/mavlink_runtime.h
@@ -0,0 +1,16 @@
+#pragma once
+
+#include "common/time.h"
+
+#include "telemetry/telemetry.h"
+
+void mavlinkRuntimeInit(void);
+void mavlinkRuntimeHandle(timeUs_t currentTimeUs);
+void mavlinkRuntimeCheckState(void);
+void mavlinkRuntimeFreePorts(void);
+
+const mavlinkTelemetryPortConfig_t *mavlinkGetPortConfig(uint8_t portIndex);
+const mavlinkTelemetryCommonConfig_t *mavlinkGetCommonConfig(void);
+uint8_t mavlinkGetProtocolVersion(void);
+void mavlinkSetActivePortContext(uint8_t portIndex);
+void mavlinkSendMessage(void);
diff --git a/src/main/mavlink/mavlink_streams.c b/src/main/mavlink/mavlink_streams.c
new file mode 100644
index 00000000000..a774f2ef00e
--- /dev/null
+++ b/src/main/mavlink/mavlink_streams.c
@@ -0,0 +1,309 @@
+#include "mavlink/mavlink_internal.h"
+
+#include "fc/fc_mavlink.h"
+
+#include "mavlink/mavlink_runtime.h"
+#include "mavlink/mavlink_streams.h"
+
+#if defined(USE_TELEMETRY) && defined(USE_TELEMETRY_MAVLINK)
+
+/* Secondary profile for ports 2..N: heartbeat only. */
+const uint8_t mavSecondaryRates[MAVLINK_STREAM_COUNT] = {
+ [MAV_DATA_STREAM_EXTENDED_STATUS] = 0,
+ [MAV_DATA_STREAM_RC_CHANNELS] = 0,
+ [MAV_DATA_STREAM_POSITION] = 0,
+ [MAV_DATA_STREAM_EXTRA1] = 0,
+ [MAV_DATA_STREAM_EXTRA2] = 0,
+ [MAV_DATA_STREAM_EXTRA3] = 0,
+ [MAV_DATA_STREAM_EXTENDED_SYS_STATE] = 0,
+ [MAV_DATA_STREAM_HEARTBEAT] = 1
+};
+
+uint8_t mavlinkClampStreamRate(uint8_t rate)
+{
+ if (rate > TELEMETRY_MAVLINK_MAXRATE) {
+ return TELEMETRY_MAVLINK_MAXRATE;
+ }
+
+ return rate;
+}
+
+int32_t mavlinkRateToIntervalUs(uint8_t rate)
+{
+ rate = mavlinkClampStreamRate(rate);
+ if (rate == 0) {
+ return -1;
+ }
+
+ return 1000000 / rate;
+}
+
+bool mavlinkPeriodicMessageFromMessageId(uint16_t messageId, mavlinkPeriodicMessage_e *periodicMessage)
+{
+ switch (messageId) {
+ case MAVLINK_MSG_ID_HEARTBEAT:
+ *periodicMessage = MAVLINK_PERIODIC_MESSAGE_HEARTBEAT;
+ return true;
+ case MAVLINK_MSG_ID_SYS_STATUS:
+ *periodicMessage = MAVLINK_PERIODIC_MESSAGE_SYS_STATUS;
+ return true;
+ case MAVLINK_MSG_ID_EXTENDED_SYS_STATE:
+ *periodicMessage = MAVLINK_PERIODIC_MESSAGE_EXTENDED_SYS_STATE;
+ return true;
+ case MAVLINK_MSG_ID_RC_CHANNELS:
+ case MAVLINK_MSG_ID_RC_CHANNELS_RAW:
+ case MAVLINK_MSG_ID_RC_CHANNELS_SCALED:
+ *periodicMessage = MAVLINK_PERIODIC_MESSAGE_RC_CHANNELS;
+ return true;
+ case MAVLINK_MSG_ID_GPS_RAW_INT:
+ *periodicMessage = MAVLINK_PERIODIC_MESSAGE_GPS_RAW_INT;
+ return true;
+ case MAVLINK_MSG_ID_GLOBAL_POSITION_INT:
+ *periodicMessage = MAVLINK_PERIODIC_MESSAGE_GLOBAL_POSITION_INT;
+ return true;
+ case MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN:
+ *periodicMessage = MAVLINK_PERIODIC_MESSAGE_GPS_GLOBAL_ORIGIN;
+ return true;
+ case MAVLINK_MSG_ID_ATTITUDE:
+ *periodicMessage = MAVLINK_PERIODIC_MESSAGE_ATTITUDE;
+ return true;
+ case MAVLINK_MSG_ID_VFR_HUD:
+ *periodicMessage = MAVLINK_PERIODIC_MESSAGE_VFR_HUD;
+ return true;
+ case MAVLINK_MSG_ID_BATTERY_STATUS:
+ *periodicMessage = MAVLINK_PERIODIC_MESSAGE_BATTERY_STATUS;
+ return true;
+ case MAVLINK_MSG_ID_SCALED_PRESSURE:
+ *periodicMessage = MAVLINK_PERIODIC_MESSAGE_SCALED_PRESSURE;
+ return true;
+ case MAVLINK_MSG_ID_SYSTEM_TIME:
+ *periodicMessage = MAVLINK_PERIODIC_MESSAGE_SYSTEM_TIME;
+ return true;
+ default:
+ return false;
+ }
+}
+
+uint8_t mavlinkPeriodicMessageBaseStream(mavlinkPeriodicMessage_e periodicMessage)
+{
+ switch (periodicMessage) {
+ case MAVLINK_PERIODIC_MESSAGE_HEARTBEAT:
+ return MAV_DATA_STREAM_HEARTBEAT;
+ case MAVLINK_PERIODIC_MESSAGE_SYS_STATUS:
+ return MAV_DATA_STREAM_EXTENDED_STATUS;
+ case MAVLINK_PERIODIC_MESSAGE_EXTENDED_SYS_STATE:
+ return MAV_DATA_STREAM_EXTENDED_SYS_STATE;
+ case MAVLINK_PERIODIC_MESSAGE_RC_CHANNELS:
+ return MAV_DATA_STREAM_RC_CHANNELS;
+ case MAVLINK_PERIODIC_MESSAGE_GPS_RAW_INT:
+ case MAVLINK_PERIODIC_MESSAGE_GLOBAL_POSITION_INT:
+ case MAVLINK_PERIODIC_MESSAGE_GPS_GLOBAL_ORIGIN:
+ return MAV_DATA_STREAM_POSITION;
+ case MAVLINK_PERIODIC_MESSAGE_ATTITUDE:
+ return MAV_DATA_STREAM_EXTRA1;
+ case MAVLINK_PERIODIC_MESSAGE_VFR_HUD:
+ return MAV_DATA_STREAM_EXTRA2;
+ case MAVLINK_PERIODIC_MESSAGE_BATTERY_STATUS:
+ case MAVLINK_PERIODIC_MESSAGE_SCALED_PRESSURE:
+ case MAVLINK_PERIODIC_MESSAGE_SYSTEM_TIME:
+ return MAV_DATA_STREAM_EXTRA3;
+ default:
+ return MAV_DATA_STREAM_ALL;
+ }
+}
+
+static void mavlinkResetMessageSchedule(mavlinkPeriodicMessage_e periodicMessage)
+{
+ if (!mavActivePort) {
+ return;
+ }
+
+ mavActivePort->mavMessageNextDue[periodicMessage] = 0;
+}
+
+static void mavlinkResetMessagesForStream(uint8_t streamNum)
+{
+ if (!mavActivePort) {
+ return;
+ }
+
+ for (uint8_t messageIndex = 0; messageIndex < MAVLINK_PERIODIC_MESSAGE_COUNT; messageIndex++) {
+ if (mavlinkPeriodicMessageBaseStream((mavlinkPeriodicMessage_e)messageIndex) == streamNum) {
+ mavActivePort->mavMessageNextDue[messageIndex] = 0;
+ }
+ }
+}
+
+int32_t mavlinkMessageBaseIntervalUs(mavlinkPeriodicMessage_e periodicMessage)
+{
+ if (!mavActivePort) {
+ return -1;
+ }
+
+ return mavlinkRateToIntervalUs(mavActivePort->mavRates[mavlinkPeriodicMessageBaseStream(periodicMessage)]);
+}
+
+int32_t mavlinkMessageIntervalUs(mavlinkPeriodicMessage_e periodicMessage)
+{
+ if (!mavActivePort) {
+ return -1;
+ }
+
+ const int32_t overrideIntervalUs = mavActivePort->mavMessageOverrideIntervalsUs[periodicMessage];
+ if (overrideIntervalUs != 0) {
+ return overrideIntervalUs;
+ }
+
+ return mavlinkMessageBaseIntervalUs(periodicMessage);
+}
+
+void mavlinkSetMessageOverrideIntervalUs(mavlinkPeriodicMessage_e periodicMessage, int32_t intervalUs)
+{
+ if (!mavActivePort) {
+ return;
+ }
+
+ mavActivePort->mavMessageOverrideIntervalsUs[periodicMessage] = intervalUs;
+ mavlinkResetMessageSchedule(periodicMessage);
+}
+
+int mavlinkStreamTrigger(enum MAV_DATA_STREAM streamNum, timeUs_t currentTimeUs)
+{
+ if (!mavActivePort || streamNum >= MAXSTREAMS) {
+ return 0;
+ }
+
+ const uint8_t rate = mavlinkClampStreamRate(mavActivePort->mavRates[streamNum]);
+ if (rate == 0) {
+ return 0;
+ }
+
+ const timeUs_t intervalUs = 1000000UL / rate;
+ if ((mavActivePort->mavStreamNextDue[streamNum] == 0) || (cmpTimeUs(currentTimeUs, mavActivePort->mavStreamNextDue[streamNum]) >= 0)) {
+ mavActivePort->mavStreamNextDue[streamNum] = currentTimeUs + intervalUs;
+ return 1;
+ }
+
+ return 0;
+}
+
+void mavlinkSetStreamRate(uint8_t streamNum, uint8_t rate)
+{
+ if (!mavActivePort || streamNum >= MAXSTREAMS) {
+ return;
+ }
+ mavActivePort->mavRates[streamNum] = mavlinkClampStreamRate(rate);
+ mavActivePort->mavStreamNextDue[streamNum] = 0;
+ mavlinkResetMessagesForStream(streamNum);
+}
+
+int mavlinkMessageTrigger(mavlinkPeriodicMessage_e periodicMessage, timeUs_t currentTimeUs)
+{
+ if (!mavActivePort) {
+ return 0;
+ }
+
+ const int32_t intervalUs = mavlinkMessageIntervalUs(periodicMessage);
+ if (intervalUs <= 0) {
+ return 0;
+ }
+
+ if ((mavActivePort->mavMessageNextDue[periodicMessage] == 0) || (cmpTimeUs(currentTimeUs, mavActivePort->mavMessageNextDue[periodicMessage]) >= 0)) {
+ mavActivePort->mavMessageNextDue[periodicMessage] = currentTimeUs + intervalUs;
+ return 1;
+ }
+
+ return 0;
+}
+
+void configureMAVLinkStreamRates(uint8_t portIndex)
+{
+ const mavlinkTelemetryPortConfig_t *primaryConfig = &telemetryConfig()->mavlink[0];
+ const uint8_t mavPrimaryRates[MAVLINK_STREAM_COUNT] = {
+ [MAV_DATA_STREAM_EXTENDED_STATUS] = primaryConfig->extended_status_rate,
+ [MAV_DATA_STREAM_RC_CHANNELS] = primaryConfig->rc_channels_rate,
+ [MAV_DATA_STREAM_POSITION] = primaryConfig->position_rate,
+ [MAV_DATA_STREAM_EXTRA1] = primaryConfig->extra1_rate,
+ [MAV_DATA_STREAM_EXTRA2] = primaryConfig->extra2_rate,
+ [MAV_DATA_STREAM_EXTRA3] = primaryConfig->extra3_rate,
+ [MAV_DATA_STREAM_EXTENDED_SYS_STATE] = primaryConfig->extra3_rate,
+ [MAV_DATA_STREAM_HEARTBEAT] = 1
+ };
+
+ const uint8_t *selectedRates = (portIndex == 0) ? mavPrimaryRates : mavSecondaryRates;
+ mavlinkPortRuntime_t *state = &mavPortStates[portIndex];
+
+ for (uint8_t stream = 0; stream < MAVLINK_STREAM_COUNT; stream++) {
+ state->mavRates[stream] = selectedRates[stream];
+ state->mavRatesConfigured[stream] = selectedRates[stream];
+ state->mavStreamNextDue[stream] = 0;
+ }
+}
+
+void processMAVLinkTelemetry(timeUs_t currentTimeUs)
+{
+ if (mavActivePort->highLatencyEnabled && mavlinkGetProtocolVersion() != 1) {
+ if ((currentTimeUs - mavActivePort->lastHighLatencyMessageUs) >= TELEMETRY_MAVLINK_HIGH_LATENCY_INTERVAL_US) {
+ mavlinkSendHighLatency2(currentTimeUs);
+ mavActivePort->lastHighLatencyMessageUs = currentTimeUs;
+ }
+ return;
+ }
+
+ // is executed @ TELEMETRY_MAVLINK_MAXRATE rate
+ if (mavlinkMessageTrigger(MAVLINK_PERIODIC_MESSAGE_SYS_STATUS, currentTimeUs)) {
+ mavlinkSendSystemStatus();
+ }
+
+ if (mavlinkMessageTrigger(MAVLINK_PERIODIC_MESSAGE_RC_CHANNELS, currentTimeUs)) {
+ mavlinkSendRCChannelsAndRSSI();
+ }
+
+#ifdef USE_GPS
+ if (mavlinkMessageTrigger(MAVLINK_PERIODIC_MESSAGE_GPS_RAW_INT, currentTimeUs)) {
+ mavlinkSendGpsRawInt(currentTimeUs);
+ }
+
+ if (mavlinkMessageTrigger(MAVLINK_PERIODIC_MESSAGE_GLOBAL_POSITION_INT, currentTimeUs)) {
+ mavlinkSendGlobalPositionInt(currentTimeUs);
+ }
+
+ if (mavlinkMessageTrigger(MAVLINK_PERIODIC_MESSAGE_GPS_GLOBAL_ORIGIN, currentTimeUs)) {
+ mavlinkSendGpsGlobalOrigin();
+ }
+#endif
+
+ if (mavlinkMessageTrigger(MAVLINK_PERIODIC_MESSAGE_ATTITUDE, currentTimeUs)) {
+ mavlinkSendAttitude();
+ }
+
+ if (mavlinkMessageTrigger(MAVLINK_PERIODIC_MESSAGE_VFR_HUD, currentTimeUs)) {
+ mavlinkSendVfrHud();
+ }
+
+ if (mavlinkMessageTrigger(MAVLINK_PERIODIC_MESSAGE_HEARTBEAT, currentTimeUs)) {
+ mavlinkSendHeartbeat();
+ }
+
+ if (mavlinkMessageTrigger(MAVLINK_PERIODIC_MESSAGE_EXTENDED_SYS_STATE, currentTimeUs)) {
+ mavlinkSendExtendedSysState();
+ }
+
+ if (mavlinkMessageTrigger(MAVLINK_PERIODIC_MESSAGE_BATTERY_STATUS, currentTimeUs)) {
+ mavlinkSendBatteryStatus();
+ }
+
+ if (mavlinkMessageTrigger(MAVLINK_PERIODIC_MESSAGE_SCALED_PRESSURE, currentTimeUs)) {
+ mavlinkSendScaledPressure();
+ }
+
+ if (mavlinkMessageTrigger(MAVLINK_PERIODIC_MESSAGE_SYSTEM_TIME, currentTimeUs)) {
+ mavlinkSendSystemTime();
+ }
+
+ if (mavlinkStreamTrigger(MAV_DATA_STREAM_EXTRA3, currentTimeUs)) {
+ mavlinkSendStatusText();
+ }
+}
+
+#endif
diff --git a/src/main/mavlink/mavlink_streams.h b/src/main/mavlink/mavlink_streams.h
new file mode 100644
index 00000000000..2084518a546
--- /dev/null
+++ b/src/main/mavlink/mavlink_streams.h
@@ -0,0 +1,20 @@
+#pragma once
+
+#include "common/time.h"
+
+#include "telemetry/mavlink.h"
+
+extern const uint8_t mavSecondaryRates[MAVLINK_STREAM_COUNT];
+
+uint8_t mavlinkClampStreamRate(uint8_t rate);
+int32_t mavlinkRateToIntervalUs(uint8_t rate);
+bool mavlinkPeriodicMessageFromMessageId(uint16_t messageId, mavlinkPeriodicMessage_e *periodicMessage);
+uint8_t mavlinkPeriodicMessageBaseStream(mavlinkPeriodicMessage_e periodicMessage);
+int32_t mavlinkMessageBaseIntervalUs(mavlinkPeriodicMessage_e periodicMessage);
+int32_t mavlinkMessageIntervalUs(mavlinkPeriodicMessage_e periodicMessage);
+void mavlinkSetMessageOverrideIntervalUs(mavlinkPeriodicMessage_e periodicMessage, int32_t intervalUs);
+int mavlinkStreamTrigger(enum MAV_DATA_STREAM streamNum, timeUs_t currentTimeUs);
+void mavlinkSetStreamRate(uint8_t streamNum, uint8_t rate);
+int mavlinkMessageTrigger(mavlinkPeriodicMessage_e periodicMessage, timeUs_t currentTimeUs);
+void configureMAVLinkStreamRates(uint8_t portIndex);
+void processMAVLinkTelemetry(timeUs_t currentTimeUs);
diff --git a/src/main/telemetry/mavlink.c b/src/main/telemetry/mavlink.c
index 29fe90f58f9..fe019c6ec87 100644
--- a/src/main/telemetry/mavlink.c
+++ b/src/main/telemetry/mavlink.c
@@ -20,3471 +20,33 @@
*
* Author: Konstantin Sharlaimov
*/
-#include
-#include
-#include
-#include
#include "platform.h"
#if defined(USE_TELEMETRY) && defined(USE_TELEMETRY_MAVLINK)
-#include "build/build_config.h"
-#include "build/debug.h"
-#include "build/version.h"
-
-#include "common/axis.h"
-#include "common/color.h"
-#include "common/maths.h"
-#include "common/utils.h"
-#include "common/string_light.h"
-
-#include "config/feature.h"
-
-#include "drivers/serial.h"
-#include "drivers/time.h"
-#include "drivers/display.h"
-#include "drivers/osd_symbols.h"
-
-#include "fc/config.h"
-#include "fc/fc_core.h"
-#include "fc/fc_msp.h"
-#include "fc/rc_controls.h"
-#include "fc/rc_modes.h"
-#include "fc/runtime_config.h"
-#include "fc/settings.h"
-
-#include "flight/failsafe.h"
-#include "flight/imu.h"
-#include "flight/mixer_profile.h"
-#include "flight/pid.h"
-#include "flight/servos.h"
-#include "flight/wind_estimator.h"
-
-#include "io/adsb.h"
-#include "io/gps.h"
-#include "io/ledstrip.h"
-#include "io/serial.h"
-#include "io/osd.h"
-
-#include "msp/msp_protocol.h"
-#include "msp/msp_serial.h"
-
-#include "navigation/navigation.h"
-#include "navigation/navigation_private.h"
-
-#include "rx/rx.h"
-#include "rx/mavlink.h"
-
-#include "sensors/acceleration.h"
-#include "sensors/barometer.h"
-#include "sensors/battery.h"
-#include "sensors/boardalignment.h"
-#include "sensors/gyro.h"
-#include "sensors/pitotmeter.h"
-#include "sensors/diagnostics.h"
-#include "sensors/sensors.h"
-#include "sensors/temperature.h"
-#include "sensors/esc_sensor.h"
+#include "mavlink/mavlink_runtime.h"
#include "telemetry/mavlink.h"
-#include "telemetry/telemetry.h"
-
-#include "blackbox/blackbox_io.h"
-
-#include "scheduler/scheduler.h"
-
-/* Secondary profile for ports 2..N: heartbeat only. */
-static const uint8_t mavSecondaryRates[MAVLINK_STREAM_COUNT] = {
- [MAV_DATA_STREAM_EXTENDED_STATUS] = 0,
- [MAV_DATA_STREAM_RC_CHANNELS] = 0,
- [MAV_DATA_STREAM_POSITION] = 0,
- [MAV_DATA_STREAM_EXTRA1] = 0,
- [MAV_DATA_STREAM_EXTRA2] = 0,
- [MAV_DATA_STREAM_EXTRA3] = 0,
- [MAV_DATA_STREAM_EXTENDED_SYS_STATE] = 0,
- [MAV_DATA_STREAM_HEARTBEAT] = 1
-};
-
-static mavlinkPortRuntime_t mavPortStates[MAX_MAVLINK_PORTS];
-static uint8_t mavPortCount = 0;
-static mavlinkRouteEntry_t mavRouteTable[MAVLINK_MAX_ROUTES];
-static uint8_t mavRouteCount = 0;
-static mspPort_t mavTunnelMspPorts[MAX_MAVLINK_PORTS];
-static uint8_t mavTunnelRemoteSystemIds[MAX_MAVLINK_PORTS];
-static uint8_t mavTunnelRemoteComponentIds[MAX_MAVLINK_PORTS];
-static uint8_t mavSendMask = 0;
-static mavlinkPortRuntime_t *mavActivePort = NULL;
-static const mavlinkTelemetryPortConfig_t *mavActiveConfig = NULL;
-static mavlink_message_t mavSendMsg;
-static mavlink_message_t mavRecvMsg;
-
-// Set active MAV identity from global MAVLink settings.
-static uint8_t mavSystemId = 1;
-static uint8_t mavAutopilotType;
-static uint8_t mavComponentId = MAV_COMP_ID_AUTOPILOT1;
-
-#define MAVLINK_TUNNEL_PAYLOAD_TYPE_INAV_MSP 0x8001
-#define MAVLINK_TUNNEL_MSP_TIMEOUT_MS 1000
-#define MAVLINK_TUNNEL_MSP_FRAMEBUF_SIZE (MSP_PORT_OUTBUF_SIZE + 16)
-
-static uint8_t mavTunnelReplyPayloadBuf[MSP_PORT_OUTBUF_SIZE];
-static uint8_t mavTunnelFrameBuf[MAVLINK_TUNNEL_MSP_FRAMEBUF_SIZE];
-
-static uint8_t mavlinkGetVehicleType(void)
-{
- switch (mixerConfig()->platformType)
- {
- case PLATFORM_MULTIROTOR:
- return MAV_TYPE_QUADROTOR;
- case PLATFORM_TRICOPTER:
- return MAV_TYPE_TRICOPTER;
- case PLATFORM_AIRPLANE:
- return MAV_TYPE_FIXED_WING;
- case PLATFORM_ROVER:
- return MAV_TYPE_GROUND_ROVER;
- case PLATFORM_BOAT:
- return MAV_TYPE_SURFACE_BOAT;
- case PLATFORM_HELICOPTER:
- return MAV_TYPE_HELICOPTER;
- default:
- return MAV_TYPE_GENERIC;
- }
-}
-
-static APM_COPTER_MODE inavToArduCopterMap(flightModeForTelemetry_e flightMode)
-{
- switch (flightMode)
- {
- case FLM_ACRO: return COPTER_MODE_ACRO;
- case FLM_ACRO_AIR: return COPTER_MODE_ACRO;
- case FLM_ANGLE: return COPTER_MODE_STABILIZE;
- case FLM_HORIZON: return COPTER_MODE_STABILIZE;
- case FLM_ANGLEHOLD: return COPTER_MODE_STABILIZE;
- case FLM_ALTITUDE_HOLD: return COPTER_MODE_ALT_HOLD;
- case FLM_POSITION_HOLD:
- {
- if (isGCSValid()) {
- return COPTER_MODE_GUIDED;
- } else {
- return COPTER_MODE_POSHOLD;
- }
- }
- case FLM_RTH: return COPTER_MODE_RTL;
- case FLM_MISSION: return COPTER_MODE_AUTO;
- case FLM_LAUNCH: return COPTER_MODE_THROW;
- case FLM_FAILSAFE:
- {
- if (failsafePhase() == FAILSAFE_RETURN_TO_HOME) {
- return COPTER_MODE_RTL;
- } else if (failsafePhase() == FAILSAFE_LANDING) {
- return COPTER_MODE_LAND;
- } else {
- return COPTER_MODE_RTL;
- }
- }
- default: return COPTER_MODE_STABILIZE;
- }
-}
-
-static APM_PLANE_MODE inavToArduPlaneMap(flightModeForTelemetry_e flightMode)
-{
- switch (flightMode)
- {
- case FLM_MANUAL: return PLANE_MODE_MANUAL;
- case FLM_ACRO: return PLANE_MODE_ACRO;
- case FLM_ACRO_AIR: return PLANE_MODE_ACRO;
- case FLM_ANGLE: return PLANE_MODE_FLY_BY_WIRE_A;
- case FLM_HORIZON: return PLANE_MODE_STABILIZE;
- case FLM_ANGLEHOLD: return PLANE_MODE_STABILIZE;
- case FLM_ALTITUDE_HOLD: return PLANE_MODE_FLY_BY_WIRE_B;
- case FLM_POSITION_HOLD:
- {
- if (isGCSValid()) {
- return PLANE_MODE_GUIDED;
- } else {
- return PLANE_MODE_LOITER;
- }
- }
- case FLM_RTH: return PLANE_MODE_RTL;
- case FLM_MISSION: return PLANE_MODE_AUTO;
- case FLM_CRUISE: return PLANE_MODE_CRUISE;
- case FLM_LAUNCH: return PLANE_MODE_TAKEOFF;
- case FLM_FAILSAFE: //failsafePhase_e
- {
- if (failsafePhase() == FAILSAFE_RETURN_TO_HOME) {
- return PLANE_MODE_RTL;
- }
- else if (failsafePhase() == FAILSAFE_LANDING) {
- return PLANE_MODE_AUTOLAND;
- }
- else {
- return PLANE_MODE_RTL;
- }
- }
- default: return PLANE_MODE_MANUAL;
- }
-}
-
-typedef struct mavlinkModeSelection_s {
- flightModeForTelemetry_e flightMode;
- uint8_t customMode;
-} mavlinkModeSelection_t;
-
-static mavlinkModeSelection_t selectMavlinkMode(bool isPlane)
-{
- mavlinkModeSelection_t modeSelection;
- modeSelection.flightMode = getFlightModeForTelemetry();
-
- if (isPlane) {
- modeSelection.customMode = (uint8_t)inavToArduPlaneMap(modeSelection.flightMode);
- } else {
- modeSelection.customMode = (uint8_t)inavToArduCopterMap(modeSelection.flightMode);
- }
-
- return modeSelection;
-}
-
-static const mavlinkTelemetryPortConfig_t *mavlinkGetPortConfig(uint8_t portIndex)
-{
- return &telemetryConfig()->mavlink[portIndex];
-}
-
-static const mavlinkTelemetryCommonConfig_t *mavlinkGetCommonConfig(void)
-{
- return &telemetryConfig()->mavlink_common;
-}
-
-static uint8_t mavlinkGetProtocolVersion(void)
-{
- return mavlinkGetCommonConfig()->version;
-}
-
-static void mavlinkApplyActivePortOutputVersion(void)
-{
- mavlink_status_t *chanState = mavlink_get_channel_status(MAVLINK_COMM_0);
- if (mavlinkGetProtocolVersion() == 1) {
- chanState->flags |= MAVLINK_STATUS_FLAG_OUT_MAVLINK1;
- } else {
- chanState->flags &= ~MAVLINK_STATUS_FLAG_OUT_MAVLINK1;
- }
-}
-
-static void mavlinkSetActivePortContext(uint8_t portIndex)
-{
- mavActivePort = &mavPortStates[portIndex];
- mavActiveConfig = mavlinkGetPortConfig(portIndex);
- const mavlinkTelemetryCommonConfig_t *commonConfig = mavlinkGetCommonConfig();
- mavAutopilotType = commonConfig->autopilot_type;
- mavSystemId = commonConfig->sysid;
- mavComponentId = MAV_COMP_ID_AUTOPILOT1;
- mavlinkApplyActivePortOutputVersion();
-}
-
-static uint8_t mavlinkClampStreamRate(uint8_t rate)
-{
- if (rate > TELEMETRY_MAVLINK_MAXRATE) {
- return TELEMETRY_MAVLINK_MAXRATE;
- }
-
- return rate;
-}
-
-static int32_t mavlinkRateToIntervalUs(uint8_t rate)
-{
- rate = mavlinkClampStreamRate(rate);
- if (rate == 0) {
- return -1;
- }
-
- return 1000000 / rate;
-}
-
-static bool mavlinkPeriodicMessageFromMessageId(uint16_t messageId, mavlinkPeriodicMessage_e *periodicMessage)
-{
- switch (messageId) {
- case MAVLINK_MSG_ID_HEARTBEAT:
- *periodicMessage = MAVLINK_PERIODIC_MESSAGE_HEARTBEAT;
- return true;
- case MAVLINK_MSG_ID_SYS_STATUS:
- *periodicMessage = MAVLINK_PERIODIC_MESSAGE_SYS_STATUS;
- return true;
- case MAVLINK_MSG_ID_EXTENDED_SYS_STATE:
- *periodicMessage = MAVLINK_PERIODIC_MESSAGE_EXTENDED_SYS_STATE;
- return true;
- case MAVLINK_MSG_ID_RC_CHANNELS:
- case MAVLINK_MSG_ID_RC_CHANNELS_RAW:
- case MAVLINK_MSG_ID_RC_CHANNELS_SCALED:
- *periodicMessage = MAVLINK_PERIODIC_MESSAGE_RC_CHANNELS;
- return true;
- case MAVLINK_MSG_ID_GPS_RAW_INT:
- *periodicMessage = MAVLINK_PERIODIC_MESSAGE_GPS_RAW_INT;
- return true;
- case MAVLINK_MSG_ID_GLOBAL_POSITION_INT:
- *periodicMessage = MAVLINK_PERIODIC_MESSAGE_GLOBAL_POSITION_INT;
- return true;
- case MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN:
- *periodicMessage = MAVLINK_PERIODIC_MESSAGE_GPS_GLOBAL_ORIGIN;
- return true;
- case MAVLINK_MSG_ID_ATTITUDE:
- *periodicMessage = MAVLINK_PERIODIC_MESSAGE_ATTITUDE;
- return true;
- case MAVLINK_MSG_ID_VFR_HUD:
- *periodicMessage = MAVLINK_PERIODIC_MESSAGE_VFR_HUD;
- return true;
- case MAVLINK_MSG_ID_BATTERY_STATUS:
- *periodicMessage = MAVLINK_PERIODIC_MESSAGE_BATTERY_STATUS;
- return true;
- case MAVLINK_MSG_ID_SCALED_PRESSURE:
- *periodicMessage = MAVLINK_PERIODIC_MESSAGE_SCALED_PRESSURE;
- return true;
- case MAVLINK_MSG_ID_SYSTEM_TIME:
- *periodicMessage = MAVLINK_PERIODIC_MESSAGE_SYSTEM_TIME;
- return true;
- default:
- return false;
- }
-}
-
-static uint8_t mavlinkPeriodicMessageBaseStream(mavlinkPeriodicMessage_e periodicMessage)
-{
- switch (periodicMessage) {
- case MAVLINK_PERIODIC_MESSAGE_HEARTBEAT:
- return MAV_DATA_STREAM_HEARTBEAT;
- case MAVLINK_PERIODIC_MESSAGE_SYS_STATUS:
- return MAV_DATA_STREAM_EXTENDED_STATUS;
- case MAVLINK_PERIODIC_MESSAGE_EXTENDED_SYS_STATE:
- return MAV_DATA_STREAM_EXTENDED_SYS_STATE;
- case MAVLINK_PERIODIC_MESSAGE_RC_CHANNELS:
- return MAV_DATA_STREAM_RC_CHANNELS;
- case MAVLINK_PERIODIC_MESSAGE_GPS_RAW_INT:
- case MAVLINK_PERIODIC_MESSAGE_GLOBAL_POSITION_INT:
- case MAVLINK_PERIODIC_MESSAGE_GPS_GLOBAL_ORIGIN:
- return MAV_DATA_STREAM_POSITION;
- case MAVLINK_PERIODIC_MESSAGE_ATTITUDE:
- return MAV_DATA_STREAM_EXTRA1;
- case MAVLINK_PERIODIC_MESSAGE_VFR_HUD:
- return MAV_DATA_STREAM_EXTRA2;
- case MAVLINK_PERIODIC_MESSAGE_BATTERY_STATUS:
- case MAVLINK_PERIODIC_MESSAGE_SCALED_PRESSURE:
- case MAVLINK_PERIODIC_MESSAGE_SYSTEM_TIME:
- return MAV_DATA_STREAM_EXTRA3;
- default:
- return MAV_DATA_STREAM_ALL;
- }
-}
-
-static void mavlinkResetMessageSchedule(mavlinkPeriodicMessage_e periodicMessage)
-{
- if (!mavActivePort) {
- return;
- }
-
- mavActivePort->mavMessageNextDue[periodicMessage] = 0;
-}
-
-static void mavlinkResetMessagesForStream(uint8_t streamNum)
-{
- if (!mavActivePort) {
- return;
- }
-
- for (uint8_t messageIndex = 0; messageIndex < MAVLINK_PERIODIC_MESSAGE_COUNT; messageIndex++) {
- if (mavlinkPeriodicMessageBaseStream((mavlinkPeriodicMessage_e)messageIndex) == streamNum) {
- mavActivePort->mavMessageNextDue[messageIndex] = 0;
- }
- }
-}
-
-static int32_t mavlinkMessageBaseIntervalUs(mavlinkPeriodicMessage_e periodicMessage)
-{
- if (!mavActivePort) {
- return -1;
- }
-
- return mavlinkRateToIntervalUs(mavActivePort->mavRates[mavlinkPeriodicMessageBaseStream(periodicMessage)]);
-}
-
-static int32_t mavlinkMessageIntervalUs(mavlinkPeriodicMessage_e periodicMessage)
-{
- if (!mavActivePort) {
- return -1;
- }
-
- const int32_t overrideIntervalUs = mavActivePort->mavMessageOverrideIntervalsUs[periodicMessage];
- if (overrideIntervalUs != 0) {
- return overrideIntervalUs;
- }
-
- return mavlinkMessageBaseIntervalUs(periodicMessage);
-}
-
-static void mavlinkSetMessageOverrideIntervalUs(mavlinkPeriodicMessage_e periodicMessage, int32_t intervalUs)
-{
- if (!mavActivePort) {
- return;
- }
-
- mavActivePort->mavMessageOverrideIntervalsUs[periodicMessage] = intervalUs;
- mavlinkResetMessageSchedule(periodicMessage);
-}
-
-static int mavlinkStreamTrigger(enum MAV_DATA_STREAM streamNum, timeUs_t currentTimeUs)
-{
- if (!mavActivePort || streamNum >= MAXSTREAMS) {
- return 0;
- }
-
- const uint8_t rate = mavlinkClampStreamRate(mavActivePort->mavRates[streamNum]);
- if (rate == 0) {
- return 0;
- }
-
- const timeUs_t intervalUs = 1000000UL / rate;
- if ((mavActivePort->mavStreamNextDue[streamNum] == 0) || (cmpTimeUs(currentTimeUs, mavActivePort->mavStreamNextDue[streamNum]) >= 0)) {
- mavActivePort->mavStreamNextDue[streamNum] = currentTimeUs + intervalUs;
- return 1;
- }
-
- return 0;
-}
-
-static void mavlinkSetStreamRate(uint8_t streamNum, uint8_t rate)
-{
- if (!mavActivePort || streamNum >= MAXSTREAMS) {
- return;
- }
- mavActivePort->mavRates[streamNum] = mavlinkClampStreamRate(rate);
- mavActivePort->mavStreamNextDue[streamNum] = 0;
- mavlinkResetMessagesForStream(streamNum);
-}
-
-static int mavlinkMessageTrigger(mavlinkPeriodicMessage_e periodicMessage, timeUs_t currentTimeUs)
-{
- if (!mavActivePort) {
- return 0;
- }
-
- const int32_t intervalUs = mavlinkMessageIntervalUs(periodicMessage);
- if (intervalUs <= 0) {
- return 0;
- }
-
- if ((mavActivePort->mavMessageNextDue[periodicMessage] == 0) || (cmpTimeUs(currentTimeUs, mavActivePort->mavMessageNextDue[periodicMessage]) >= 0)) {
- mavActivePort->mavMessageNextDue[periodicMessage] = currentTimeUs + intervalUs;
- return 1;
- }
-
- return 0;
-}
-
-static void configureMAVLinkStreamRates(uint8_t portIndex)
-{
- const mavlinkTelemetryPortConfig_t *primaryConfig = &telemetryConfig()->mavlink[0];
- const uint8_t mavPrimaryRates[MAVLINK_STREAM_COUNT] = {
- [MAV_DATA_STREAM_EXTENDED_STATUS] = primaryConfig->extended_status_rate,
- [MAV_DATA_STREAM_RC_CHANNELS] = primaryConfig->rc_channels_rate,
- [MAV_DATA_STREAM_POSITION] = primaryConfig->position_rate,
- [MAV_DATA_STREAM_EXTRA1] = primaryConfig->extra1_rate,
- [MAV_DATA_STREAM_EXTRA2] = primaryConfig->extra2_rate,
- [MAV_DATA_STREAM_EXTRA3] = primaryConfig->extra3_rate,
- [MAV_DATA_STREAM_EXTENDED_SYS_STATE] = primaryConfig->extra3_rate,
- [MAV_DATA_STREAM_HEARTBEAT] = 1
- };
-
- const uint8_t *selectedRates = (portIndex == 0) ? mavPrimaryRates : mavSecondaryRates;
- mavlinkPortRuntime_t *state = &mavPortStates[portIndex];
-
- for (uint8_t stream = 0; stream < MAVLINK_STREAM_COUNT; stream++) {
- state->mavRates[stream] = selectedRates[stream];
- state->mavRatesConfigured[stream] = selectedRates[stream];
- state->mavStreamNextDue[stream] = 0;
- }
-}
-
-static void freeMAVLinkTelemetryPortByIndex(uint8_t portIndex)
-{
- mavlinkPortRuntime_t *state = &mavPortStates[portIndex];
-
- if (state->port) {
- closeSerialPort(state->port);
- }
-
- state->port = NULL;
- state->telemetryEnabled = false;
- state->txbuffValid = false;
- state->txbuffFree = 100;
- state->lastMavlinkMessageUs = 0;
- state->lastHighLatencyMessageUs = 0;
- state->highLatencyEnabled = mavlinkGetPortConfig(portIndex)->high_latency;
- state->txSeq = 0;
- state->txDroppedFrames = 0;
- memset(state->mavStreamNextDue, 0, sizeof(state->mavStreamNextDue));
- memset(state->mavMessageOverrideIntervalsUs, 0, sizeof(state->mavMessageOverrideIntervalsUs));
- memset(state->mavMessageNextDue, 0, sizeof(state->mavMessageNextDue));
- memset(&state->mavRecvStatus, 0, sizeof(state->mavRecvStatus));
- memset(&state->mavRecvMsg, 0, sizeof(state->mavRecvMsg));
- resetMspPort(&mavTunnelMspPorts[portIndex], NULL);
- mavTunnelRemoteSystemIds[portIndex] = 0;
- mavTunnelRemoteComponentIds[portIndex] = 0;
-}
-
-void freeMAVLinkTelemetryPort(void)
-{
- for (uint8_t portIndex = 0; portIndex < mavPortCount; portIndex++) {
- freeMAVLinkTelemetryPortByIndex(portIndex);
- }
-
- mavSendMask = 0;
- mavRouteCount = 0;
-}
void initMAVLinkTelemetry(void)
{
- memset(mavPortStates, 0, sizeof(mavPortStates));
- memset(mavRouteTable, 0, sizeof(mavRouteTable));
- memset(mavTunnelMspPorts, 0, sizeof(mavTunnelMspPorts));
- memset(mavTunnelRemoteSystemIds, 0, sizeof(mavTunnelRemoteSystemIds));
- memset(mavTunnelRemoteComponentIds, 0, sizeof(mavTunnelRemoteComponentIds));
- mavPortCount = 0;
- mavRouteCount = 0;
- mavSendMask = 0;
-
- const serialPortConfig_t *serialPortConfig = findSerialPortConfig(FUNCTION_TELEMETRY_MAVLINK);
- while (serialPortConfig && mavPortCount < MAX_MAVLINK_PORTS) {
- mavlinkPortRuntime_t *state = &mavPortStates[mavPortCount];
- state->portConfig = serialPortConfig;
- state->portSharing = determinePortSharing(serialPortConfig, FUNCTION_TELEMETRY_MAVLINK);
- state->txbuffFree = 100;
- state->highLatencyEnabled = mavlinkGetPortConfig(mavPortCount)->high_latency;
- configureMAVLinkStreamRates(mavPortCount);
-
- mavPortCount++;
- serialPortConfig = findNextSerialPortConfig(FUNCTION_TELEMETRY_MAVLINK);
- }
-
- mavActivePort = NULL;
- mavActiveConfig = NULL;
+ mavlinkRuntimeInit();
}
-static void configureMAVLinkTelemetryPort(uint8_t portIndex)
+void handleMAVLinkTelemetry(timeUs_t currentTimeUs)
{
- mavlinkPortRuntime_t *state = &mavPortStates[portIndex];
-
- if (!state->portConfig) {
- return;
- }
-
- baudRate_e baudRateIndex = state->portConfig->telemetry_baudrateIndex;
- if (baudRateIndex == BAUD_AUTO) {
- // default rate for minimOSD
- baudRateIndex = BAUD_57600;
- }
-
- state->port = openSerialPort(state->portConfig->identifier, FUNCTION_TELEMETRY_MAVLINK, NULL, NULL, baudRates[baudRateIndex], TELEMETRY_MAVLINK_PORT_MODE, SERIAL_NOT_INVERTED);
- if (!state->port) {
- return;
- }
-
- state->telemetryEnabled = true;
- state->txbuffValid = false;
- state->txbuffFree = 100;
- state->lastMavlinkMessageUs = 0;
- state->lastHighLatencyMessageUs = 0;
- state->highLatencyEnabled = mavlinkGetPortConfig(portIndex)->high_latency;
- state->txSeq = 0;
- state->txDroppedFrames = 0;
- memset(state->mavStreamNextDue, 0, sizeof(state->mavStreamNextDue));
- memset(state->mavMessageOverrideIntervalsUs, 0, sizeof(state->mavMessageOverrideIntervalsUs));
- memset(state->mavMessageNextDue, 0, sizeof(state->mavMessageNextDue));
- memset(&state->mavRecvStatus, 0, sizeof(state->mavRecvStatus));
- memset(&state->mavRecvMsg, 0, sizeof(state->mavRecvMsg));
- resetMspPort(&mavTunnelMspPorts[portIndex], NULL);
- mavTunnelRemoteSystemIds[portIndex] = 0;
- mavTunnelRemoteComponentIds[portIndex] = 0;
+ mavlinkRuntimeHandle(currentTimeUs);
}
void checkMAVLinkTelemetryState(void)
{
- for (uint8_t portIndex = 0; portIndex < mavPortCount; portIndex++) {
- mavlinkPortRuntime_t *state = &mavPortStates[portIndex];
-
- bool newTelemetryEnabledValue = telemetryDetermineEnabledState(state->portSharing);
- if ((state->portConfig->functionMask & FUNCTION_RX_SERIAL) &&
- rxConfig()->receiverType == RX_TYPE_SERIAL &&
- rxConfig()->serialrx_provider == SERIALRX_MAVLINK) {
- newTelemetryEnabledValue = true;
- }
-
- if (newTelemetryEnabledValue == state->telemetryEnabled) {
- continue;
- }
-
- if (newTelemetryEnabledValue) {
- configureMAVLinkTelemetryPort(portIndex);
- if (state->telemetryEnabled) {
- configureMAVLinkStreamRates(portIndex);
- }
- } else {
- freeMAVLinkTelemetryPortByIndex(portIndex);
- }
- }
-}
-
-static void mavlinkSendMessage(void)
-{
- const mavlink_msg_entry_t *msgEntry = mavlink_get_msg_entry(mavSendMsg.msgid);
- if (!msgEntry) {
- return;
- }
-
- uint8_t sendMask = mavSendMask;
- if (sendMask == 0) {
- if (mavActivePort) {
- for (uint8_t portIndex = 0; portIndex < mavPortCount; portIndex++) {
- if (&mavPortStates[portIndex] == mavActivePort) {
- sendMask = MAVLINK_PORT_MASK(portIndex);
- break;
- }
- }
- } else if (mavPortCount == 1 && mavPortStates[0].telemetryEnabled && mavPortStates[0].port) {
- sendMask = MAVLINK_PORT_MASK(0);
- }
- }
-
- for (uint8_t portIndex = 0; portIndex < mavPortCount; portIndex++) {
- if ((sendMask & MAVLINK_PORT_MASK(portIndex)) == 0) {
- continue;
- }
-
- mavlinkPortRuntime_t *state = &mavPortStates[portIndex];
- if (!state->telemetryEnabled || !state->port) {
- continue;
- }
-
- mavlink_status_t txStatus = { 0 };
- txStatus.current_tx_seq = state->txSeq;
- if (mavlinkGetProtocolVersion() == 1) {
- txStatus.flags |= MAVLINK_STATUS_FLAG_OUT_MAVLINK1;
- }
-
- mavlink_message_t txMsg = mavSendMsg;
- mavlink_finalize_message_buffer(
- &txMsg,
- txMsg.sysid,
- txMsg.compid,
- &txStatus,
- msgEntry->min_msg_len,
- txMsg.len,
- msgEntry->crc_extra
- );
- state->txSeq = txStatus.current_tx_seq;
-
- uint8_t mavBuffer[MAVLINK_MAX_PACKET_LEN];
- const int msgLength = mavlink_msg_to_send_buffer(mavBuffer, &txMsg);
- if (msgLength <= 0) {
- continue;
- }
-
- // Drop the frame on this port if there is no room; do not block telemetry task.
- if (serialTxBytesFree(state->port) < (uint32_t)msgLength) {
- state->txDroppedFrames++;
- continue;
- }
-
- serialBeginWrite(state->port);
- serialWriteBuf(state->port, mavBuffer, msgLength);
- serialEndWrite(state->port);
- }
-}
-
-static void mavlinkResetTunnelState(uint8_t ingressPortIndex)
-{
- resetMspPort(&mavTunnelMspPorts[ingressPortIndex], NULL);
- mavTunnelRemoteSystemIds[ingressPortIndex] = 0;
- mavTunnelRemoteComponentIds[ingressPortIndex] = 0;
-}
-
-static void mavlinkSendTunnelReply(uint8_t targetSystem, uint8_t targetComponent, const uint8_t *payload, uint8_t payloadLength)
-{
- uint8_t tunnelPayload[MAVLINK_MSG_TUNNEL_FIELD_PAYLOAD_LEN] = { 0 };
- memcpy(tunnelPayload, payload, payloadLength);
-
- mavlink_msg_tunnel_pack(
- mavSystemId,
- mavComponentId,
- &mavSendMsg,
- targetSystem,
- targetComponent,
- MAVLINK_TUNNEL_PAYLOAD_TYPE_INAV_MSP,
- payloadLength,
- tunnelPayload);
- mavlinkSendMessage();
-}
-
-static void mavlinkSendTunnelMspReply(uint8_t targetSystem, uint8_t targetComponent, mspPacket_t *reply, uint8_t *replyPayloadHead, mspVersion_e mspVersion)
-{
- sbufSwitchToReader(&reply->buf, replyPayloadHead);
-
- const int frameLength = mspSerialEncodePacket(reply, mspVersion, mavTunnelFrameBuf, sizeof(mavTunnelFrameBuf));
- for (int offset = 0; offset < frameLength; offset += MAVLINK_MSG_TUNNEL_FIELD_PAYLOAD_LEN) {
- const uint8_t chunkLength = MIN(MAVLINK_MSG_TUNNEL_FIELD_PAYLOAD_LEN, frameLength - offset);
- mavlinkSendTunnelReply(
- targetSystem,
- targetComponent,
- mavTunnelFrameBuf + offset,
- chunkLength);
- }
-}
-
-static bool handleIncoming_TUNNEL(uint8_t ingressPortIndex)
-{
- if (mavlinkGetProtocolVersion() == 1) {
- return false;
- }
-
- mavlink_tunnel_t msg;
- mavlink_msg_tunnel_decode(&mavRecvMsg, &msg);
-
- if (msg.payload_type != MAVLINK_TUNNEL_PAYLOAD_TYPE_INAV_MSP) {
- return false;
- }
-
- if (msg.target_system != mavSystemId) {
- return false;
- }
-
- if (msg.target_component != 0 && msg.target_component != mavComponentId) {
- return false;
- }
-
- mspPort_t *mspPort = &mavTunnelMspPorts[ingressPortIndex];
- const timeMs_t now = millis();
- if (msg.payload_length > MAVLINK_MSG_TUNNEL_FIELD_PAYLOAD_LEN) {
- mavlinkResetTunnelState(ingressPortIndex);
- return false;
- }
-
- if (mspPort->c_state != MSP_IDLE &&
- ((now - mspPort->lastActivityMs) > MAVLINK_TUNNEL_MSP_TIMEOUT_MS ||
- mavTunnelRemoteSystemIds[ingressPortIndex] != mavRecvMsg.sysid ||
- mavTunnelRemoteComponentIds[ingressPortIndex] != mavRecvMsg.compid)) {
- mavlinkResetTunnelState(ingressPortIndex);
- }
-
- mavTunnelRemoteSystemIds[ingressPortIndex] = mavRecvMsg.sysid;
- mavTunnelRemoteComponentIds[ingressPortIndex] = mavRecvMsg.compid;
- mspPort->lastActivityMs = now;
-
- bool handled = false;
- for (uint8_t payloadIndex = 0; payloadIndex < msg.payload_length; payloadIndex++) {
- if (!mspSerialProcessReceivedByte(mspPort, msg.payload[payloadIndex])) {
- continue;
- }
-
- handled = true;
- if (mspPort->c_state != MSP_COMMAND_RECEIVED) {
- continue;
- }
-
- mspPacket_t reply = {
- .buf = { .ptr = mavTunnelReplyPayloadBuf, .end = ARRAYEND(mavTunnelReplyPayloadBuf), },
- .cmd = -1,
- .flags = 0,
- .result = 0,
- };
- uint8_t *replyPayloadHead = reply.buf.ptr;
-
- if (mspPort->cmdMSP == MSP_SET_PASSTHROUGH) {
- reply.cmd = MSP_SET_PASSTHROUGH;
- reply.result = MSP_RESULT_ERROR;
- mavlinkSendTunnelMspReply(mavRecvMsg.sysid, mavRecvMsg.compid, &reply, replyPayloadHead, mspPort->mspVersion);
- mavlinkResetTunnelState(ingressPortIndex);
- break;
- }
-
- mspPostProcessFnPtr mspPostProcessFn = NULL;
- const uint16_t command = mspPort->cmdMSP;
- mspResult_e status = mspSerialProcessCommand(mspPort, mspFcProcessCommand, &reply, &mspPostProcessFn);
-
- if (mspPostProcessFn && command != MSP_REBOOT) {
- sbufInit(&reply.buf, mavTunnelReplyPayloadBuf, ARRAYEND(mavTunnelReplyPayloadBuf));
- reply.result = MSP_RESULT_ERROR;
- mspPostProcessFn = NULL;
- status = MSP_RESULT_ERROR;
- }
-
- if (status != MSP_RESULT_NO_REPLY) {
- mavlinkSendTunnelMspReply(mavRecvMsg.sysid, mavRecvMsg.compid, &reply, replyPayloadHead, mspPort->mspVersion);
- }
-
- mavlinkResetTunnelState(ingressPortIndex);
-
- if (mspPostProcessFn) {
- waitForSerialPortToFinishTransmitting(mavPortStates[ingressPortIndex].port);
- mspPostProcessFn(mavPortStates[ingressPortIndex].port);
- }
-
- break;
- }
-
- return handled;
-}
-
-static void mavlinkSendAutopilotVersion(void)
-{
- if (mavlinkGetProtocolVersion() == 1) return;
-
- // Capabilities aligned with what we actually support.
- uint64_t capabilities = 0;
- capabilities |= MAV_PROTOCOL_CAPABILITY_MAVLINK2;
- capabilities |= MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT;
- capabilities |= MAV_PROTOCOL_CAPABILITY_MISSION_INT;
- capabilities |= MAV_PROTOCOL_CAPABILITY_COMMAND_INT;
- capabilities |= MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_LOCAL_NED;
- capabilities |= MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_GLOBAL_INT;
-
- const uint32_t flightSwVersion =
- ((uint32_t)ARDUPILOT_VERSION_MAJOR << 24) |
- ((uint32_t)ARDUPILOT_VERSION_MINOR << 16) |
- ((uint32_t)ARDUPILOT_VERSION_PATCH << 8);
-
- // Bare minimum: caps + IDs. Everything else 0 is fine.
- mavlink_msg_autopilot_version_pack(
- mavSystemId,
- mavComponentId,
- &mavSendMsg,
- capabilities, // capabilities
- flightSwVersion, // flight_sw_version
- 0, // middleware_sw_version
- 0, // os_sw_version
- 0, // board_version
- 0ULL, // flight_custom_version
- 0ULL, // middleware_custom_version
- 0ULL, // os_custom_version
- 0ULL, // vendor_id
- 0ULL, // product_id
- (uint64_t)mavSystemId, // uid (any stable nonzero is fine)
- 0ULL // uid2
- );
- mavlinkSendMessage();
-}
-
-static void mavlinkSendProtocolVersion(void)
-{
- if (mavlinkGetProtocolVersion() == 1) return;
-
- uint8_t specHash[8] = {0};
- uint8_t libHash[8] = {0};
- const uint16_t protocolVersion = (uint16_t)mavlinkGetProtocolVersion() * 100;
-
- mavlink_msg_protocol_version_pack(
- mavSystemId,
- mavComponentId,
- &mavSendMsg,
- protocolVersion,
- protocolVersion,
- protocolVersion,
- specHash,
- libHash);
-
- mavlinkSendMessage();
-}
-
-static bool mavlinkFrameIsSupported(uint8_t frame, mavFrameSupportMask_e allowedMask)
-{
- switch (frame) {
- case MAV_FRAME_GLOBAL:
- return allowedMask & MAV_FRAME_SUPPORTED_GLOBAL;
- case MAV_FRAME_GLOBAL_INT:
- return allowedMask & MAV_FRAME_SUPPORTED_GLOBAL_INT;
- case MAV_FRAME_GLOBAL_RELATIVE_ALT:
- return allowedMask & MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT;
- case MAV_FRAME_GLOBAL_RELATIVE_ALT_INT:
- return allowedMask & MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT_INT;
- default:
- return false;
- }
-}
-
-static bool mavlinkFrameUsesAbsoluteAltitude(uint8_t frame)
-{
- return frame == MAV_FRAME_GLOBAL || frame == MAV_FRAME_GLOBAL_INT;
-}
-
-static MAV_RESULT mavlinkSetAltitudeTargetFromFrame(uint8_t frame, float altitudeMeters)
-{
-#ifdef USE_BARO
- geoAltitudeDatumFlag_e datum;
-
- switch (frame) {
- case MAV_FRAME_GLOBAL:
- case MAV_FRAME_GLOBAL_INT:
- datum = NAV_WP_MSL_DATUM;
- break;
- case MAV_FRAME_GLOBAL_RELATIVE_ALT:
- case MAV_FRAME_GLOBAL_RELATIVE_ALT_INT:
- datum = NAV_WP_TAKEOFF_DATUM;
- break;
- default:
- return MAV_RESULT_UNSUPPORTED;
- }
-
- const int32_t targetAltitudeCm = (int32_t)lrintf(altitudeMeters * 100.0f);
- return navigationSetAltitudeTargetWithDatum(datum, targetAltitudeCm) ? MAV_RESULT_ACCEPTED : MAV_RESULT_DENIED;
-#else
- UNUSED(frame);
- UNUSED(altitudeMeters);
- return MAV_RESULT_UNSUPPORTED;
-#endif
-}
-
-static MAV_MISSION_RESULT mavlinkMissionResultFromCommandResult(MAV_RESULT result)
-{
- switch (result) {
- case MAV_RESULT_ACCEPTED:
- return MAV_MISSION_ACCEPTED;
- case MAV_RESULT_UNSUPPORTED:
- return MAV_MISSION_UNSUPPORTED;
- default:
- return MAV_MISSION_ERROR;
- }
-}
-
-static bool mavlinkHandleArmedGuidedMissionItem(uint8_t current, uint8_t frame, mavFrameSupportMask_e allowedFrames, int32_t latitudeE7, int32_t longitudeE7, float altitudeMeters)
-{
- if (!isGCSValid()) {
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg,
- mavRecvMsg.sysid, mavRecvMsg.compid,
- MAV_MISSION_ERROR, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
- return true;
- }
-
- if (!mavlinkFrameIsSupported(frame, allowedFrames)) {
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg,
- mavRecvMsg.sysid, mavRecvMsg.compid,
- MAV_MISSION_UNSUPPORTED_FRAME, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
- return true;
- }
-
- if (current == 2) {
- navWaypoint_t wp = {0};
- wp.action = NAV_WP_ACTION_WAYPOINT;
- wp.lat = latitudeE7;
- wp.lon = longitudeE7;
- wp.alt = (int32_t)lrintf(altitudeMeters * 100.0f);
- wp.p3 = mavlinkFrameUsesAbsoluteAltitude(frame) ? NAV_WP_ALTMODE : 0;
-
- setWaypoint(255, &wp);
-
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg,
- mavRecvMsg.sysid, mavRecvMsg.compid,
- MAV_MISSION_ACCEPTED, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
- return true;
- }
-
- if (current == 3) {
- const MAV_RESULT result = mavlinkSetAltitudeTargetFromFrame(frame, altitudeMeters);
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg,
- mavRecvMsg.sysid, mavRecvMsg.compid,
- mavlinkMissionResultFromCommandResult(result), MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
- return true;
- }
-
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg,
- mavRecvMsg.sysid, mavRecvMsg.compid,
- MAV_MISSION_ERROR, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
- return true;
-}
-
-static uint8_t navWaypointFrame(const navWaypoint_t *wp, bool useIntMessages)
-{
- switch (wp->action) {
- case NAV_WP_ACTION_RTH:
- case NAV_WP_ACTION_JUMP:
- case NAV_WP_ACTION_SET_HEAD:
- return MAV_FRAME_MISSION;
- default:
- break;
- }
-
- const bool absoluteAltitude = (wp->p3 & NAV_WP_ALTMODE) == NAV_WP_ALTMODE;
-
- if (absoluteAltitude) {
- return useIntMessages ? MAV_FRAME_GLOBAL_INT : MAV_FRAME_GLOBAL;
- }
-
- return useIntMessages ? MAV_FRAME_GLOBAL_RELATIVE_ALT_INT : MAV_FRAME_GLOBAL_RELATIVE_ALT;
-}
-
-const mavlinkModeDescriptor_t planeModes[] = {
- { PLANE_MODE_MANUAL, "MANUAL" },
- { PLANE_MODE_ACRO, "ACRO" },
- { PLANE_MODE_STABILIZE, "STABILIZE" },
- { PLANE_MODE_FLY_BY_WIRE_A,"FBWA" },
- { PLANE_MODE_FLY_BY_WIRE_B,"FBWB" },
- { PLANE_MODE_CRUISE, "CRUISE" },
- { PLANE_MODE_AUTO, "AUTO" },
- { PLANE_MODE_RTL, "RTL" },
- { PLANE_MODE_LOITER, "LOITER" },
- { PLANE_MODE_TAKEOFF, "TAKEOFF" },
- { PLANE_MODE_GUIDED, "GUIDED" },
-};
-const uint8_t planeModesCount = (uint8_t)ARRAYLEN(planeModes);
-
-const mavlinkModeDescriptor_t copterModes[] = {
- { COPTER_MODE_ACRO, "ACRO" },
- { COPTER_MODE_STABILIZE, "STABILIZE" },
- { COPTER_MODE_ALT_HOLD, "ALT_HOLD" },
- { COPTER_MODE_POSHOLD, "POSHOLD" },
- { COPTER_MODE_LOITER, "LOITER" },
- { COPTER_MODE_AUTO, "AUTO" },
- { COPTER_MODE_GUIDED, "GUIDED" },
- { COPTER_MODE_RTL, "RTL" },
- { COPTER_MODE_LAND, "LAND" },
- { COPTER_MODE_BRAKE, "BRAKE" },
- { COPTER_MODE_THROW, "THROW" },
- { COPTER_MODE_SMART_RTL, "SMART_RTL" },
- { COPTER_MODE_DRIFT, "DRIFT" },
-};
-const uint8_t copterModesCount = (uint8_t)ARRAYLEN(copterModes);
-
-static bool mavlinkPlaneModeIsConfigured(uint8_t customMode)
-{
- switch ((APM_PLANE_MODE)customMode) {
- case PLANE_MODE_MANUAL:
- return isModeActivationConditionPresent(BOXMANUAL);
- case PLANE_MODE_ACRO:
- return true;
- case PLANE_MODE_STABILIZE:
- return isModeActivationConditionPresent(BOXHORIZON) ||
- isModeActivationConditionPresent(BOXANGLEHOLD);
- case PLANE_MODE_FLY_BY_WIRE_A:
- return isModeActivationConditionPresent(BOXANGLE);
- case PLANE_MODE_FLY_BY_WIRE_B:
- return isModeActivationConditionPresent(BOXNAVALTHOLD);
- case PLANE_MODE_CRUISE:
- return isModeActivationConditionPresent(BOXNAVCRUISE) ||
- (isModeActivationConditionPresent(BOXNAVCOURSEHOLD) &&
- isModeActivationConditionPresent(BOXNAVALTHOLD));
- case PLANE_MODE_AUTO:
- return isModeActivationConditionPresent(BOXNAVWP);
- case PLANE_MODE_RTL:
- return isModeActivationConditionPresent(BOXNAVRTH);
- case PLANE_MODE_GUIDED:
- return isModeActivationConditionPresent(BOXNAVPOSHOLD) &&
- isModeActivationConditionPresent(BOXGCSNAV);
- case PLANE_MODE_LOITER:
- return isModeActivationConditionPresent(BOXNAVPOSHOLD);
- case PLANE_MODE_TAKEOFF:
- return isModeActivationConditionPresent(BOXNAVLAUNCH);
- default:
- return false;
- }
-}
-
-static bool mavlinkCopterModeIsConfigured(uint8_t customMode)
-{
- switch ((APM_COPTER_MODE)customMode) {
- case COPTER_MODE_ACRO:
- return true;
- case COPTER_MODE_STABILIZE:
- return isModeActivationConditionPresent(BOXANGLE) ||
- isModeActivationConditionPresent(BOXHORIZON) ||
- isModeActivationConditionPresent(BOXANGLEHOLD);
- case COPTER_MODE_ALT_HOLD:
- return isModeActivationConditionPresent(BOXNAVALTHOLD);
- case COPTER_MODE_GUIDED:
- return isModeActivationConditionPresent(BOXNAVPOSHOLD) &&
- isModeActivationConditionPresent(BOXGCSNAV);
- case COPTER_MODE_POSHOLD:
- return isModeActivationConditionPresent(BOXNAVPOSHOLD);
- case COPTER_MODE_RTL:
- return isModeActivationConditionPresent(BOXNAVRTH);
- case COPTER_MODE_AUTO:
- return isModeActivationConditionPresent(BOXNAVWP);
- case COPTER_MODE_THROW:
- return isModeActivationConditionPresent(BOXNAVLAUNCH);
- case COPTER_MODE_BRAKE:
- return isModeActivationConditionPresent(BOXBRAKING);
- default:
- return false;
- }
-}
-
-static void mavlinkSendAvailableModes(const mavlinkModeDescriptor_t *modes, uint8_t count, uint8_t currentCustom,
- bool (*isModeConfigured)(uint8_t customMode))
-{
- uint8_t availableCount = 0;
- for (uint8_t i = 0; i < count; i++) {
- if (isModeConfigured(modes[i].customMode)) {
- availableCount++;
- }
- }
-
- if (availableCount == 0) {
- return;
- }
-
- uint8_t modeIndex = 0;
- for (uint8_t i = 0; i < count; i++) {
- if (!isModeConfigured(modes[i].customMode)) {
- continue;
- }
-
- modeIndex++;
- const uint8_t stdMode = MAV_STANDARD_MODE_NON_STANDARD;
- const uint32_t properties = 0;
-
- mavlink_msg_available_modes_pack(
- mavSystemId,
- mavComponentId,
- &mavSendMsg,
- availableCount,
- modeIndex,
- stdMode,
- modes[i].customMode,
- properties,
- modes[i].name);
-
- mavlinkSendMessage();
-
- if (modes[i].customMode == currentCustom) {
- mavlink_msg_current_mode_pack(
- mavSystemId,
- mavComponentId,
- &mavSendMsg,
- stdMode,
- currentCustom,
- currentCustom);
- mavlinkSendMessage();
- }
- }
-}
-
-static void mavlinkSendExtendedSysState(void)
-{
- uint8_t vtolState = MAV_VTOL_STATE_UNDEFINED;
- uint8_t landedState;
-
- switch (NAV_Status.state) {
- case MW_NAV_STATE_LAND_START:
- case MW_NAV_STATE_LAND_IN_PROGRESS:
- case MW_NAV_STATE_LAND_SETTLE:
- case MW_NAV_STATE_LAND_START_DESCENT:
- case MW_NAV_STATE_EMERGENCY_LANDING:
- landedState = MAV_LANDED_STATE_LANDING;
- break;
- case MW_NAV_STATE_LANDED:
- landedState = MAV_LANDED_STATE_ON_GROUND;
- break;
- default:
- if (!ARMING_FLAG(ARMED) || STATE(LANDING_DETECTED)) {
- landedState = MAV_LANDED_STATE_ON_GROUND;
- } else {
- landedState = MAV_LANDED_STATE_IN_AIR;
- }
- break;
- }
-
- mavlink_msg_extended_sys_state_pack(
- mavSystemId,
- mavComponentId,
- &mavSendMsg,
- vtolState,
- landedState);
-
- mavlinkSendMessage();
-}
-
-void mavlinkSendSystemStatus(void)
-{
- // Receiver is assumed to be always present
- uint32_t onboard_control_sensors_present = (MAV_SYS_STATUS_SENSOR_RC_RECEIVER);
- // GYRO and RC are assumed as minimum requirements
- uint32_t onboard_control_sensors_enabled = (MAV_SYS_STATUS_SENSOR_3D_GYRO | MAV_SYS_STATUS_SENSOR_RC_RECEIVER);
- uint32_t onboard_control_sensors_health = 0;
-
- if (getHwGyroStatus() == HW_SENSOR_OK) {
- onboard_control_sensors_present |= MAV_SYS_STATUS_SENSOR_3D_GYRO;
- // Missing presence will report as sensor unhealthy
- onboard_control_sensors_health |= MAV_SYS_STATUS_SENSOR_3D_GYRO;
- }
-
- hardwareSensorStatus_e accStatus = getHwAccelerometerStatus();
- if (accStatus == HW_SENSOR_OK) {
- onboard_control_sensors_present |= MAV_SYS_STATUS_SENSOR_3D_ACCEL;
- onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_3D_ACCEL;
- onboard_control_sensors_health |= MAV_SYS_STATUS_SENSOR_3D_ACCEL;
- } else if (accStatus == HW_SENSOR_UNHEALTHY) {
- onboard_control_sensors_present |= MAV_SYS_STATUS_SENSOR_3D_ACCEL;
- onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_3D_ACCEL;
- } else if (accStatus == HW_SENSOR_UNAVAILABLE) {
- onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_3D_ACCEL;
- }
-
- hardwareSensorStatus_e compassStatus = getHwCompassStatus();
- if (compassStatus == HW_SENSOR_OK) {
- onboard_control_sensors_present |= MAV_SYS_STATUS_SENSOR_3D_MAG;
- onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_3D_MAG;
- onboard_control_sensors_health |= MAV_SYS_STATUS_SENSOR_3D_MAG;
- } else if (compassStatus == HW_SENSOR_UNHEALTHY) {
- onboard_control_sensors_present |= MAV_SYS_STATUS_SENSOR_3D_MAG;
- onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_3D_MAG;
- } else if (compassStatus == HW_SENSOR_UNAVAILABLE) {
- onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_3D_MAG;
- }
-
- hardwareSensorStatus_e baroStatus = getHwBarometerStatus();
- if (baroStatus == HW_SENSOR_OK) {
- onboard_control_sensors_present |= MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE;
- onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE;
- onboard_control_sensors_health |= MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE;
- } else if (baroStatus == HW_SENSOR_UNHEALTHY) {
- onboard_control_sensors_present |= MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE;
- onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE;
- } else if (baroStatus == HW_SENSOR_UNAVAILABLE) {
- onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE;
- }
-
- hardwareSensorStatus_e pitotStatus = getHwPitotmeterStatus();
- if (pitotStatus == HW_SENSOR_OK) {
- onboard_control_sensors_present |= MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE;
- onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE;
- onboard_control_sensors_health |= MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE;
- } else if (pitotStatus == HW_SENSOR_UNHEALTHY) {
- onboard_control_sensors_present |= MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE;
- onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE;
- } else if (pitotStatus == HW_SENSOR_UNAVAILABLE) {
- onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE;
- }
-
- hardwareSensorStatus_e gpsStatus = getHwGPSStatus();
- if (gpsStatus == HW_SENSOR_OK) {
- onboard_control_sensors_present |= MAV_SYS_STATUS_SENSOR_GPS;
- onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_GPS;
- onboard_control_sensors_health |= MAV_SYS_STATUS_SENSOR_GPS;
- } else if (gpsStatus == HW_SENSOR_UNHEALTHY) {
- onboard_control_sensors_present |= MAV_SYS_STATUS_SENSOR_GPS;
- onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_GPS;
- } else if (gpsStatus == HW_SENSOR_UNAVAILABLE) {
- onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_GPS;
- }
-
- hardwareSensorStatus_e opFlowStatus = getHwOpticalFlowStatus();
- if (opFlowStatus == HW_SENSOR_OK) {
- onboard_control_sensors_present |= MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW;
- onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW;
- onboard_control_sensors_health |= MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW;
- } else if (opFlowStatus == HW_SENSOR_UNHEALTHY) {
- onboard_control_sensors_present |= MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW;
- onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW;
- } else if (opFlowStatus == HW_SENSOR_UNAVAILABLE) {
- onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW;
- }
-
- hardwareSensorStatus_e rangefinderStatus = getHwRangefinderStatus();
- if (rangefinderStatus == HW_SENSOR_OK) {
- onboard_control_sensors_present |= MAV_SYS_STATUS_SENSOR_LASER_POSITION;
- onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_LASER_POSITION;
- onboard_control_sensors_health |= MAV_SYS_STATUS_SENSOR_LASER_POSITION;
- } else if (rangefinderStatus == HW_SENSOR_UNHEALTHY) {
- onboard_control_sensors_present |= MAV_SYS_STATUS_SENSOR_LASER_POSITION;
- onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_LASER_POSITION;
- } else if (rangefinderStatus == HW_SENSOR_UNAVAILABLE) {
- onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_LASER_POSITION;
- }
-
- if (rxIsReceivingSignal() && rxAreFlightChannelsValid()) {
- onboard_control_sensors_health |= MAV_SYS_STATUS_SENSOR_RC_RECEIVER;
- }
-
-#ifdef USE_BLACKBOX
- // BLACKBOX is assumed enabled and present for boards with capability
- onboard_control_sensors_present |= MAV_SYS_STATUS_LOGGING;
- onboard_control_sensors_enabled |= MAV_SYS_STATUS_LOGGING;
- // Unhealthy only for cases with not enough space to record
- if (!isBlackboxDeviceFull()) {
- onboard_control_sensors_health |= MAV_SYS_STATUS_LOGGING;
- }
-#endif
-
- mavlink_msg_sys_status_pack(mavSystemId, mavComponentId, &mavSendMsg,
- // onboard_control_sensors_present Bitmask showing which onboard controllers and sensors are present.
- //Value of 0: not present. Value of 1: present. Indices according MAV_SYS_STATUS_SENSOR
- onboard_control_sensors_present,
- // onboard_control_sensors_enabled Bitmask showing which onboard controllers and sensors are enabled
- onboard_control_sensors_enabled,
- // onboard_control_sensors_health Bitmask showing which onboard controllers and sensors are operational or have an error.
- onboard_control_sensors_health,
- // load Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000
- constrain(averageSystemLoadPercent*10, 0, 1000),
- // voltage_battery Battery voltage, in millivolts (1 = 1 millivolt)
- feature(FEATURE_VBAT) ? getBatteryVoltage() * 10 : 0,
- // current_battery Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current
- isAmperageConfigured() ? getAmperage() : -1,
- // battery_remaining Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery
- feature(FEATURE_VBAT) ? calculateBatteryPercentage() : 100,
- // drop_rate_comm Communication drops in percent, (0%: 0, 100%: 10'000), (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)
- 0,
- // errors_comm Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)
- 0,
- // errors_count1 Autopilot-specific errors
- 0,
- // errors_count2 Autopilot-specific errors
- 0,
- // errors_count3 Autopilot-specific errors
- 0,
- // errors_count4 Autopilot-specific errors
- 0, 0, 0, 0);
-
- mavlinkSendMessage();
-}
-
-void mavlinkSendRCChannelsAndRSSI(void)
-{
-#define GET_CHANNEL_VALUE(x) ((rxRuntimeConfig.channelCount >= (x + 1)) ? rxGetChannelValue(x) : 0)
- if (mavlinkGetProtocolVersion() == 1) {
- mavlink_msg_rc_channels_raw_pack(mavSystemId, mavComponentId, &mavSendMsg,
- // time_boot_ms Timestamp (milliseconds since system boot)
- millis(),
- // port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos.
- 0,
- // chan1_raw RC channel 1 value, in microseconds
- GET_CHANNEL_VALUE(0),
- // chan2_raw RC channel 2 value, in microseconds
- GET_CHANNEL_VALUE(1),
- // chan3_raw RC channel 3 value, in microseconds
- GET_CHANNEL_VALUE(2),
- // chan4_raw RC channel 4 value, in microseconds
- GET_CHANNEL_VALUE(3),
- // chan5_raw RC channel 5 value, in microseconds
- GET_CHANNEL_VALUE(4),
- // chan6_raw RC channel 6 value, in microseconds
- GET_CHANNEL_VALUE(5),
- // chan7_raw RC channel 7 value, in microseconds
- GET_CHANNEL_VALUE(6),
- // chan8_raw RC channel 8 value, in microseconds
- GET_CHANNEL_VALUE(7),
- // rssi Receive signal strength indicator, 0: 0%, 254: 100%
- //https://github.com/mavlink/mavlink/issues/1027
- scaleRange(getRSSI(), 0, 1023, 0, 254));
- }
- else {
- mavlink_msg_rc_channels_pack(mavSystemId, mavComponentId, &mavSendMsg,
- // time_boot_ms Timestamp (milliseconds since system boot)
- millis(),
- // Total number of RC channels being received.
- rxRuntimeConfig.channelCount,
- // chan1_raw RC channel 1 value, in microseconds
- GET_CHANNEL_VALUE(0),
- // chan2_raw RC channel 2 value, in microseconds
- GET_CHANNEL_VALUE(1),
- // chan3_raw RC channel 3 value, in microseconds
- GET_CHANNEL_VALUE(2),
- // chan4_raw RC channel 4 value, in microseconds
- GET_CHANNEL_VALUE(3),
- // chan5_raw RC channel 5 value, in microseconds
- GET_CHANNEL_VALUE(4),
- // chan6_raw RC channel 6 value, in microseconds
- GET_CHANNEL_VALUE(5),
- // chan7_raw RC channel 7 value, in microseconds
- GET_CHANNEL_VALUE(6),
- // chan8_raw RC channel 8 value, in microseconds
- GET_CHANNEL_VALUE(7),
- // chan9_raw RC channel 9 value, in microseconds
- GET_CHANNEL_VALUE(8),
- // chan10_raw RC channel 10 value, in microseconds
- GET_CHANNEL_VALUE(9),
- // chan11_raw RC channel 11 value, in microseconds
- GET_CHANNEL_VALUE(10),
- // chan12_raw RC channel 12 value, in microseconds
- GET_CHANNEL_VALUE(11),
- // chan13_raw RC channel 13 value, in microseconds
- GET_CHANNEL_VALUE(12),
- // chan14_raw RC channel 14 value, in microseconds
- GET_CHANNEL_VALUE(13),
- // chan15_raw RC channel 15 value, in microseconds
- GET_CHANNEL_VALUE(14),
- // chan16_raw RC channel 16 value, in microseconds
- GET_CHANNEL_VALUE(15),
- // chan17_raw RC channel 17 value, in microseconds
- GET_CHANNEL_VALUE(16),
- // chan18_raw RC channel 18 value, in microseconds
- GET_CHANNEL_VALUE(17),
- // rssi Receive signal strength indicator, 0: 0%, 254: 100%
- //https://github.com/mavlink/mavlink/issues/1027
- scaleRange(getRSSI(), 0, 1023, 0, 254));
- }
-#undef GET_CHANNEL_VALUE
-
- mavlinkSendMessage();
+ mavlinkRuntimeCheckState();
}
-#if defined(USE_GPS)
-static void mavlinkSendHomePosition(void)
+void freeMAVLinkTelemetryPort(void)
{
- float q[4] = { 1.0f, 0.0f, 0.0f, 0.0f };
-
- mavlink_msg_home_position_pack(
- mavSystemId,
- mavComponentId,
- &mavSendMsg,
- GPS_home.lat,
- GPS_home.lon,
- GPS_home.alt * 10,
- 0.0f,
- 0.0f,
- 0.0f,
- q,
- 0.0f,
- 0.0f,
- 0.0f,
- ((uint64_t) millis()) * 1000);
-
- mavlinkSendMessage();
-}
-
-static void mavlinkSendGpsRawInt(timeUs_t currentTimeUs)
-{
- uint8_t gpsFixType = 0;
-
- if (!(sensors(SENSOR_GPS)
-#ifdef USE_GPS_FIX_ESTIMATION
- || STATE(GPS_ESTIMATED_FIX)
-#endif
- ))
- return;
-
- if (gpsSol.fixType == GPS_NO_FIX)
- gpsFixType = 1;
- else if (gpsSol.fixType == GPS_FIX_2D)
- gpsFixType = 2;
- else if (gpsSol.fixType == GPS_FIX_3D)
- gpsFixType = 3;
-
- mavlink_msg_gps_raw_int_pack(mavSystemId, mavComponentId, &mavSendMsg,
- // time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
- currentTimeUs,
- // fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
- gpsFixType,
- // lat Latitude in 1E7 degrees
- gpsSol.llh.lat,
- // lon Longitude in 1E7 degrees
- gpsSol.llh.lon,
- // alt Altitude in 1E3 meters (millimeters) above MSL
- gpsSol.llh.alt * 10,
- // eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
- gpsSol.eph,
- // epv GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
- gpsSol.epv,
- // vel GPS ground speed (m/s * 100). If unknown, set to: 65535
- gpsSol.groundSpeed,
- // cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535
- gpsSol.groundCourse * 10,
- // satellites_visible Number of satellites visible. If unknown, set to 255
- gpsSol.numSat,
- // alt_ellipsoid Altitude (above WGS84, EGM96 ellipsoid). Positive for up
- 0,
- // h_acc Position uncertainty in mm,
- gpsSol.eph * 10,
- // v_acc Altitude uncertainty in mm,
- gpsSol.epv * 10,
- // vel_acc Speed uncertainty in mm (??)
- 0,
- // hdg_acc Heading uncertainty in degE5
- 0,
- // yaw Yaw in earth frame from north. Use 0 if this GPS does not provide yaw. Use 65535 if this GPS is configured to provide yaw and is currently unable to provide it. Use 36000 for north.
- 0);
-
- mavlinkSendMessage();
-}
-
-static void mavlinkSendGlobalPositionInt(timeUs_t currentTimeUs)
-{
- if (!(sensors(SENSOR_GPS)
-#ifdef USE_GPS_FIX_ESTIMATION
- || STATE(GPS_ESTIMATED_FIX)
-#endif
- )) {
- return;
- }
-
- mavlink_msg_global_position_int_pack(mavSystemId, mavComponentId, &mavSendMsg,
- // time_boot_ms Timestamp (milliseconds since system boot)
- currentTimeUs / 1000,
- // lat Latitude in 1E7 degrees
- gpsSol.llh.lat,
- // lon Longitude in 1E7 degrees
- gpsSol.llh.lon,
- // alt Altitude in 1E3 meters (millimeters) above MSL
- gpsSol.llh.alt * 10,
- // relative_alt Altitude above ground in meters, expressed as * 1000 (millimeters)
- getEstimatedActualPosition(Z) * 10,
- // [cm/s] Ground X Speed (Latitude, positive north)
- getEstimatedActualVelocity(X),
- // [cm/s] Ground Y Speed (Longitude, positive east)
- getEstimatedActualVelocity(Y),
- // [cm/s] Ground Z Speed (Altitude, positive down)
- -getEstimatedActualVelocity(Z),
- // [cdeg] Vehicle heading (yaw angle) (0.0..359.99 degrees, 0=north)
- DECIDEGREES_TO_CENTIDEGREES(attitude.values.yaw)
- );
-
- mavlinkSendMessage();
-}
-
-static void mavlinkSendGpsGlobalOrigin(void)
-{
- mavlink_msg_gps_global_origin_pack(mavSystemId, mavComponentId, &mavSendMsg,
- // latitude Latitude (WGS84), expressed as * 1E7
- GPS_home.lat,
- // longitude Longitude (WGS84), expressed as * 1E7
- GPS_home.lon,
- // altitude Altitude(WGS84), expressed as * 1000
- GPS_home.alt * 10, // FIXME
- // time_usec Timestamp (microseconds since system boot)
- // Use millis() * 1000 as micros() will overflow after 1.19 hours.
- ((uint64_t) millis()) * 1000);
-
- mavlinkSendMessage();
-}
-
-void mavlinkSendPosition(timeUs_t currentTimeUs)
-{
- mavlinkSendGpsRawInt(currentTimeUs);
- mavlinkSendGlobalPositionInt(currentTimeUs);
- mavlinkSendGpsGlobalOrigin();
-}
-#endif
-
-void mavlinkSendAttitude(void)
-{
- mavlink_msg_attitude_pack(mavSystemId, mavComponentId, &mavSendMsg,
- // time_boot_ms Timestamp (milliseconds since system boot)
- millis(),
- // roll Roll angle (rad)
- RADIANS_TO_MAVLINK_RANGE(DECIDEGREES_TO_RADIANS(attitude.values.roll)),
- // pitch Pitch angle (rad)
- RADIANS_TO_MAVLINK_RANGE(DECIDEGREES_TO_RADIANS(-attitude.values.pitch)),
- // yaw Yaw angle (rad)
- RADIANS_TO_MAVLINK_RANGE(DECIDEGREES_TO_RADIANS(attitude.values.yaw)),
- // rollspeed Roll angular speed (rad/s)
- DEGREES_TO_RADIANS(gyro.gyroADCf[FD_ROLL]),
- // pitchspeed Pitch angular speed (rad/s)
- DEGREES_TO_RADIANS(gyro.gyroADCf[FD_PITCH]),
- // yawspeed Yaw angular speed (rad/s)
- DEGREES_TO_RADIANS(gyro.gyroADCf[FD_YAW]));
-
- mavlinkSendMessage();
-}
-
-void mavlinkSendVfrHud(void)
-{
- float mavAltitude = 0;
- float mavGroundSpeed = 0;
- float mavAirSpeed = 0;
- float mavClimbRate = 0;
-
-#if defined(USE_GPS)
- // use ground speed if source available
- if (sensors(SENSOR_GPS)
-#ifdef USE_GPS_FIX_ESTIMATION
- || STATE(GPS_ESTIMATED_FIX)
-#endif
- ) {
- mavGroundSpeed = gpsSol.groundSpeed / 100.0f;
- }
-#endif
-
-#if defined(USE_PITOT)
- if (sensors(SENSOR_PITOT) && pitotIsHealthy()) {
- mavAirSpeed = getAirspeedEstimate() / 100.0f;
- }
-#endif
-
- // select best source for altitude
- mavAltitude = getEstimatedActualPosition(Z) / 100.0f;
- mavClimbRate = getEstimatedActualVelocity(Z) / 100.0f;
-
- int16_t thr = getThrottlePercent(osdUsingScaledThrottle());
- mavlink_msg_vfr_hud_pack(mavSystemId, mavComponentId, &mavSendMsg,
- // airspeed Current airspeed in m/s
- mavAirSpeed,
- // groundspeed Current ground speed in m/s
- mavGroundSpeed,
- // heading Current heading in degrees, in compass units (0..360, 0=north)
- DECIDEGREES_TO_DEGREES(attitude.values.yaw),
- // throttle Current throttle setting in integer percent, 0 to 100
- thr,
- // alt Current altitude (MSL), in meters, if we have surface or baro use them, otherwise use GPS (less accurate)
- mavAltitude,
- // climb Current climb rate in meters/second
- mavClimbRate);
-
- mavlinkSendMessage();
-}
-
-static uint8_t mavlinkGetAutopilotEnum(void);
-
-void mavlinkSendHeartbeat(void)
-{
- uint8_t mavModes = MAV_MODE_FLAG_CUSTOM_MODE_ENABLED;
-
- const bool isPlane = (STATE(FIXED_WING_LEGACY) || mixerConfig()->platformType == PLATFORM_AIRPLANE);
- const mavlinkModeSelection_t modeSelection = selectMavlinkMode(isPlane);
- flightModeForTelemetry_e flm = modeSelection.flightMode;
- uint8_t mavCustomMode = modeSelection.customMode;
- uint8_t mavSystemType;
- if (isPlane) {
- mavSystemType = MAV_TYPE_FIXED_WING;
- }
- else {
- mavSystemType = mavlinkGetVehicleType();
- }
-
- const bool manualInputAllowed = !(flm == FLM_MISSION || flm == FLM_RTH || flm == FLM_FAILSAFE);
- if (manualInputAllowed) {
- mavModes |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED;
- }
- if (flm == FLM_POSITION_HOLD && isGCSValid()) {
- mavModes |= MAV_MODE_FLAG_GUIDED_ENABLED;
- }
- else if (flm == FLM_MISSION || flm == FLM_RTH ) {
- mavModes |= MAV_MODE_FLAG_AUTO_ENABLED;
- }
- else if (flm != FLM_MANUAL && flm!= FLM_ACRO && flm!=FLM_ACRO_AIR) {
- mavModes |= MAV_MODE_FLAG_STABILIZE_ENABLED;
- }
-
- if (ARMING_FLAG(ARMED))
- mavModes |= MAV_MODE_FLAG_SAFETY_ARMED;
-
- uint8_t mavSystemState = 0;
- if (ARMING_FLAG(ARMED)) {
- if (failsafeIsActive()) {
- mavSystemState = MAV_STATE_CRITICAL;
- }
- else {
- mavSystemState = MAV_STATE_ACTIVE;
- }
- }
- else if (areSensorsCalibrating()) {
- mavSystemState = MAV_STATE_CALIBRATING;
- }
- else {
- mavSystemState = MAV_STATE_STANDBY;
- }
-
- mavlink_msg_heartbeat_pack(mavSystemId, mavComponentId, &mavSendMsg,
- // type Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
- mavSystemType,
- // autopilot Autopilot type / class. defined in MAV_AUTOPILOT ENUM
- mavlinkGetAutopilotEnum(),
- // base_mode System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h
- mavModes,
- // custom_mode A bitfield for use for autopilot-specific flags.
- mavCustomMode,
- // system_status System status flag, see MAV_STATE ENUM
- mavSystemState);
-
- mavlinkSendMessage();
-}
-
-static void mavlinkSendBatteryStatus(void)
-{
- uint16_t batteryVoltages[MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_LEN];
- uint16_t batteryVoltagesExt[MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_EXT_LEN];
- memset(batteryVoltages, UINT16_MAX, sizeof(batteryVoltages));
- memset(batteryVoltagesExt, 0, sizeof(batteryVoltagesExt));
- if (feature(FEATURE_VBAT)) {
- uint8_t batteryCellCount = getBatteryCellCount();
- if (batteryCellCount > 0) {
- for (int cell=0; cell < batteryCellCount && cell < MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_LEN + MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_EXT_LEN; cell++) {
- if (cell < MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_LEN) {
- batteryVoltages[cell] = getBatteryAverageCellVoltage() * 10;
- } else {
- batteryVoltagesExt[cell-MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_LEN] = getBatteryAverageCellVoltage() * 10;
- }
- }
- }
- else {
- batteryVoltages[0] = getBatteryVoltage() * 10;
- }
- }
- else {
- batteryVoltages[0] = 0;
- }
-
- mavlink_msg_battery_status_pack(mavSystemId, mavComponentId, &mavSendMsg,
- // id Battery ID
- 0,
- // battery_function Function of the battery
- MAV_BATTERY_FUNCTION_UNKNOWN,
- // type Type (chemistry) of the battery
- MAV_BATTERY_TYPE_UNKNOWN,
- // temperature Temperature of the battery in centi-degrees celsius. INT16_MAX for unknown temperature
- INT16_MAX,
- // voltages Battery voltage of cells, in millivolts (1 = 1 millivolt). Cells above the valid cell count for this battery should have the UINT16_MAX value.
- batteryVoltages,
- // current_battery Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current
- isAmperageConfigured() ? getAmperage() : -1,
- // current_consumed Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate
- isAmperageConfigured() ? getMAhDrawn() : -1,
- // energy_consumed Consumed energy, in 100*Joules (intergrated U*I*dt) (1 = 100 Joule), -1: autopilot does not provide energy consumption estimate
- isAmperageConfigured() ? getMWhDrawn()*36 : -1,
- // battery_remaining Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery);
- feature(FEATURE_VBAT) ? calculateBatteryPercentage() : -1,
- // time_remaining Remaining battery time, 0: autopilot does not provide remaining battery time estimate
- 0, // TODO this could easily be implemented
- // charge_state State for extent of discharge, provided by autopilot for warning or external reactions
- 0,
- // voltages_ext Battery voltages for cells 11 to 14. Cells above the valid cell count for this battery should have a value of 0, where zero indicates not supported (note, this is different than for the voltages field and allows empty byte truncation). If the measured value is 0 then 1 should be sent instead.
- batteryVoltagesExt,
- // mode Battery mode. Default (0) is that battery mode reporting is not supported or battery is in normal-use mode.
- 0,
- // fault_bitmask Fault/health indications. These should be set when charge_state is MAV_BATTERY_CHARGE_STATE_FAILED or MAV_BATTERY_CHARGE_STATE_UNHEALTHY (if not, fault reporting is not supported).
- 0);
-
- mavlinkSendMessage();
-}
-
-static void mavlinkSendScaledPressure(void)
-{
- int16_t temperature;
- sensors(SENSOR_BARO) ? getBaroTemperature(&temperature) : getIMUTemperature(&temperature);
- mavlink_msg_scaled_pressure_pack(mavSystemId, mavComponentId, &mavSendMsg,
- millis(),
- 0,
- 0,
- temperature * 10,
- 0);
-
- mavlinkSendMessage();
-}
-
-static void mavlinkSendSystemTime(void)
-{
- mavlink_msg_system_time_pack(
- mavSystemId,
- mavComponentId,
- &mavSendMsg,
- 0,
- millis());
-
- mavlinkSendMessage();
-}
-
-static bool mavlinkSendStatusText(void)
-{
-// FIXME - Status text is limited to boards with USE_OSD
-#ifdef USE_OSD
- char buff[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN] = {" "};
- textAttributes_t elemAttr = osdGetSystemMessage(buff, sizeof(buff), false);
- if (buff[0] != SYM_BLANK) {
- MAV_SEVERITY severity = MAV_SEVERITY_NOTICE;
- if (TEXT_ATTRIBUTES_HAVE_BLINK(elemAttr)) {
- severity = MAV_SEVERITY_CRITICAL;
- } else if TEXT_ATTRIBUTES_HAVE_INVERTED(elemAttr) {
- severity = MAV_SEVERITY_WARNING;
- }
-
- mavlink_msg_statustext_pack(mavSystemId, mavComponentId, &mavSendMsg,
- (uint8_t)severity,
- buff,
- 0,
- 0);
-
- mavlinkSendMessage();
- return true;
- }
-#endif
- return false;
-}
-
-void mavlinkSendBatteryTemperatureStatusText(void)
-{
- mavlinkSendBatteryStatus();
- mavlinkSendScaledPressure();
- mavlinkSendStatusText();
-}
-
-static uint8_t mavlinkGetAutopilotEnum(void)
-{
- if (mavAutopilotType == MAVLINK_AUTOPILOT_ARDUPILOT) {
- return MAV_AUTOPILOT_ARDUPILOTMEGA;
- }
-
- return MAV_AUTOPILOT_GENERIC;
-}
-
-static uint8_t mavlinkHeadingDeg2FromCd(int32_t headingCd)
-{
- return (uint8_t)(wrap_36000(headingCd) / 200);
-}
-
-static uint16_t mavlinkComputeHighLatencyFailures(void)
-{
- uint16_t flags = 0;
-
-#if defined(USE_GPS)
- if (!(sensors(SENSOR_GPS)
-#ifdef USE_GPS_FIX_ESTIMATION
- || STATE(GPS_ESTIMATED_FIX)
-#endif
- ) || gpsSol.fixType == GPS_NO_FIX) {
- flags |= HL_FAILURE_FLAG_GPS;
- }
-#endif
-
-#ifdef USE_PITOT
- if (getHwPitotmeterStatus() != HW_SENSOR_OK) {
- flags |= HL_FAILURE_FLAG_DIFFERENTIAL_PRESSURE;
- }
-#endif
-
- if (getHwBarometerStatus() != HW_SENSOR_OK) {
- flags |= HL_FAILURE_FLAG_ABSOLUTE_PRESSURE;
- }
-
- if (getHwAccelerometerStatus() != HW_SENSOR_OK) {
- flags |= HL_FAILURE_FLAG_3D_ACCEL;
- }
-
- if (getHwGyroStatus() != HW_SENSOR_OK) {
- flags |= HL_FAILURE_FLAG_3D_GYRO;
- }
-
- if (getHwCompassStatus() != HW_SENSOR_OK) {
- flags |= HL_FAILURE_FLAG_3D_MAG;
- }
-
- if (getHwRangefinderStatus() != HW_SENSOR_OK) {
- flags |= HL_FAILURE_FLAG_TERRAIN;
- }
-
- const batteryState_e batteryState = getBatteryState();
- if (batteryState == BATTERY_WARNING || batteryState == BATTERY_CRITICAL) {
- flags |= HL_FAILURE_FLAG_BATTERY;
- }
-
- if (!rxIsReceivingSignal() || !rxAreFlightChannelsValid()) {
- flags |= HL_FAILURE_FLAG_RC_RECEIVER;
- }
-
- return flags;
-}
-
-static void mavlinkSendHighLatency2(timeUs_t currentTimeUs)
-{
- const bool isPlane = (STATE(FIXED_WING_LEGACY) || mixerConfig()->platformType == PLATFORM_AIRPLANE);
- const mavlinkModeSelection_t modeSelection = selectMavlinkMode(isPlane);
-
- int32_t latitude = 0;
- int32_t longitude = 0;
- int16_t altitude = (int16_t)constrain((int32_t)(getEstimatedActualPosition(Z) / 100), INT16_MIN, INT16_MAX);
- int16_t targetAltitude = (int16_t)constrain((int32_t)(posControl.desiredState.pos.z / 100), INT16_MIN, INT16_MAX);
- uint16_t targetDistance = 0;
- uint16_t wpNum = 0;
- uint8_t heading = mavlinkHeadingDeg2FromCd(DECIDEGREES_TO_CENTIDEGREES(attitude.values.yaw));
- uint8_t targetHeading = mavlinkHeadingDeg2FromCd(posControl.desiredState.yaw);
- uint8_t groundspeed = 0;
- uint8_t airspeed = 0;
- uint8_t airspeedSp = 0;
- uint8_t windspeed = 0;
- uint8_t windHeading = 0;
- uint8_t eph = UINT8_MAX;
- uint8_t epv = UINT8_MAX;
- int8_t temperatureAir = 0;
- int8_t climbRate = (int8_t)constrain(lrintf(getEstimatedActualVelocity(Z) / 10.0f), INT8_MIN, INT8_MAX);
- int8_t battery = feature(FEATURE_VBAT) ? (int8_t)calculateBatteryPercentage() : -1;
-
-#if defined(USE_GPS)
- if (sensors(SENSOR_GPS)
-#ifdef USE_GPS_FIX_ESTIMATION
- || STATE(GPS_ESTIMATED_FIX)
-#endif
- ) {
- latitude = gpsSol.llh.lat;
- longitude = gpsSol.llh.lon;
- altitude = (int16_t)constrain((int32_t)(gpsSol.llh.alt / 100), INT16_MIN, INT16_MAX);
-
- const int32_t desiredAltCm = lrintf(posControl.desiredState.pos.z);
- const int32_t targetAltCm = GPS_home.alt + desiredAltCm;
- targetAltitude = (int16_t)constrain(targetAltCm / 100, INT16_MIN, INT16_MAX);
-
- groundspeed = (uint8_t)constrain(lrintf(gpsSol.groundSpeed / 20.0f), 0, UINT8_MAX);
-
- if (gpsSol.flags.validEPE) {
- eph = (uint8_t)constrain((gpsSol.eph + 5) / 10, 0, UINT8_MAX);
- epv = (uint8_t)constrain((gpsSol.epv + 5) / 10, 0, UINT8_MAX);
- }
-
- if (posControl.activeWaypointIndex >= 0) {
- wpNum = (uint16_t)posControl.activeWaypointIndex;
- targetDistance = (uint16_t)constrain(lrintf(posControl.wpDistance / 1000.0f), 0, UINT16_MAX);
- }
- }
-#endif
-
-#if defined(USE_PITOT)
- if (sensors(SENSOR_PITOT) && pitotIsHealthy()) {
- airspeed = (uint8_t)constrain(lrintf(getAirspeedEstimate() / 20.0f), 0, UINT8_MAX);
- airspeedSp = airspeed;
- }
-#endif
-
- if (airspeedSp == 0) {
- const float desiredVelXY = calc_length_pythagorean_2D(posControl.desiredState.vel.x, posControl.desiredState.vel.y);
- airspeedSp = (uint8_t)constrain(lrintf(desiredVelXY / 20.0f), 0, UINT8_MAX);
- }
-
- if (airspeed == 0) {
- airspeed = groundspeed;
- }
-
-#ifdef USE_WIND_ESTIMATOR
- if (isEstimatedWindSpeedValid()) {
- uint16_t windAngleCd = 0;
- const float windHoriz = getEstimatedHorizontalWindSpeed(&windAngleCd);
- windspeed = (uint8_t)constrain(lrintf(windHoriz / 20.0f), 0, UINT8_MAX);
- windHeading = mavlinkHeadingDeg2FromCd(windAngleCd);
- }
-#endif
-
- int16_t temperature;
- sensors(SENSOR_BARO) ? getBaroTemperature(&temperature) : getIMUTemperature(&temperature);
- temperatureAir = (int8_t)constrain(temperature, INT8_MIN, INT8_MAX);
-
- const uint16_t failureFlags = mavlinkComputeHighLatencyFailures();
-
- mavlink_msg_high_latency2_pack(
- mavSystemId,
- mavComponentId,
- &mavSendMsg,
- (uint32_t)(currentTimeUs / 1000),
- mavlinkGetVehicleType(),
- mavlinkGetAutopilotEnum(),
- modeSelection.customMode,
- latitude,
- longitude,
- altitude,
- targetAltitude,
- heading,
- targetHeading,
- targetDistance,
- (uint8_t)constrain(getThrottlePercent(osdUsingScaledThrottle()), 0, 100),
- airspeed,
- airspeedSp,
- groundspeed,
- windspeed,
- windHeading,
- eph,
- epv,
- temperatureAir,
- climbRate,
- battery,
- wpNum,
- failureFlags,
- 0,
- 0,
- 0);
-
- mavlinkSendMessage();
-}
-
-void processMAVLinkTelemetry(timeUs_t currentTimeUs)
-{
- if (mavActivePort->highLatencyEnabled && mavlinkGetProtocolVersion() != 1) {
- if ((currentTimeUs - mavActivePort->lastHighLatencyMessageUs) >= TELEMETRY_MAVLINK_HIGH_LATENCY_INTERVAL_US) {
- mavlinkSendHighLatency2(currentTimeUs);
- mavActivePort->lastHighLatencyMessageUs = currentTimeUs;
- }
- return;
- }
-
- // is executed @ TELEMETRY_MAVLINK_MAXRATE rate
- if (mavlinkMessageTrigger(MAVLINK_PERIODIC_MESSAGE_SYS_STATUS, currentTimeUs)) {
- mavlinkSendSystemStatus();
- }
-
- if (mavlinkMessageTrigger(MAVLINK_PERIODIC_MESSAGE_RC_CHANNELS, currentTimeUs)) {
- mavlinkSendRCChannelsAndRSSI();
- }
-
-#ifdef USE_GPS
- if (mavlinkMessageTrigger(MAVLINK_PERIODIC_MESSAGE_GPS_RAW_INT, currentTimeUs)) {
- mavlinkSendGpsRawInt(currentTimeUs);
- }
-
- if (mavlinkMessageTrigger(MAVLINK_PERIODIC_MESSAGE_GLOBAL_POSITION_INT, currentTimeUs)) {
- mavlinkSendGlobalPositionInt(currentTimeUs);
- }
-
- if (mavlinkMessageTrigger(MAVLINK_PERIODIC_MESSAGE_GPS_GLOBAL_ORIGIN, currentTimeUs)) {
- mavlinkSendGpsGlobalOrigin();
- }
-#endif
-
- if (mavlinkMessageTrigger(MAVLINK_PERIODIC_MESSAGE_ATTITUDE, currentTimeUs)) {
- mavlinkSendAttitude();
- }
-
- if (mavlinkMessageTrigger(MAVLINK_PERIODIC_MESSAGE_VFR_HUD, currentTimeUs)) {
- mavlinkSendVfrHud();
- }
-
- if (mavlinkMessageTrigger(MAVLINK_PERIODIC_MESSAGE_HEARTBEAT, currentTimeUs)) {
- mavlinkSendHeartbeat();
- }
-
- if (mavlinkMessageTrigger(MAVLINK_PERIODIC_MESSAGE_EXTENDED_SYS_STATE, currentTimeUs)) {
- mavlinkSendExtendedSysState();
- }
-
- if (mavlinkMessageTrigger(MAVLINK_PERIODIC_MESSAGE_BATTERY_STATUS, currentTimeUs)) {
- mavlinkSendBatteryStatus();
- }
-
- if (mavlinkMessageTrigger(MAVLINK_PERIODIC_MESSAGE_SCALED_PRESSURE, currentTimeUs)) {
- mavlinkSendScaledPressure();
- }
-
- if (mavlinkMessageTrigger(MAVLINK_PERIODIC_MESSAGE_SYSTEM_TIME, currentTimeUs)) {
- mavlinkSendSystemTime();
- }
-
- if (mavlinkStreamTrigger(MAV_DATA_STREAM_EXTRA3, currentTimeUs)) {
- mavlinkSendStatusText();
- }
-
-}
-
-static void mavlinkResetIncomingMissionTransaction(void);
-
-static bool handleIncoming_MISSION_CLEAR_ALL(void)
-{
- mavlink_mission_clear_all_t msg;
- mavlink_msg_mission_clear_all_decode(&mavRecvMsg, &msg);
-
- // Check if this message is for us
- if (msg.target_system == mavSystemId) {
- resetWaypointList();
- mavlinkResetIncomingMissionTransaction();
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, MAV_MISSION_ACCEPTED, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
- return true;
- }
-
- return false;
-}
-
-// Static state for MISSION UPLOAD transaction (starting with MISSION_COUNT)
-#define MAVLINK_MISSION_UPLOAD_TIMEOUT_MS 10000
-static int incomingMissionWpCount = 0;
-static int incomingMissionWpSequence = 0;
-static uint8_t incomingMissionSourceSystem = 0;
-static uint8_t incomingMissionSourceComponent = 0;
-static timeMs_t incomingMissionLastActivityMs = 0;
-
-static void mavlinkResetIncomingMissionTransaction(void)
-{
- incomingMissionWpCount = 0;
- incomingMissionWpSequence = 0;
- incomingMissionSourceSystem = 0;
- incomingMissionSourceComponent = 0;
- incomingMissionLastActivityMs = 0;
-}
-
-static void mavlinkStartIncomingMissionTransaction(int missionCount)
-{
- incomingMissionWpCount = missionCount;
- incomingMissionWpSequence = 0;
- incomingMissionSourceSystem = mavRecvMsg.sysid;
- incomingMissionSourceComponent = mavRecvMsg.compid;
- incomingMissionLastActivityMs = millis();
-}
-
-static void mavlinkTouchIncomingMissionTransaction(void)
-{
- incomingMissionLastActivityMs = millis();
-}
-
-static bool mavlinkIsIncomingMissionTransactionActive(void)
-{
- if (incomingMissionWpCount <= 0) {
- return false;
- }
-
- if ((timeMs_t)(millis() - incomingMissionLastActivityMs) > MAVLINK_MISSION_UPLOAD_TIMEOUT_MS) {
- mavlinkResetIncomingMissionTransaction();
- return false;
- }
-
- return true;
-}
-
-static bool mavlinkIsIncomingMissionTransactionOwner(void)
-{
- return mavRecvMsg.sysid == incomingMissionSourceSystem &&
- mavRecvMsg.compid == incomingMissionSourceComponent;
-}
-
-static bool mavlinkHandleMissionItemCommon(bool useIntMessages, uint8_t frame, uint16_t command, uint8_t autocontinue, uint16_t seq, float param1, float param2, float param3, float param4, int32_t lat, int32_t lon, float altMeters)
-{
- if (!mavlinkIsIncomingMissionTransactionActive() || !mavlinkIsIncomingMissionTransactionOwner()) {
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, MAV_MISSION_INVALID_SEQUENCE, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
- return true;
- }
-
- mavlinkTouchIncomingMissionTransaction();
-
- const bool lastMissionItem = incomingMissionWpCount > 0 && ((int)seq + 1 >= incomingMissionWpCount);
-
- if (autocontinue == 0 && !lastMissionItem) {
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, MAV_MISSION_UNSUPPORTED, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
- return true;
- }
-
- UNUSED(param3);
-
- navWaypoint_t wp;
- memset(&wp, 0, sizeof(wp));
-
- switch (command) {
- case MAV_CMD_NAV_WAYPOINT:
- if (!mavlinkFrameIsSupported(frame,
- MAV_FRAME_SUPPORTED_GLOBAL |
- MAV_FRAME_SUPPORTED_GLOBAL_INT |
- MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT |
- MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT_INT)) {
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, MAV_MISSION_UNSUPPORTED_FRAME, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
- return true;
- }
- wp.action = NAV_WP_ACTION_WAYPOINT;
- wp.lat = lat;
- wp.lon = lon;
- wp.alt = (int32_t)(altMeters * 100.0f);
- wp.p1 = 0;
- wp.p2 = 0;
- wp.p3 = mavlinkFrameUsesAbsoluteAltitude(frame) ? NAV_WP_ALTMODE : 0;
- break;
-
- case MAV_CMD_NAV_LOITER_TIME:
- if (!mavlinkFrameIsSupported(frame,
- MAV_FRAME_SUPPORTED_GLOBAL |
- MAV_FRAME_SUPPORTED_GLOBAL_INT |
- MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT |
- MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT_INT)) {
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, MAV_MISSION_UNSUPPORTED_FRAME, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
- return true;
- }
- wp.action = NAV_WP_ACTION_HOLD_TIME;
- wp.lat = lat;
- wp.lon = lon;
- wp.alt = (int32_t)(altMeters * 100.0f);
- wp.p1 = (int16_t)lrintf(param1);
- wp.p2 = 0;
- wp.p3 = mavlinkFrameUsesAbsoluteAltitude(frame) ? NAV_WP_ALTMODE : 0;
- break;
-
- case MAV_CMD_NAV_RETURN_TO_LAUNCH:
- {
- const bool coordinateFrame = mavlinkFrameIsSupported(frame,
- MAV_FRAME_SUPPORTED_GLOBAL |
- MAV_FRAME_SUPPORTED_GLOBAL_INT |
- MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT |
- MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT_INT);
-
- if (!coordinateFrame && frame != MAV_FRAME_MISSION) {
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, MAV_MISSION_UNSUPPORTED_FRAME, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
- return true;
- }
- wp.action = NAV_WP_ACTION_RTH;
- wp.lat = 0;
- wp.lon = 0;
- wp.alt = coordinateFrame ? (int32_t)(altMeters * 100.0f) : 0;
- wp.p1 = 0; // Land if non-zero
- wp.p2 = 0;
- wp.p3 = mavlinkFrameUsesAbsoluteAltitude(frame) ? NAV_WP_ALTMODE : 0;
- break;
- }
-
- case MAV_CMD_NAV_LAND:
- if (!mavlinkFrameIsSupported(frame,
- MAV_FRAME_SUPPORTED_GLOBAL |
- MAV_FRAME_SUPPORTED_GLOBAL_INT |
- MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT |
- MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT_INT)) {
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, MAV_MISSION_UNSUPPORTED_FRAME, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
- return true;
- }
- wp.action = NAV_WP_ACTION_LAND;
- wp.lat = lat;
- wp.lon = lon;
- wp.alt = (int32_t)(altMeters * 100.0f);
- wp.p1 = 0; // Speed (cm/s)
- wp.p2 = 0; // Elevation Adjustment (m): P2 defines the ground elevation (in metres) for the LAND WP. If the altitude mode is absolute, this is also absolute; for relative altitude, then it is the difference between the assumed home location and the LAND WP.
- wp.p3 = mavlinkFrameUsesAbsoluteAltitude(frame) ? NAV_WP_ALTMODE : 0; // Altitude Mode & Actions, P3 defines the altitude mode. 0 (default, legacy) = Relative to Home, 1 = Absolute (AMSL).
- break;
-
- case MAV_CMD_DO_JUMP:
- if (frame != MAV_FRAME_MISSION) {
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, MAV_MISSION_UNSUPPORTED_FRAME, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
- return true;
- }
- if (param1 < 0.0f) {
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, MAV_MISSION_UNSUPPORTED, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
- return true;
- }
- wp.lat = 0;
- wp.lon = 0;
- wp.alt = 0;
- wp.action = NAV_WP_ACTION_JUMP;
- wp.p1 = (int16_t)lrintf(param1 + 1.0f);
- wp.p2 = (int16_t)lrintf(param2);
- wp.p3 = 0;
- break;
-
- case MAV_CMD_DO_SET_ROI:
- if (param1 != MAV_ROI_LOCATION ||
- !mavlinkFrameIsSupported(frame,
- MAV_FRAME_SUPPORTED_GLOBAL |
- MAV_FRAME_SUPPORTED_GLOBAL_INT |
- MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT |
- MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT_INT)) {
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, MAV_MISSION_UNSUPPORTED, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
- return true;
- }
- wp.action = NAV_WP_ACTION_SET_POI;
- wp.lat = lat;
- wp.lon = lon;
- wp.alt = (int32_t)(altMeters * 100.0f);
- wp.p1 = 0;
- wp.p2 = 0;
- wp.p3 = mavlinkFrameUsesAbsoluteAltitude(frame) ? NAV_WP_ALTMODE : 0;
- break;
-
- case MAV_CMD_CONDITION_YAW:
- if (frame != MAV_FRAME_MISSION) {
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, MAV_MISSION_UNSUPPORTED_FRAME, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
- return true;
- }
- if (param4 != 0.0f) {
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, MAV_MISSION_UNSUPPORTED, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
- return true;
- }
- wp.lat = 0;
- wp.lon = 0;
- wp.alt = 0;
- wp.action = NAV_WP_ACTION_SET_HEAD;
- wp.p1 = (int16_t)lrintf(param1);
- wp.p2 = 0;
- wp.p3 = 0;
- break;
-
- default:
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, MAV_MISSION_UNSUPPORTED, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
- return true;
- }
-
- if (seq == incomingMissionWpSequence) {
- incomingMissionWpSequence++;
-
- wp.flag = (incomingMissionWpSequence >= incomingMissionWpCount) ? NAV_WP_FLAG_LAST : 0;
-
- setWaypoint(incomingMissionWpSequence, &wp);
-
- if (incomingMissionWpSequence >= incomingMissionWpCount) {
- if (isWaypointListValid()) {
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, MAV_MISSION_ACCEPTED, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
- }
- else {
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, MAV_MISSION_INVALID, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
- }
- mavlinkResetIncomingMissionTransaction();
- }
- else {
- if (useIntMessages) {
- mavlink_msg_mission_request_int_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, incomingMissionWpSequence, MAV_MISSION_TYPE_MISSION);
- } else {
- mavlink_msg_mission_request_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, incomingMissionWpSequence, MAV_MISSION_TYPE_MISSION);
- }
- mavlinkSendMessage();
- }
- }
- else {
- // If we get a duplicate of the last accepted item, re-request the next one instead of aborting.
- if (seq + 1 == incomingMissionWpSequence) {
- mavlinkTouchIncomingMissionTransaction();
- if (useIntMessages) {
- mavlink_msg_mission_request_int_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, incomingMissionWpSequence, MAV_MISSION_TYPE_MISSION);
- } else {
- mavlink_msg_mission_request_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, incomingMissionWpSequence, MAV_MISSION_TYPE_MISSION);
- }
- mavlinkSendMessage();
- } else {
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, MAV_MISSION_INVALID_SEQUENCE, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
- }
- }
-
- return true;
-}
-
-static bool handleIncoming_MISSION_COUNT(void)
-{
- mavlink_mission_count_t msg;
- mavlink_msg_mission_count_decode(&mavRecvMsg, &msg);
-
- // Check if this message is for us
- if (msg.target_system == mavSystemId) {
- mavlinkResetIncomingMissionTransaction();
- if (ARMING_FLAG(ARMED)) {
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, MAV_MISSION_ERROR, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
- return true;
- }
- if (msg.count == 0) {
- resetWaypointList();
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, MAV_MISSION_ACCEPTED, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
- return true;
- }
- if (msg.count <= NAV_MAX_WAYPOINTS) {
- mavlinkStartIncomingMissionTransaction(msg.count);
- mavlink_msg_mission_request_int_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, incomingMissionWpSequence, MAV_MISSION_TYPE_MISSION);
- mavlinkSendMessage();
- return true;
- } else {
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, MAV_MISSION_NO_SPACE, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
- return true;
- }
- }
-
- return false;
-}
-
-static bool handleIncoming_MISSION_ITEM(void)
-{
- mavlink_mission_item_t msg;
- mavlink_msg_mission_item_decode(&mavRecvMsg, &msg);
-
- if (msg.target_system != mavSystemId) {
- return false;
- }
-
- if (ARMING_FLAG(ARMED)) {
- if (msg.command == MAV_CMD_NAV_WAYPOINT) {
- return mavlinkHandleArmedGuidedMissionItem(msg.current, msg.frame,
- MAV_FRAME_SUPPORTED_GLOBAL | MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT,
- (int32_t)lrintf(msg.x * 1e7f), (int32_t)lrintf(msg.y * 1e7f), msg.z);
- }
-
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, MAV_MISSION_ERROR, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
- return true;
- }
-
- return mavlinkHandleMissionItemCommon(false, msg.frame, msg.command, msg.autocontinue, msg.seq, msg.param1, msg.param2, msg.param3, msg.param4, (int32_t)(msg.x * 1e7f), (int32_t)(msg.y * 1e7f), msg.z);
-}
-
-static bool handleIncoming_MISSION_REQUEST_LIST(void)
-{
- mavlink_mission_request_list_t msg;
- mavlink_msg_mission_request_list_decode(&mavRecvMsg, &msg);
-
- // Check if this message is for us
- if (msg.target_system == mavSystemId) {
- mavlink_msg_mission_count_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, getWaypointCount(), MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
- return true;
- }
-
- return false;
-}
-
-static bool fillMavlinkMissionItemFromWaypoint(const navWaypoint_t *wp, bool useIntMessages, mavlinkMissionItemData_t *item)
-{
- mavlinkMissionItemData_t data = {0};
-
- data.frame = navWaypointFrame(wp, useIntMessages);
-
- switch (wp->action) {
- case NAV_WP_ACTION_WAYPOINT:
- data.command = MAV_CMD_NAV_WAYPOINT;
- data.lat = wp->lat;
- data.lon = wp->lon;
- data.alt = wp->alt / 100.0f;
- break;
-
- case NAV_WP_ACTION_HOLD_TIME:
- data.command = MAV_CMD_NAV_LOITER_TIME;
- data.param1 = wp->p1;
- data.lat = wp->lat;
- data.lon = wp->lon;
- data.alt = wp->alt / 100.0f;
- break;
-
- case NAV_WP_ACTION_RTH:
- data.command = MAV_CMD_NAV_RETURN_TO_LAUNCH;
- break;
-
- case NAV_WP_ACTION_LAND:
- data.command = MAV_CMD_NAV_LAND;
- data.lat = wp->lat;
- data.lon = wp->lon;
- data.alt = wp->alt / 100.0f;
- break;
-
- case NAV_WP_ACTION_JUMP:
- data.command = MAV_CMD_DO_JUMP;
- data.param1 = (wp->p1 > 0) ? (float)(wp->p1 - 1) : 0.0f;
- data.param2 = wp->p2;
- break;
-
- case NAV_WP_ACTION_SET_POI:
- data.command = MAV_CMD_DO_SET_ROI;
- data.param1 = MAV_ROI_LOCATION;
- data.lat = wp->lat;
- data.lon = wp->lon;
- data.alt = wp->alt / 100.0f;
- break;
-
- case NAV_WP_ACTION_SET_HEAD:
- data.command = MAV_CMD_CONDITION_YAW;
- data.param1 = wp->p1;
- break;
-
- default:
- return false;
- }
-
- *item = data;
- return true;
-}
-
-static bool handleIncoming_MISSION_REQUEST(void)
-{
- mavlink_mission_request_t msg;
- mavlink_msg_mission_request_decode(&mavRecvMsg, &msg);
-
- if (msg.target_system != mavSystemId) {
- return false;
- }
-
- int wpCount = getWaypointCount();
-
- if (msg.seq < wpCount) {
- navWaypoint_t wp;
- getWaypoint(msg.seq + 1, &wp);
-
- mavlinkMissionItemData_t item;
- if (fillMavlinkMissionItemFromWaypoint(&wp, false, &item)) {
- mavlink_msg_mission_item_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid,
- msg.seq,
- item.frame,
- item.command,
- 0,
- 1,
- item.param1, item.param2, item.param3, item.param4,
- item.lat / 1e7f,
- item.lon / 1e7f,
- item.alt,
- MAV_MISSION_TYPE_MISSION);
- mavlinkSendMessage();
- } else {
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, MAV_MISSION_ERROR, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
- }
- }
- else {
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, MAV_MISSION_INVALID_SEQUENCE, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
- }
-
- return true;
-}
-
-static bool mavlinkIsLocalTarget(uint8_t targetSystem, uint8_t targetComponent)
-{
- if (targetSystem != 0 && targetSystem != mavSystemId) {
- return false;
- }
-
- if (targetComponent != 0 && targetComponent != mavComponentId) {
- return false;
- }
-
- return true;
-}
-
-static void mavlinkSendCommandAck(uint16_t command, MAV_RESULT result, uint8_t ackTargetSystem, uint8_t ackTargetComponent)
-{
- mavlink_msg_command_ack_pack(mavSystemId, mavComponentId, &mavSendMsg,
- command,
- result,
- 0,
- 0,
- ackTargetSystem,
- ackTargetComponent);
- mavlinkSendMessage();
-}
-
-static bool handleIncoming_COMMAND(uint8_t targetSystem, uint8_t targetComponent, uint8_t ackTargetSystem, uint8_t ackTargetComponent, uint16_t command, uint8_t frame, float param1, float param2, float param3, float param4, float latitudeDeg, float longitudeDeg, float altitudeMeters)
-{
- if (!mavlinkIsLocalTarget(targetSystem, targetComponent)) {
- return false;
- }
- UNUSED(param3);
-
- switch (command) {
- case MAV_CMD_DO_REPOSITION:
- if (!mavlinkFrameIsSupported(frame,
- MAV_FRAME_SUPPORTED_GLOBAL |
- MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT |
- MAV_FRAME_SUPPORTED_GLOBAL_INT |
- MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT_INT)) {
- mavlinkSendCommandAck(command, MAV_RESULT_UNSUPPORTED, ackTargetSystem, ackTargetComponent);
- return true;
- }
-
- if (isnan(latitudeDeg) || isnan(longitudeDeg)) {
- mavlinkSendCommandAck(command, MAV_RESULT_FAILED, ackTargetSystem, ackTargetComponent);
- return true;
- }
-
- if (isGCSValid()) {
- navWaypoint_t wp = {0};
- wp.action = NAV_WP_ACTION_WAYPOINT;
- wp.lat = (int32_t)(latitudeDeg * 1e7f);
- wp.lon = (int32_t)(longitudeDeg * 1e7f);
- wp.alt = (int32_t)(altitudeMeters * 100.0f);
- if (!isnan(param4) && param4 >= 0.0f && param4 < 360.0f) {
- wp.p1 = (int16_t)param4;
- } else {
- wp.p1 = 0;
- }
- wp.p2 = 0;
- wp.p3 = mavlinkFrameUsesAbsoluteAltitude(frame) ? NAV_WP_ALTMODE : 0;
- wp.flag = 0;
-
- setWaypoint(255, &wp);
-
- mavlinkSendCommandAck(command, MAV_RESULT_ACCEPTED, ackTargetSystem, ackTargetComponent);
- } else {
- mavlinkSendCommandAck(command, MAV_RESULT_DENIED, ackTargetSystem, ackTargetComponent);
- }
- return true;
- case MAV_CMD_DO_CHANGE_ALTITUDE:
- {
- const MAV_RESULT result = mavlinkSetAltitudeTargetFromFrame((uint8_t)lrintf(param2), param1);
- mavlinkSendCommandAck(command, result, ackTargetSystem, ackTargetComponent);
- return true;
- }
- case MAV_CMD_CONDITION_YAW:
- {
- if (!(navGetCurrentStateFlags() & NAV_CTL_YAW)) {
- mavlinkSendCommandAck(command, MAV_RESULT_DENIED, ackTargetSystem, ackTargetComponent);
- return true;
- }
-
- int32_t targetHeadingCd = wrap_36000((int32_t)lrintf(param1 * 100.0f));
-
- if (param4 != 0.0f) {
- const int32_t currentHeadingCd = STATE(AIRPLANE) ? posControl.actualState.cog : posControl.actualState.yaw;
- const int32_t headingChangeCd = (int32_t)lrintf(fabsf(param1) * 100.0f);
-
- if (param3 < 0.0f) {
- targetHeadingCd = wrap_36000(currentHeadingCd - headingChangeCd);
- } else {
- targetHeadingCd = wrap_36000(currentHeadingCd + headingChangeCd);
- }
- }
-
- updateHeadingHoldTarget(CENTIDEGREES_TO_DEGREES(targetHeadingCd));
- posControl.desiredState.yaw = targetHeadingCd;
- posControl.cruise.course = targetHeadingCd;
- posControl.cruise.previousCourse = targetHeadingCd;
-
- mavlinkSendCommandAck(command, MAV_RESULT_ACCEPTED, ackTargetSystem, ackTargetComponent);
- return true;
- }
- case MAV_CMD_SET_MESSAGE_INTERVAL:
- {
- mavlinkPeriodicMessage_e periodicMessage;
- MAV_RESULT result = MAV_RESULT_UNSUPPORTED;
-
- if (mavlinkPeriodicMessageFromMessageId((uint16_t)param1, &periodicMessage)) {
- if (param2 == 0.0f) {
- mavlinkSetMessageOverrideIntervalUs(periodicMessage, 0);
- result = MAV_RESULT_ACCEPTED;
- } else if (param2 < 0.0f) {
- mavlinkSetMessageOverrideIntervalUs(periodicMessage, -1);
- result = MAV_RESULT_ACCEPTED;
- } else {
- uint32_t intervalUs = (uint32_t)param2;
- if (intervalUs > 0) {
- const uint32_t minIntervalUs = 1000000UL / TELEMETRY_MAVLINK_MAXRATE;
- if (intervalUs < minIntervalUs) {
- intervalUs = minIntervalUs;
- }
-
- mavlinkSetMessageOverrideIntervalUs(periodicMessage, (int32_t)intervalUs);
- result = MAV_RESULT_ACCEPTED;
- }
- }
- }
-
- mavlinkSendCommandAck(command, result, ackTargetSystem, ackTargetComponent);
- return true;
- }
- case MAV_CMD_GET_MESSAGE_INTERVAL:
- {
- mavlinkPeriodicMessage_e periodicMessage;
- if (!mavlinkPeriodicMessageFromMessageId((uint16_t)param1, &periodicMessage)) {
- mavlinkSendCommandAck(command, MAV_RESULT_UNSUPPORTED, ackTargetSystem, ackTargetComponent);
- return true;
- }
-
- mavlink_msg_message_interval_pack(
- mavSystemId,
- mavComponentId,
- &mavSendMsg,
- (uint16_t)param1,
- mavlinkMessageIntervalUs(periodicMessage));
- mavlinkSendMessage();
-
- mavlinkSendCommandAck(command, MAV_RESULT_ACCEPTED, ackTargetSystem, ackTargetComponent);
- return true;
- }
- case MAV_CMD_CONTROL_HIGH_LATENCY:
- if (param1 == 0.0f || param1 == 1.0f) {
- if (mavlinkGetProtocolVersion() == 1 && param1 > 0.5f) {
- mavlinkSendCommandAck(command, MAV_RESULT_UNSUPPORTED, ackTargetSystem, ackTargetComponent);
- return true;
- }
-
- mavActivePort->highLatencyEnabled = param1 > 0.5f;
- if (mavActivePort->highLatencyEnabled) {
- mavActivePort->lastHighLatencyMessageUs = 0;
- }
- mavlinkSendCommandAck(command, MAV_RESULT_ACCEPTED, ackTargetSystem, ackTargetComponent);
- } else {
- mavlinkSendCommandAck(command, MAV_RESULT_FAILED, ackTargetSystem, ackTargetComponent);
- }
- return true;
- case MAV_CMD_REQUEST_PROTOCOL_VERSION:
- if (mavlinkGetProtocolVersion() == 1) {
- mavlinkSendCommandAck(command, MAV_RESULT_UNSUPPORTED, ackTargetSystem, ackTargetComponent);
- } else {
- mavlinkSendProtocolVersion();
- mavlinkSendCommandAck(command, MAV_RESULT_ACCEPTED, ackTargetSystem, ackTargetComponent);
- }
- return true;
- case MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES:
- if (mavlinkGetProtocolVersion() == 1) {
- mavlinkSendCommandAck(command, MAV_RESULT_UNSUPPORTED, ackTargetSystem, ackTargetComponent);
- } else {
- mavlinkSendAutopilotVersion();
- mavlinkSendCommandAck(command, MAV_RESULT_ACCEPTED, ackTargetSystem, ackTargetComponent);
- }
- return true;
- case MAV_CMD_REQUEST_MESSAGE:
- {
- bool sent = false;
- uint16_t messageId = (uint16_t)param1;
-
- switch (messageId) {
- case MAVLINK_MSG_ID_HEARTBEAT:
- mavlinkSendHeartbeat();
- sent = true;
- break;
- case MAVLINK_MSG_ID_AUTOPILOT_VERSION:
- if (mavlinkGetProtocolVersion() != 1) {
- mavlinkSendAutopilotVersion();
- sent = true;
- }
- break;
- case MAVLINK_MSG_ID_PROTOCOL_VERSION:
- if (mavlinkGetProtocolVersion() != 1) {
- mavlinkSendProtocolVersion();
- sent = true;
- }
- break;
- case MAVLINK_MSG_ID_SYS_STATUS:
- mavlinkSendSystemStatus();
- sent = true;
- break;
- case MAVLINK_MSG_ID_ATTITUDE:
- mavlinkSendAttitude();
- sent = true;
- break;
- case MAVLINK_MSG_ID_VFR_HUD:
- mavlinkSendVfrHud();
- sent = true;
- break;
- case MAVLINK_MSG_ID_AVAILABLE_MODES:
- {
- const bool isPlane = mixerConfig()->platformType == PLATFORM_AIRPLANE || STATE(FIXED_WING_LEGACY);
- const mavlinkModeSelection_t modeSelection = selectMavlinkMode(isPlane);
- if (isPlane) {
- mavlinkSendAvailableModes(planeModes, planeModesCount, modeSelection.customMode, mavlinkPlaneModeIsConfigured);
- } else {
- mavlinkSendAvailableModes(copterModes, copterModesCount, modeSelection.customMode, mavlinkCopterModeIsConfigured);
- }
- sent = true;
- }
- break;
- case MAVLINK_MSG_ID_CURRENT_MODE:
- {
- const bool isPlane = mixerConfig()->platformType == PLATFORM_AIRPLANE || STATE(FIXED_WING_LEGACY);
- const mavlinkModeSelection_t modeSelection = selectMavlinkMode(isPlane);
- mavlink_msg_current_mode_pack(
- mavSystemId,
- mavComponentId,
- &mavSendMsg,
- MAV_STANDARD_MODE_NON_STANDARD,
- modeSelection.customMode,
- modeSelection.customMode);
- mavlinkSendMessage();
- sent = true;
- }
- break;
- case MAVLINK_MSG_ID_EXTENDED_SYS_STATE:
- mavlinkSendExtendedSysState();
- sent = true;
- break;
- case MAVLINK_MSG_ID_RC_CHANNELS:
- case MAVLINK_MSG_ID_RC_CHANNELS_RAW:
- case MAVLINK_MSG_ID_RC_CHANNELS_SCALED:
- mavlinkSendRCChannelsAndRSSI();
- sent = true;
- break;
- case MAVLINK_MSG_ID_GPS_RAW_INT:
- #ifdef USE_GPS
- mavlinkSendGpsRawInt(micros());
- sent = true;
- #endif
- break;
- case MAVLINK_MSG_ID_GLOBAL_POSITION_INT:
- #ifdef USE_GPS
- mavlinkSendGlobalPositionInt(micros());
- sent = true;
- #endif
- break;
- case MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN:
- #ifdef USE_GPS
- mavlinkSendGpsGlobalOrigin();
- sent = true;
- #endif
- break;
- case MAVLINK_MSG_ID_BATTERY_STATUS:
- mavlinkSendBatteryStatus();
- sent = true;
- break;
- case MAVLINK_MSG_ID_SCALED_PRESSURE:
- mavlinkSendScaledPressure();
- sent = true;
- break;
- case MAVLINK_MSG_ID_SYSTEM_TIME:
- mavlinkSendSystemTime();
- sent = true;
- break;
- case MAVLINK_MSG_ID_STATUSTEXT:
- sent = mavlinkSendStatusText();
- break;
- case MAVLINK_MSG_ID_HOME_POSITION:
- #ifdef USE_GPS
- if (STATE(GPS_FIX_HOME)) {
- mavlinkSendHomePosition();
- sent = true;
- }
- #endif
- break;
- default:
- break;
- }
-
- mavlinkSendCommandAck(command, sent ? MAV_RESULT_ACCEPTED : MAV_RESULT_UNSUPPORTED, ackTargetSystem, ackTargetComponent);
- return true;
- }
-#ifdef USE_GPS
- case MAV_CMD_GET_HOME_POSITION:
- if (STATE(GPS_FIX_HOME)) {
- mavlinkSendHomePosition();
- mavlinkSendCommandAck(command, MAV_RESULT_ACCEPTED, ackTargetSystem, ackTargetComponent);
- } else {
- mavlinkSendCommandAck(command, MAV_RESULT_FAILED, ackTargetSystem, ackTargetComponent);
- }
- return true;
-#endif
- default:
- mavlinkSendCommandAck(command, MAV_RESULT_UNSUPPORTED, ackTargetSystem, ackTargetComponent);
- return true;
- }
-}
-
-static bool handleIncoming_COMMAND_INT(void)
-{
- mavlink_command_int_t msg;
- mavlink_msg_command_int_decode(&mavRecvMsg, &msg);
-
- return handleIncoming_COMMAND(msg.target_system, msg.target_component, mavRecvMsg.sysid, mavRecvMsg.compid, msg.command, msg.frame, msg.param1, msg.param2, msg.param3, msg.param4, (float)msg.x / 1e7f, (float)msg.y / 1e7f, msg.z);
-}
-
-static bool handleIncoming_COMMAND_LONG(void)
-{
- mavlink_command_long_t msg;
- mavlink_msg_command_long_decode(&mavRecvMsg, &msg);
-
- // COMMAND_LONG has no frame field; location commands are WGS84 global by definition.
- return handleIncoming_COMMAND(msg.target_system, msg.target_component, mavRecvMsg.sysid, mavRecvMsg.compid, msg.command, MAV_FRAME_GLOBAL, msg.param1, msg.param2, msg.param3, msg.param4, msg.param5, msg.param6, msg.param7);
-}
-
-static bool handleIncoming_MISSION_ITEM_INT(void)
-{
- mavlink_mission_item_int_t msg;
- mavlink_msg_mission_item_int_decode(&mavRecvMsg, &msg);
-
- if (msg.target_system != mavSystemId) {
- return false;
- }
-
- if (ARMING_FLAG(ARMED)) {
- if (msg.command == MAV_CMD_NAV_WAYPOINT) {
- return mavlinkHandleArmedGuidedMissionItem(msg.current, msg.frame,
- MAV_FRAME_SUPPORTED_GLOBAL_INT | MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT_INT,
- msg.x, msg.y, msg.z);
- }
-
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, MAV_MISSION_ERROR, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
- return true;
- }
-
- return mavlinkHandleMissionItemCommon(true, msg.frame, msg.command, msg.autocontinue, msg.seq, msg.param1, msg.param2, msg.param3, msg.param4, msg.x, msg.y, msg.z);
-}
-
-static bool handleIncoming_MISSION_REQUEST_INT(void)
-{
- mavlink_mission_request_int_t msg;
- mavlink_msg_mission_request_int_decode(&mavRecvMsg, &msg);
-
- if (msg.target_system != mavSystemId) {
- return false;
- }
-
- int wpCount = getWaypointCount();
-
- if (msg.seq < wpCount) {
- navWaypoint_t wp;
- getWaypoint(msg.seq + 1, &wp);
-
- mavlinkMissionItemData_t item;
- if (fillMavlinkMissionItemFromWaypoint(&wp, true, &item)) {
- mavlink_msg_mission_item_int_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid,
- msg.seq,
- item.frame,
- item.command,
- 0,
- 1,
- item.param1, item.param2, item.param3, item.param4,
- item.lat,
- item.lon,
- item.alt,
- MAV_MISSION_TYPE_MISSION);
- mavlinkSendMessage();
- } else {
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, MAV_MISSION_ERROR, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
- }
- }
- else {
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavRecvMsg.sysid, mavRecvMsg.compid, MAV_MISSION_INVALID_SEQUENCE, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
- }
-
- return true;
-}
-
-static bool handleIncoming_REQUEST_DATA_STREAM(void)
-{
- mavlink_request_data_stream_t msg;
- mavlink_msg_request_data_stream_decode(&mavRecvMsg, &msg);
-
- if (!mavlinkIsLocalTarget(msg.target_system, msg.target_component)) {
- return false;
- }
-
- uint8_t rate = 0;
- if (msg.start_stop != 0) {
- rate = (uint8_t)msg.req_message_rate;
- if (rate > TELEMETRY_MAVLINK_MAXRATE) {
- rate = TELEMETRY_MAVLINK_MAXRATE;
- }
- }
-
- if (msg.req_stream_id == MAV_DATA_STREAM_ALL) {
- mavlinkSetStreamRate(MAV_DATA_STREAM_EXTENDED_STATUS, rate);
- mavlinkSetStreamRate(MAV_DATA_STREAM_RC_CHANNELS, rate);
- mavlinkSetStreamRate(MAV_DATA_STREAM_POSITION, rate);
- mavlinkSetStreamRate(MAV_DATA_STREAM_EXTRA1, rate);
- mavlinkSetStreamRate(MAV_DATA_STREAM_EXTRA2, rate);
- mavlinkSetStreamRate(MAV_DATA_STREAM_EXTRA3, rate);
- mavlinkSetStreamRate(MAV_DATA_STREAM_EXTENDED_SYS_STATE, rate);
- return true;
- }
-
- mavlinkSetStreamRate(msg.req_stream_id, rate);
- return true;
-}
-
-static bool handleIncoming_SET_POSITION_TARGET_GLOBAL_INT(void)
-{
- mavlink_set_position_target_global_int_t msg;
- mavlink_msg_set_position_target_global_int_decode(&mavRecvMsg, &msg);
-
- if (!mavlinkIsLocalTarget(msg.target_system, msg.target_component)) {
- return false;
- }
-
- uint8_t frame = msg.coordinate_frame;
- if (!mavlinkFrameIsSupported(frame,
- MAV_FRAME_SUPPORTED_GLOBAL |
- MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT |
- MAV_FRAME_SUPPORTED_GLOBAL_INT |
- MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT_INT)) {
- return true;
- }
-
- const uint16_t typeMask = msg.type_mask;
- const bool xIgnored = (typeMask & POSITION_TARGET_TYPEMASK_X_IGNORE) != 0;
- const bool yIgnored = (typeMask & POSITION_TARGET_TYPEMASK_Y_IGNORE) != 0;
- const bool zIgnored = (typeMask & POSITION_TARGET_TYPEMASK_Z_IGNORE) != 0;
-
- // Altitude-only SET_POSITION_TARGET_GLOBAL_INT mirrors MAV_CMD_DO_CHANGE_ALTITUDE semantics.
- if (xIgnored && yIgnored && !zIgnored) {
- if (isGCSValid()) {
- mavlinkSetAltitudeTargetFromFrame(frame, msg.alt);
- }
- return true;
- }
-
- if (xIgnored || yIgnored) {
- return true;
- }
-
- if (isGCSValid()) {
- navWaypoint_t wp = {0};
- wp.action = NAV_WP_ACTION_WAYPOINT;
- wp.lat = msg.lat_int;
- wp.lon = msg.lon_int;
- wp.alt = zIgnored ? 0 : (int32_t)(msg.alt * 100.0f);
- wp.p1 = 0;
- wp.p2 = 0;
- wp.p3 = mavlinkFrameUsesAbsoluteAltitude(frame) ? NAV_WP_ALTMODE : 0;
- wp.flag = 0;
-
- setWaypoint(255, &wp);
- }
-
- return true;
-}
-
-static bool handleIncoming_SET_POSITION_TARGET_LOCAL_NED(void)
-{
- mavlink_set_position_target_local_ned_t msg;
- mavlink_msg_set_position_target_local_ned_decode(&mavRecvMsg, &msg);
-
- if (!mavlinkIsLocalTarget(msg.target_system, msg.target_component)) {
- return false;
- }
-
- if (msg.coordinate_frame != MAV_FRAME_LOCAL_OFFSET_NED) {
- return true;
- }
-
- const uint16_t typeMask = msg.type_mask;
- const bool xIgnored = (typeMask & POSITION_TARGET_TYPEMASK_X_IGNORE) != 0;
- const bool yIgnored = (typeMask & POSITION_TARGET_TYPEMASK_Y_IGNORE) != 0;
- const bool zIgnored = (typeMask & POSITION_TARGET_TYPEMASK_Z_IGNORE) != 0;
-
- if (!isGCSValid() || zIgnored) {
- return true;
- }
-
- if ((!xIgnored && fabsf(msg.x) > 0.01f) || (!yIgnored && fabsf(msg.y) > 0.01f)) {
- return true;
- }
-
- const int32_t targetAltitudeCm = (int32_t)lrintf((float)getEstimatedActualPosition(Z) - (msg.z * 100.0f));
- navigationSetAltitudeTargetWithDatum(NAV_WP_TAKEOFF_DATUM, targetAltitudeCm);
-
- return true;
-}
-
-
-static bool handleIncoming_RC_CHANNELS_OVERRIDE(void) {
- mavlink_rc_channels_override_t msg;
- mavlink_msg_rc_channels_override_decode(&mavRecvMsg, &msg);
- mavlinkRxHandleMessage(&msg);
- return true;
-}
-
-static bool handleIncoming_PARAM_REQUEST_LIST(void) {
- mavlink_param_request_list_t msg;
- mavlink_msg_param_request_list_decode(&mavRecvMsg, &msg);
-
- // Respond that we don't have any parameters to force Mission Planner to give up quickly
- if (mavlinkIsLocalTarget(msg.target_system, msg.target_component)) {
- // mavlink_msg_param_value_pack(system_id, component_id, msg, param_value->param_id, param_value->param_value, param_value->param_type, param_value->param_count, param_value->param_index);
- mavlink_msg_param_value_pack(mavSystemId, mavComponentId, &mavSendMsg, 0, 0, 0, 0, 0);
- mavlinkSendMessage();
- }
- return true;
-}
-
-static void mavlinkParseRxStats(const mavlink_radio_status_t *msg) {
- switch(mavActiveConfig->radio_type) {
- case MAVLINK_RADIO_NONE:
- break;
- case MAVLINK_RADIO_SIK:
- // rssi scaling info from: https://ardupilot.org/rover/docs/common-3dr-radio-advanced-configuration-and-technical-information.html
- rxLinkStatistics.uplinkRSSI = (msg->rssi / 1.9) - 127;
- rxLinkStatistics.uplinkSNR = msg->noise / 1.9;
- rxLinkStatistics.uplinkLQ = msg->rssi != 255 ? scaleRange(msg->rssi, 0, 254, 0, 100) : 0;
- break;
- case MAVLINK_RADIO_ELRS:
- rxLinkStatistics.uplinkRSSI = -msg->remrssi;
- rxLinkStatistics.uplinkSNR = msg->noise;
- rxLinkStatistics.uplinkLQ = scaleRange(msg->rssi, 0, 255, 0, 100);
- break;
- case MAVLINK_RADIO_GENERIC:
- default:
- rxLinkStatistics.uplinkRSSI = msg->rssi;
- rxLinkStatistics.uplinkSNR = msg->noise;
- rxLinkStatistics.uplinkLQ = msg->rssi != 255 ? scaleRange(msg->rssi, 0, 254, 0, 100) : 0;
- break;
- }
-}
-
-static bool handleIncoming_RADIO_STATUS(void) {
- mavlink_radio_status_t msg;
- mavlink_msg_radio_status_decode(&mavRecvMsg, &msg);
- if (msg.txbuf > 0) {
- mavActivePort->txbuffValid = true;
- mavActivePort->txbuffFree = msg.txbuf;
- } else {
- mavActivePort->txbuffValid = false;
- mavActivePort->txbuffFree = 100;
- }
-
- if (rxConfig()->receiverType == RX_TYPE_SERIAL &&
- rxConfig()->serialrx_provider == SERIALRX_MAVLINK) {
- mavlinkParseRxStats(&msg);
- }
-
- return true;
-}
-
-static bool handleIncoming_HEARTBEAT(void) {
- mavlink_heartbeat_t msg;
- mavlink_msg_heartbeat_decode(&mavRecvMsg, &msg);
-
- switch (msg.type) {
-#ifdef USE_ADSB
- case MAV_TYPE_ADSB:
- return adsbHeartbeat();
-#endif
- default:
- break;
- }
-
- return false;
-}
-
-#ifdef USE_ADSB
-static bool handleIncoming_ADSB_VEHICLE(void) {
- mavlink_adsb_vehicle_t msg;
- mavlink_msg_adsb_vehicle_decode(&mavRecvMsg, &msg);
-
- adsbVehicleValues_t* vehicle = getVehicleForFill();
- if(vehicle != NULL){
- vehicle->icao = msg.ICAO_address;
- vehicle->gps.lat = msg.lat;
- vehicle->gps.lon = msg.lon;
- vehicle->alt = (int32_t)(msg.altitude / 10);
- vehicle->horVelocity = msg.hor_velocity;
- vehicle->heading = msg.heading;
- vehicle->flags = msg.flags;
- vehicle->altitudeType = msg.altitude_type;
- memcpy(&(vehicle->callsign), msg.callsign, sizeof(vehicle->callsign));
- vehicle->emitterType = msg.emitter_type;
- vehicle->tslc = msg.tslc;
-
- adsbNewVehicle(vehicle);
- }
-
- return true;
-}
-#endif
-
-static bool mavlinkIsFromLocalIdentity(uint8_t sysid, uint8_t compid)
-{
- return sysid == mavlinkGetCommonConfig()->sysid && compid == MAV_COMP_ID_AUTOPILOT1;
-}
-
-static void mavlinkLearnRoute(uint8_t ingressPortIndex)
-{
- if (mavRecvMsg.sysid == 0 || mavlinkIsFromLocalIdentity(mavRecvMsg.sysid, mavRecvMsg.compid)) {
- return;
- }
-
- for (uint8_t routeIndex = 0; routeIndex < mavRouteCount; routeIndex++) {
- mavlinkRouteEntry_t *route = &mavRouteTable[routeIndex];
- if (route->sysid == mavRecvMsg.sysid && route->compid == mavRecvMsg.compid) {
- route->ingressPortIndex = ingressPortIndex;
- return;
- }
- }
-
- if (mavRouteCount >= MAVLINK_MAX_ROUTES) {
- return;
- }
-
- mavRouteTable[mavRouteCount].sysid = mavRecvMsg.sysid;
- mavRouteTable[mavRouteCount].compid = mavRecvMsg.compid;
- mavRouteTable[mavRouteCount].ingressPortIndex = ingressPortIndex;
- mavRouteCount++;
-}
-
-static void mavlinkExtractTargets(const mavlink_message_t *msg, int16_t *targetSystem, int16_t *targetComponent)
-{
- *targetSystem = -1;
- *targetComponent = -1;
-
- const mavlink_msg_entry_t *msgEntry = mavlink_get_msg_entry(msg->msgid);
- if (!msgEntry) {
- return;
- }
-
- if (msgEntry->flags & MAV_MSG_ENTRY_FLAG_HAVE_TARGET_SYSTEM) {
- *targetSystem = _MAV_RETURN_uint8_t(msg, msgEntry->target_system_ofs);
- }
-
- if (msgEntry->flags & MAV_MSG_ENTRY_FLAG_HAVE_TARGET_COMPONENT) {
- *targetComponent = _MAV_RETURN_uint8_t(msg, msgEntry->target_component_ofs);
- }
-}
-
-static uint8_t mavlinkComputeForwardMask(uint8_t ingressPortIndex, int16_t targetSystem, int16_t targetComponent)
-{
- uint8_t mask = 0;
-
- if (targetSystem <= 0) {
- for (uint8_t portIndex = 0; portIndex < mavPortCount; portIndex++) {
- if (portIndex == ingressPortIndex) {
- continue;
- }
-
- const mavlinkPortRuntime_t *state = &mavPortStates[portIndex];
- if (!state->telemetryEnabled || !state->port) {
- continue;
- }
-
- mask |= MAVLINK_PORT_MASK(portIndex);
- }
- return mask;
- }
-
- for (uint8_t routeIndex = 0; routeIndex < mavRouteCount; routeIndex++) {
- const mavlinkRouteEntry_t *route = &mavRouteTable[routeIndex];
-
- if (route->sysid != targetSystem) {
- continue;
- }
- if (targetComponent > 0 && route->compid != targetComponent) {
- continue;
- }
- if (route->ingressPortIndex == ingressPortIndex || route->ingressPortIndex >= mavPortCount) {
- continue;
- }
-
- const mavlinkPortRuntime_t *state = &mavPortStates[route->ingressPortIndex];
- if (!state->telemetryEnabled || !state->port) {
- continue;
- }
-
- mask |= MAVLINK_PORT_MASK(route->ingressPortIndex);
- }
-
- return mask;
-}
-
-static void mavlinkForwardMessage(uint8_t ingressPortIndex, int16_t targetSystem, int16_t targetComponent)
-{
- if (mavRecvMsg.msgid == MAVLINK_MSG_ID_RADIO_STATUS) {
- return;
- }
-
- uint8_t mavBuffer[MAVLINK_MAX_PACKET_LEN];
- const int msgLength = mavlink_msg_to_send_buffer(mavBuffer, &mavRecvMsg);
- if (msgLength <= 0) {
- return;
- }
-
- const uint8_t forwardMask = mavlinkComputeForwardMask(ingressPortIndex, targetSystem, targetComponent);
- for (uint8_t portIndex = 0; portIndex < mavPortCount; portIndex++) {
- if ((forwardMask & MAVLINK_PORT_MASK(portIndex)) == 0) {
- continue;
- }
-
- mavlinkPortRuntime_t *state = &mavPortStates[portIndex];
- if (serialTxBytesFree(state->port) < (uint32_t)msgLength) {
- state->txDroppedFrames++;
- continue;
- }
-
- serialBeginWrite(state->port);
- serialWriteBuf(state->port, mavBuffer, msgLength);
- serialEndWrite(state->port);
- }
-}
-
-static int8_t mavlinkResolveLocalPortForTarget(int16_t targetSystem, int16_t targetComponent, uint8_t ingressPortIndex)
-{
- if (targetSystem <= 0) {
- return ingressPortIndex;
- }
-
- if ((uint8_t)targetSystem != mavlinkGetCommonConfig()->sysid) {
- return -1;
- }
-
- if (targetComponent > 0 && (uint8_t)targetComponent != MAV_COMP_ID_AUTOPILOT1) {
- return -1;
- }
-
- if (ingressPortIndex < mavPortCount) {
- return ingressPortIndex;
- }
-
- return mavPortCount > 0 ? 0 : -1;
-}
-
-static bool mavlinkShouldFanOutLocalBroadcast(const mavlink_message_t *msg)
-{
- if (msg->msgid == MAVLINK_MSG_ID_REQUEST_DATA_STREAM) {
- return true;
- }
-
- if (msg->msgid == MAVLINK_MSG_ID_COMMAND_LONG) {
- mavlink_command_long_t cmd;
- mavlink_msg_command_long_decode(msg, &cmd);
- return cmd.command == MAV_CMD_SET_MESSAGE_INTERVAL || cmd.command == MAV_CMD_CONTROL_HIGH_LATENCY;
- }
-
- if (msg->msgid == MAVLINK_MSG_ID_COMMAND_INT) {
- mavlink_command_int_t cmd;
- mavlink_msg_command_int_decode(msg, &cmd);
- return cmd.command == MAV_CMD_SET_MESSAGE_INTERVAL || cmd.command == MAV_CMD_CONTROL_HIGH_LATENCY;
- }
-
- return false;
-}
-
-// Returns whether a message was processed
-static bool processMAVLinkIncomingTelemetry(uint8_t ingressPortIndex)
-{
- mavlinkPortRuntime_t *state = &mavPortStates[ingressPortIndex];
-
- while (serialRxBytesWaiting(state->port) > 0) {
- // Limit handling to one message per cycle
- const char c = serialRead(state->port);
- const uint8_t result = mavlink_parse_char(ingressPortIndex, c, &state->mavRecvMsg, &state->mavRecvStatus);
- if (result == MAVLINK_FRAMING_OK) {
- mavRecvMsg = state->mavRecvMsg;
-
- if (mavlinkIsFromLocalIdentity(mavRecvMsg.sysid, mavRecvMsg.compid)) {
- return false;
- }
-
- mavlinkLearnRoute(ingressPortIndex);
-
- int16_t targetSystem;
- int16_t targetComponent;
- mavlinkExtractTargets(&mavRecvMsg, &targetSystem, &targetComponent);
- mavlinkForwardMessage(ingressPortIndex, targetSystem, targetComponent);
-
- if (mavRecvMsg.msgid == MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE) {
- mavlinkSetActivePortContext(ingressPortIndex);
- mavSendMask = MAVLINK_PORT_MASK(ingressPortIndex);
- handleIncoming_RC_CHANNELS_OVERRIDE();
- return false;
- }
-
- const int8_t localPortIndex = mavlinkResolveLocalPortForTarget(targetSystem, targetComponent, ingressPortIndex);
- if (localPortIndex < 0) {
- return false;
- }
-
- uint8_t localPortMask = MAVLINK_PORT_MASK((uint8_t)localPortIndex);
- const bool isLocalOrSystemBroadcast = targetSystem == 0 || ((targetSystem > 0) && ((uint8_t)targetSystem == mavlinkGetCommonConfig()->sysid));
- if (targetComponent == 0 && isLocalOrSystemBroadcast && mavlinkShouldFanOutLocalBroadcast(&mavRecvMsg)) {
- localPortMask = 0;
- for (uint8_t portIndex = 0; portIndex < mavPortCount; portIndex++) {
- localPortMask |= MAVLINK_PORT_MASK(portIndex);
- }
- }
-
- bool handled = false;
- for (uint8_t localIndex = 0; localIndex < mavPortCount; localIndex++) {
- if (!(localPortMask & MAVLINK_PORT_MASK(localIndex))) {
- continue;
- }
-
- mavlinkSetActivePortContext(localIndex);
- mavSendMask = MAVLINK_PORT_MASK(ingressPortIndex);
- bool localHandled = false;
-
- switch (mavRecvMsg.msgid) {
- case MAVLINK_MSG_ID_HEARTBEAT:
- localHandled = handleIncoming_HEARTBEAT();
- break;
- case MAVLINK_MSG_ID_PARAM_REQUEST_LIST:
- localHandled = handleIncoming_PARAM_REQUEST_LIST();
- break;
- case MAVLINK_MSG_ID_MISSION_CLEAR_ALL:
- localHandled = handleIncoming_MISSION_CLEAR_ALL();
- break;
- case MAVLINK_MSG_ID_MISSION_COUNT:
- localHandled = handleIncoming_MISSION_COUNT();
- break;
- case MAVLINK_MSG_ID_MISSION_ITEM:
- localHandled = handleIncoming_MISSION_ITEM();
- break;
- case MAVLINK_MSG_ID_MISSION_ITEM_INT:
- localHandled = handleIncoming_MISSION_ITEM_INT();
- break;
- case MAVLINK_MSG_ID_MISSION_REQUEST_LIST:
- localHandled = handleIncoming_MISSION_REQUEST_LIST();
- break;
- case MAVLINK_MSG_ID_COMMAND_LONG:
- localHandled = handleIncoming_COMMAND_LONG();
- break;
- case MAVLINK_MSG_ID_COMMAND_INT: //7 parameters: parameters 1-4, 7 are floats, and parameters 5,6 are scaled integers
- localHandled = handleIncoming_COMMAND_INT();
- break;
- case MAVLINK_MSG_ID_MISSION_REQUEST:
- localHandled = handleIncoming_MISSION_REQUEST();
- break;
- case MAVLINK_MSG_ID_MISSION_REQUEST_INT:
- localHandled = handleIncoming_MISSION_REQUEST_INT();
- break;
- case MAVLINK_MSG_ID_REQUEST_DATA_STREAM:
- localHandled = handleIncoming_REQUEST_DATA_STREAM();
- break;
- case MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE:
- handleIncoming_RC_CHANNELS_OVERRIDE();
- // Don't set that we handled a message, otherwise RC channel packets will block telemetry messages
- localHandled = false;
- break;
- case MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED:
- localHandled = handleIncoming_SET_POSITION_TARGET_LOCAL_NED();
- break;
- case MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT:
- localHandled = handleIncoming_SET_POSITION_TARGET_GLOBAL_INT();
- break;
-#ifdef USE_ADSB
- case MAVLINK_MSG_ID_ADSB_VEHICLE:
- localHandled = handleIncoming_ADSB_VEHICLE();
- break;
-#endif
- case MAVLINK_MSG_ID_RADIO_STATUS:
- handleIncoming_RADIO_STATUS();
- // Don't set that we handled a message, otherwise radio status packets will block telemetry messages.
- localHandled = false;
- break;
- case MAVLINK_MSG_ID_TUNNEL:
- localHandled = handleIncoming_TUNNEL(ingressPortIndex);
- break;
- default:
- localHandled = false;
- break;
- }
-
- handled = handled || localHandled;
- }
-
- return handled;
- }
- }
-
- return false;
-}
-
-static bool isMAVLinkTelemetryHalfDuplex(void) {
- return telemetryConfig()->halfDuplex ||
- (rxConfig()->receiverType == RX_TYPE_SERIAL && rxConfig()->serialrx_provider == SERIALRX_MAVLINK && tristateWithDefaultOffIsActive(rxConfig()->halfDuplex));
-}
-
-void handleMAVLinkTelemetry(timeUs_t currentTimeUs)
-{
- for (uint8_t portIndex = 0; portIndex < mavPortCount; portIndex++) {
- mavlinkPortRuntime_t *state = &mavPortStates[portIndex];
- if (!state->telemetryEnabled || !state->port) {
- continue;
- }
-
- mavlinkSetActivePortContext(portIndex);
-
- // Process incoming MAVLink on this port and forward when needed.
- const bool receivedMessage = processMAVLinkIncomingTelemetry(portIndex);
-
- // Restore context back to this port before periodic send decisions.
- mavlinkSetActivePortContext(portIndex);
- bool shouldSendTelemetry = false;
-
- if (state->txbuffValid) {
- // Use flow control if available.
- shouldSendTelemetry = state->txbuffFree >= mavActiveConfig->min_txbuff;
- } else {
- // If not, use blind frame pacing and half-duplex backoff after RX activity.
- const bool halfDuplexBackoff = isMAVLinkTelemetryHalfDuplex() && receivedMessage;
- shouldSendTelemetry = ((currentTimeUs - state->lastMavlinkMessageUs) >= TELEMETRY_MAVLINK_DELAY) && !halfDuplexBackoff;
- }
-
- if (!shouldSendTelemetry) {
- continue;
- }
-
- mavSendMask = MAVLINK_PORT_MASK(portIndex);
- processMAVLinkTelemetry(currentTimeUs);
- state->lastMavlinkMessageUs = currentTimeUs;
- }
-
- mavSendMask = 0;
+ mavlinkRuntimeFreePorts();
}
#endif
diff --git a/src/test/unit/CMakeLists.txt b/src/test/unit/CMakeLists.txt
index 7debcc97758..04527fd7046 100644
--- a/src/test/unit/CMakeLists.txt
+++ b/src/test/unit/CMakeLists.txt
@@ -44,7 +44,8 @@ set_property(SOURCE gimbal_serial_unittest.cc PROPERTY depends "io/gimbal_serial
set_property(SOURCE gimbal_serial_unittest.cc PROPERTY definitions USE_SERIAL_GIMBAL GIMBAL_UNIT_TEST USE_HEADTRACKER)
set_property(SOURCE mavlink_unittest.cc PROPERTY depends
- "telemetry/mavlink.c" "common/crc.c" "common/maths.c" "common/streambuf.c" "msp/msp_serial.c")
+ "fc/fc_mavlink.c" "mavlink/mavlink_ports.c" "mavlink/mavlink_routing.c" "mavlink/mavlink_runtime.c"
+ "mavlink/mavlink_streams.c" "telemetry/mavlink.c" "common/crc.c" "common/maths.c" "common/streambuf.c" "msp/msp_serial.c")
set_property(SOURCE mavlink_unittest.cc PROPERTY definitions USE_TELEMETRY USE_TELEMETRY_MAVLINK)
set_property(SOURCE mavlink_unittest.cc PROPERTY includes
"${CMAKE_CURRENT_SOURCE_DIR}/../../../lib/main/MAVLink")
diff --git a/src/test/unit/mavlink_unittest.cc b/src/test/unit/mavlink_unittest.cc
index 7b579dcfa9f..749f10afcfd 100644
--- a/src/test/unit/mavlink_unittest.cc
+++ b/src/test/unit/mavlink_unittest.cc
@@ -295,6 +295,8 @@ static void initMavlinkTestState(void)
lastAltitudeTargetCm = 0;
testFlightMode = FLM_MANUAL;
testSensorsMask = 0;
+ armingFlags = 0;
+ stateFlags = 0;
memset(&gpsSol, 0, sizeof(gpsSol));
memset(&GPS_home, 0, sizeof(GPS_home));
memset(waypointStore, 0, sizeof(waypointStore));
From ed1628324beaa967945a8742fa758289c7348e66 Mon Sep 17 00:00:00 2001
From: frogmane <7685285+xznhj8129@users.noreply.github.com>
Date: Fri, 3 Apr 2026 17:51:08 -0400
Subject: [PATCH 35/46] Rename MAVLink shared types header
---
src/main/CMakeLists.txt | 1 +
src/main/fc/fc_mavlink.h | 2 +-
src/main/mavlink/mavlink_internal.h | 2 +-
src/main/mavlink/mavlink_routing.h | 2 +-
src/main/mavlink/mavlink_streams.h | 2 +-
src/main/mavlink/mavlink_types.h | 189 ++++++++++++++++++++++++++++
src/main/telemetry/mavlink.h | 171 +------------------------
src/test/unit/mavlink_unittest.cc | 1 +
8 files changed, 197 insertions(+), 173 deletions(-)
create mode 100644 src/main/mavlink/mavlink_types.h
diff --git a/src/main/CMakeLists.txt b/src/main/CMakeLists.txt
index 26ca5b952c6..4fff0f3bf35 100755
--- a/src/main/CMakeLists.txt
+++ b/src/main/CMakeLists.txt
@@ -394,6 +394,7 @@ main_sources(COMMON_SRC
io/osd/custom_elements.c
mavlink/mavlink_internal.h
+ mavlink/mavlink_types.h
mavlink/mavlink_ports.c
mavlink/mavlink_ports.h
mavlink/mavlink_routing.c
diff --git a/src/main/fc/fc_mavlink.h b/src/main/fc/fc_mavlink.h
index 29be4363157..c945ba1ba14 100644
--- a/src/main/fc/fc_mavlink.h
+++ b/src/main/fc/fc_mavlink.h
@@ -2,7 +2,7 @@
#include "common/time.h"
-#include "telemetry/mavlink.h"
+#include "mavlink/mavlink_types.h"
typedef enum {
MAVLINK_FC_DISPATCH_NOT_HANDLED = 0,
diff --git a/src/main/mavlink/mavlink_internal.h b/src/main/mavlink/mavlink_internal.h
index 4c365f364db..ecc9b54998f 100644
--- a/src/main/mavlink/mavlink_internal.h
+++ b/src/main/mavlink/mavlink_internal.h
@@ -67,7 +67,7 @@
#include "sensors/temperature.h"
#include "sensors/esc_sensor.h"
-#include "telemetry/mavlink.h"
+#include "mavlink/mavlink_types.h"
#include "telemetry/telemetry.h"
#include "blackbox/blackbox_io.h"
diff --git a/src/main/mavlink/mavlink_routing.h b/src/main/mavlink/mavlink_routing.h
index 1aa472e0f8c..ae63f372416 100644
--- a/src/main/mavlink/mavlink_routing.h
+++ b/src/main/mavlink/mavlink_routing.h
@@ -3,7 +3,7 @@
#include
#include
-#include "telemetry/mavlink.h"
+#include "mavlink/mavlink_types.h"
bool mavlinkIsFromLocalIdentity(uint8_t sysid, uint8_t compid);
void mavlinkLearnRoute(uint8_t ingressPortIndex);
diff --git a/src/main/mavlink/mavlink_streams.h b/src/main/mavlink/mavlink_streams.h
index 2084518a546..e3ffc467ef5 100644
--- a/src/main/mavlink/mavlink_streams.h
+++ b/src/main/mavlink/mavlink_streams.h
@@ -2,7 +2,7 @@
#include "common/time.h"
-#include "telemetry/mavlink.h"
+#include "mavlink/mavlink_types.h"
extern const uint8_t mavSecondaryRates[MAVLINK_STREAM_COUNT];
diff --git a/src/main/mavlink/mavlink_types.h b/src/main/mavlink/mavlink_types.h
new file mode 100644
index 00000000000..09f21dc99ed
--- /dev/null
+++ b/src/main/mavlink/mavlink_types.h
@@ -0,0 +1,189 @@
+/*
+ * This file is part of Cleanflight.
+ *
+ * Cleanflight is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * Cleanflight is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with Cleanflight. If not, see .
+ */
+
+#pragma once
+
+#include "common/time.h"
+
+#include "io/serial.h"
+
+#include "target/common.h"
+
+#pragma GCC diagnostic push
+#pragma GCC diagnostic ignored "-Wunused-function"
+#ifndef MAVLINK_COMM_NUM_BUFFERS
+#define MAVLINK_COMM_NUM_BUFFERS MAX_MAVLINK_PORTS
+#endif
+#include "common/mavlink.h"
+#pragma GCC diagnostic pop
+
+#define TELEMETRY_MAVLINK_PORT_MODE MODE_RXTX
+#define TELEMETRY_MAVLINK_MAXRATE 50
+#define TELEMETRY_MAVLINK_DELAY ((1000 * 1000) / TELEMETRY_MAVLINK_MAXRATE)
+#define TELEMETRY_MAVLINK_HIGH_LATENCY_INTERVAL_US (5 * 1000 * 1000)
+#define MAV_DATA_STREAM_EXTENDED_SYS_STATE (MAV_DATA_STREAM_EXTRA3 + 1)
+#define MAV_DATA_STREAM_HEARTBEAT (MAV_DATA_STREAM_EXTENDED_SYS_STATE + 1)
+#define MAVLINK_STREAM_COUNT (MAV_DATA_STREAM_HEARTBEAT + 1)
+#define ARDUPILOT_VERSION_MAJOR 4
+#define ARDUPILOT_VERSION_MINOR 6
+#define ARDUPILOT_VERSION_PATCH 3
+#define MAVLINK_MAX_ROUTES 32
+#define MAVLINK_PORT_MASK(portIndex) (1U << (portIndex))
+#define MAXSTREAMS MAVLINK_STREAM_COUNT
+
+typedef enum {
+ MAVLINK_PERIODIC_MESSAGE_HEARTBEAT,
+ MAVLINK_PERIODIC_MESSAGE_SYS_STATUS,
+ MAVLINK_PERIODIC_MESSAGE_EXTENDED_SYS_STATE,
+ MAVLINK_PERIODIC_MESSAGE_RC_CHANNELS,
+ MAVLINK_PERIODIC_MESSAGE_GPS_RAW_INT,
+ MAVLINK_PERIODIC_MESSAGE_GLOBAL_POSITION_INT,
+ MAVLINK_PERIODIC_MESSAGE_GPS_GLOBAL_ORIGIN,
+ MAVLINK_PERIODIC_MESSAGE_ATTITUDE,
+ MAVLINK_PERIODIC_MESSAGE_VFR_HUD,
+ MAVLINK_PERIODIC_MESSAGE_BATTERY_STATUS,
+ MAVLINK_PERIODIC_MESSAGE_SCALED_PRESSURE,
+ MAVLINK_PERIODIC_MESSAGE_SYSTEM_TIME,
+ MAVLINK_PERIODIC_MESSAGE_COUNT
+} mavlinkPeriodicMessage_e;
+
+typedef enum {
+ MAV_FRAME_SUPPORTED_NONE = 0,
+ MAV_FRAME_SUPPORTED_GLOBAL = (1 << 0),
+ MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT = (1 << 1),
+ MAV_FRAME_SUPPORTED_GLOBAL_INT = (1 << 2),
+ MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT_INT = (1 << 3),
+} mavFrameSupportMask_e;
+
+/**
+ * MAVLink requires angles to be in the range -Pi..Pi.
+ * This converts angles from a range of 0..Pi to -Pi..Pi
+ */
+#define RADIANS_TO_MAVLINK_RANGE(angle) (((angle) > M_PIf) ? ((angle) - (2 * M_PIf)) : (angle))
+
+/** @brief A mapping of plane flight modes for custom_mode field of heartbeat. */
+typedef enum APM_PLANE_MODE
+{
+ PLANE_MODE_MANUAL=0,
+ PLANE_MODE_CIRCLE=1,
+ PLANE_MODE_STABILIZE=2,
+ PLANE_MODE_TRAINING=3,
+ PLANE_MODE_ACRO=4,
+ PLANE_MODE_FLY_BY_WIRE_A=5,
+ PLANE_MODE_FLY_BY_WIRE_B=6,
+ PLANE_MODE_CRUISE=7,
+ PLANE_MODE_AUTOTUNE=8,
+ PLANE_MODE_AUTO=10,
+ PLANE_MODE_RTL=11,
+ PLANE_MODE_LOITER=12,
+ PLANE_MODE_TAKEOFF=13,
+ PLANE_MODE_AVOID_ADSB=14,
+ PLANE_MODE_GUIDED=15,
+ PLANE_MODE_INITIALIZING=16,
+ PLANE_MODE_QSTABILIZE=17,
+ PLANE_MODE_QHOVER=18,
+ PLANE_MODE_QLOITER=19,
+ PLANE_MODE_QLAND=20,
+ PLANE_MODE_QRTL=21,
+ PLANE_MODE_QAUTOTUNE=22,
+ PLANE_MODE_QACRO=23,
+ PLANE_MODE_THERMAL=24,
+ PLANE_MODE_LOITER_ALT_QLAND=25,
+ PLANE_MODE_AUTOLAND=26,
+ PLANE_MODE_ENUM_END=27,
+} APM_PLANE_MODE;
+
+/** @brief A mapping of copter flight modes for custom_mode field of heartbeat. */
+typedef enum APM_COPTER_MODE
+{
+ COPTER_MODE_STABILIZE=0,
+ COPTER_MODE_ACRO=1,
+ COPTER_MODE_ALT_HOLD=2,
+ COPTER_MODE_AUTO=3,
+ COPTER_MODE_GUIDED=4,
+ COPTER_MODE_LOITER=5,
+ COPTER_MODE_RTL=6,
+ COPTER_MODE_CIRCLE=7,
+ COPTER_MODE_LAND=9,
+ COPTER_MODE_DRIFT=11,
+ COPTER_MODE_SPORT=13,
+ COPTER_MODE_FLIP=14,
+ COPTER_MODE_AUTOTUNE=15,
+ COPTER_MODE_POSHOLD=16,
+ COPTER_MODE_BRAKE=17,
+ COPTER_MODE_THROW=18,
+ COPTER_MODE_AVOID_ADSB=19,
+ COPTER_MODE_GUIDED_NOGPS=20,
+ COPTER_MODE_SMART_RTL=21,
+ COPTER_MODE_FLOWHOLD=22,
+ COPTER_MODE_FOLLOW=23,
+ COPTER_MODE_ZIGZAG=24,
+ COPTER_MODE_SYSTEMID=25,
+ COPTER_MODE_AUTOROTATE=26,
+ COPTER_MODE_AUTO_RTL=27,
+ COPTER_MODE_TURTLE=28,
+ COPTER_MODE_ENUM_END=29,
+} APM_COPTER_MODE;
+
+typedef struct mavlinkRouteEntry_s {
+ uint8_t sysid;
+ uint8_t compid;
+ uint8_t ingressPortIndex;
+} mavlinkRouteEntry_t;
+
+typedef struct mavlinkPortRuntime_s {
+ serialPort_t *port;
+ const serialPortConfig_t *portConfig;
+ portSharing_e portSharing;
+ bool telemetryEnabled;
+ bool txbuffValid;
+ uint8_t txbuffFree;
+ timeUs_t lastMavlinkMessageUs;
+ timeUs_t lastHighLatencyMessageUs;
+ bool highLatencyEnabled;
+ uint8_t mavRates[MAVLINK_STREAM_COUNT];
+ uint8_t mavRatesConfigured[MAVLINK_STREAM_COUNT];
+ timeUs_t mavStreamNextDue[MAVLINK_STREAM_COUNT];
+ int32_t mavMessageOverrideIntervalsUs[MAVLINK_PERIODIC_MESSAGE_COUNT];
+ timeUs_t mavMessageNextDue[MAVLINK_PERIODIC_MESSAGE_COUNT];
+ uint8_t txSeq;
+ uint32_t txDroppedFrames;
+ mavlink_message_t mavRecvMsg;
+ mavlink_status_t mavRecvStatus;
+} mavlinkPortRuntime_t;
+
+typedef struct mavlinkModeDescriptor_s {
+ uint8_t customMode;
+ const char *name;
+} mavlinkModeDescriptor_t;
+
+extern const mavlinkModeDescriptor_t planeModes[];
+extern const uint8_t planeModesCount;
+extern const mavlinkModeDescriptor_t copterModes[];
+extern const uint8_t copterModesCount;
+
+typedef struct mavlinkMissionItemData_s {
+ uint8_t frame;
+ uint16_t command;
+ float param1;
+ float param2;
+ float param3;
+ float param4;
+ int32_t lat;
+ int32_t lon;
+ float alt;
+} mavlinkMissionItemData_t;
diff --git a/src/main/telemetry/mavlink.h b/src/main/telemetry/mavlink.h
index c732f6c3fff..29f9f2fb8cd 100755
--- a/src/main/telemetry/mavlink.h
+++ b/src/main/telemetry/mavlink.h
@@ -17,176 +17,9 @@
#pragma once
-#include "common/time.h"
-
-#include "io/serial.h"
-
-#include "target/common.h"
-
-#pragma GCC diagnostic push
-#pragma GCC diagnostic ignored "-Wunused-function"
-#ifndef MAVLINK_COMM_NUM_BUFFERS
-#define MAVLINK_COMM_NUM_BUFFERS MAX_MAVLINK_PORTS
-#endif
-#include "common/mavlink.h"
-#pragma GCC diagnostic pop
-
-#define TELEMETRY_MAVLINK_PORT_MODE MODE_RXTX
-#define TELEMETRY_MAVLINK_MAXRATE 50
-#define TELEMETRY_MAVLINK_DELAY ((1000 * 1000) / TELEMETRY_MAVLINK_MAXRATE)
-#define TELEMETRY_MAVLINK_HIGH_LATENCY_INTERVAL_US (5 * 1000 * 1000)
-#define MAV_DATA_STREAM_EXTENDED_SYS_STATE (MAV_DATA_STREAM_EXTRA3 + 1)
-#define MAV_DATA_STREAM_HEARTBEAT (MAV_DATA_STREAM_EXTENDED_SYS_STATE + 1)
-#define MAVLINK_STREAM_COUNT (MAV_DATA_STREAM_HEARTBEAT + 1)
-#define ARDUPILOT_VERSION_MAJOR 4
-#define ARDUPILOT_VERSION_MINOR 6
-#define ARDUPILOT_VERSION_PATCH 3
-#define MAVLINK_MAX_ROUTES 32
-#define MAVLINK_PORT_MASK(portIndex) (1U << (portIndex))
-#define MAXSTREAMS MAVLINK_STREAM_COUNT
-
-typedef enum {
- MAVLINK_PERIODIC_MESSAGE_HEARTBEAT,
- MAVLINK_PERIODIC_MESSAGE_SYS_STATUS,
- MAVLINK_PERIODIC_MESSAGE_EXTENDED_SYS_STATE,
- MAVLINK_PERIODIC_MESSAGE_RC_CHANNELS,
- MAVLINK_PERIODIC_MESSAGE_GPS_RAW_INT,
- MAVLINK_PERIODIC_MESSAGE_GLOBAL_POSITION_INT,
- MAVLINK_PERIODIC_MESSAGE_GPS_GLOBAL_ORIGIN,
- MAVLINK_PERIODIC_MESSAGE_ATTITUDE,
- MAVLINK_PERIODIC_MESSAGE_VFR_HUD,
- MAVLINK_PERIODIC_MESSAGE_BATTERY_STATUS,
- MAVLINK_PERIODIC_MESSAGE_SCALED_PRESSURE,
- MAVLINK_PERIODIC_MESSAGE_SYSTEM_TIME,
- MAVLINK_PERIODIC_MESSAGE_COUNT
-} mavlinkPeriodicMessage_e;
-
-typedef enum {
- MAV_FRAME_SUPPORTED_NONE = 0,
- MAV_FRAME_SUPPORTED_GLOBAL = (1 << 0),
- MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT = (1 << 1),
- MAV_FRAME_SUPPORTED_GLOBAL_INT = (1 << 2),
- MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT_INT = (1 << 3),
-} mavFrameSupportMask_e;
-
-/**
- * MAVLink requires angles to be in the range -Pi..Pi.
- * This converts angles from a range of 0..Pi to -Pi..Pi
- */
-#define RADIANS_TO_MAVLINK_RANGE(angle) (((angle) > M_PIf) ? ((angle) - (2 * M_PIf)) : (angle))
-
-/** @brief A mapping of plane flight modes for custom_mode field of heartbeat. */
-typedef enum APM_PLANE_MODE
-{
- PLANE_MODE_MANUAL=0,
- PLANE_MODE_CIRCLE=1,
- PLANE_MODE_STABILIZE=2,
- PLANE_MODE_TRAINING=3,
- PLANE_MODE_ACRO=4,
- PLANE_MODE_FLY_BY_WIRE_A=5,
- PLANE_MODE_FLY_BY_WIRE_B=6,
- PLANE_MODE_CRUISE=7,
- PLANE_MODE_AUTOTUNE=8,
- PLANE_MODE_AUTO=10,
- PLANE_MODE_RTL=11,
- PLANE_MODE_LOITER=12,
- PLANE_MODE_TAKEOFF=13,
- PLANE_MODE_AVOID_ADSB=14,
- PLANE_MODE_GUIDED=15,
- PLANE_MODE_INITIALIZING=16,
- PLANE_MODE_QSTABILIZE=17,
- PLANE_MODE_QHOVER=18,
- PLANE_MODE_QLOITER=19,
- PLANE_MODE_QLAND=20,
- PLANE_MODE_QRTL=21,
- PLANE_MODE_QAUTOTUNE=22,
- PLANE_MODE_QACRO=23,
- PLANE_MODE_THERMAL=24,
- PLANE_MODE_LOITER_ALT_QLAND=25,
- PLANE_MODE_AUTOLAND=26,
- PLANE_MODE_ENUM_END=27,
-} APM_PLANE_MODE;
-
-/** @brief A mapping of copter flight modes for custom_mode field of heartbeat. */
-typedef enum APM_COPTER_MODE
-{
- COPTER_MODE_STABILIZE=0,
- COPTER_MODE_ACRO=1,
- COPTER_MODE_ALT_HOLD=2,
- COPTER_MODE_AUTO=3,
- COPTER_MODE_GUIDED=4,
- COPTER_MODE_LOITER=5,
- COPTER_MODE_RTL=6,
- COPTER_MODE_CIRCLE=7,
- COPTER_MODE_LAND=9,
- COPTER_MODE_DRIFT=11,
- COPTER_MODE_SPORT=13,
- COPTER_MODE_FLIP=14,
- COPTER_MODE_AUTOTUNE=15,
- COPTER_MODE_POSHOLD=16,
- COPTER_MODE_BRAKE=17,
- COPTER_MODE_THROW=18,
- COPTER_MODE_AVOID_ADSB=19,
- COPTER_MODE_GUIDED_NOGPS=20,
- COPTER_MODE_SMART_RTL=21,
- COPTER_MODE_FLOWHOLD=22,
- COPTER_MODE_FOLLOW=23,
- COPTER_MODE_ZIGZAG=24,
- COPTER_MODE_SYSTEMID=25,
- COPTER_MODE_AUTOROTATE=26,
- COPTER_MODE_AUTO_RTL=27,
- COPTER_MODE_TURTLE=28,
- COPTER_MODE_ENUM_END=29,
-} APM_COPTER_MODE;
-
-typedef struct mavlinkRouteEntry_s {
- uint8_t sysid;
- uint8_t compid;
- uint8_t ingressPortIndex;
-} mavlinkRouteEntry_t;
+#include "mavlink/mavlink_types.h"
-typedef struct mavlinkPortRuntime_s {
- serialPort_t *port;
- const serialPortConfig_t *portConfig;
- portSharing_e portSharing;
- bool telemetryEnabled;
- bool txbuffValid;
- uint8_t txbuffFree;
- timeUs_t lastMavlinkMessageUs;
- timeUs_t lastHighLatencyMessageUs;
- bool highLatencyEnabled;
- uint8_t mavRates[MAVLINK_STREAM_COUNT];
- uint8_t mavRatesConfigured[MAVLINK_STREAM_COUNT];
- timeUs_t mavStreamNextDue[MAVLINK_STREAM_COUNT];
- int32_t mavMessageOverrideIntervalsUs[MAVLINK_PERIODIC_MESSAGE_COUNT];
- timeUs_t mavMessageNextDue[MAVLINK_PERIODIC_MESSAGE_COUNT];
- uint8_t txSeq;
- uint32_t txDroppedFrames;
- mavlink_message_t mavRecvMsg;
- mavlink_status_t mavRecvStatus;
-} mavlinkPortRuntime_t;
-
-typedef struct mavlinkModeDescriptor_s {
- uint8_t customMode;
- const char *name;
-} mavlinkModeDescriptor_t;
-
-extern const mavlinkModeDescriptor_t planeModes[];
-extern const uint8_t planeModesCount;
-extern const mavlinkModeDescriptor_t copterModes[];
-extern const uint8_t copterModesCount;
-
-typedef struct mavlinkMissionItemData_s {
- uint8_t frame;
- uint16_t command;
- float param1;
- float param2;
- float param3;
- float param4;
- int32_t lat;
- int32_t lon;
- float alt;
-} mavlinkMissionItemData_t;
+#include "common/time.h"
void initMAVLinkTelemetry(void);
void handleMAVLinkTelemetry(timeUs_t currentTimeUs);
diff --git a/src/test/unit/mavlink_unittest.cc b/src/test/unit/mavlink_unittest.cc
index 749f10afcfd..846ed7efd0f 100644
--- a/src/test/unit/mavlink_unittest.cc
+++ b/src/test/unit/mavlink_unittest.cc
@@ -76,6 +76,7 @@ extern "C" {
#include "sensors/sensors.h"
#include "sensors/temperature.h"
+ #include "mavlink/mavlink_types.h"
#include "telemetry/mavlink.h"
#include "telemetry/telemetry.h"
From 3847f8d48d574a1fb179c099a3bd7e221e4d2143 Mon Sep 17 00:00:00 2001
From: frogmane <7685285+xznhj8129@users.noreply.github.com>
Date: Fri, 3 Apr 2026 18:04:23 -0400
Subject: [PATCH 36/46] Move MAVLink sends into streams
---
src/main/fc/fc_mavlink.c | 1269 +---------------------------
src/main/fc/fc_mavlink.h | 18 -
src/main/mavlink/mavlink_streams.c | 1135 ++++++++++++++++++++++++-
src/main/mavlink/mavlink_streams.h | 3 +
src/main/mavlink/mavlink_types.h | 5 -
5 files changed, 1138 insertions(+), 1292 deletions(-)
diff --git a/src/main/fc/fc_mavlink.c b/src/main/fc/fc_mavlink.c
index bd7f31eed5e..503bc75ed43 100644
--- a/src/main/fc/fc_mavlink.c
+++ b/src/main/fc/fc_mavlink.c
@@ -7,120 +7,6 @@
#if defined(USE_TELEMETRY) && defined(USE_TELEMETRY_MAVLINK)
-static uint8_t mavlinkGetVehicleType(void)
-{
- switch (mixerConfig()->platformType)
- {
- case PLATFORM_MULTIROTOR:
- return MAV_TYPE_QUADROTOR;
- case PLATFORM_TRICOPTER:
- return MAV_TYPE_TRICOPTER;
- case PLATFORM_AIRPLANE:
- return MAV_TYPE_FIXED_WING;
- case PLATFORM_ROVER:
- return MAV_TYPE_GROUND_ROVER;
- case PLATFORM_BOAT:
- return MAV_TYPE_SURFACE_BOAT;
- case PLATFORM_HELICOPTER:
- return MAV_TYPE_HELICOPTER;
- default:
- return MAV_TYPE_GENERIC;
- }
-}
-
-static APM_COPTER_MODE inavToArduCopterMap(flightModeForTelemetry_e flightMode)
-{
- switch (flightMode)
- {
- case FLM_ACRO: return COPTER_MODE_ACRO;
- case FLM_ACRO_AIR: return COPTER_MODE_ACRO;
- case FLM_ANGLE: return COPTER_MODE_STABILIZE;
- case FLM_HORIZON: return COPTER_MODE_STABILIZE;
- case FLM_ANGLEHOLD: return COPTER_MODE_STABILIZE;
- case FLM_ALTITUDE_HOLD: return COPTER_MODE_ALT_HOLD;
- case FLM_POSITION_HOLD:
- {
- if (isGCSValid()) {
- return COPTER_MODE_GUIDED;
- } else {
- return COPTER_MODE_POSHOLD;
- }
- }
- case FLM_RTH: return COPTER_MODE_RTL;
- case FLM_MISSION: return COPTER_MODE_AUTO;
- case FLM_LAUNCH: return COPTER_MODE_THROW;
- case FLM_FAILSAFE:
- {
- if (failsafePhase() == FAILSAFE_RETURN_TO_HOME) {
- return COPTER_MODE_RTL;
- } else if (failsafePhase() == FAILSAFE_LANDING) {
- return COPTER_MODE_LAND;
- } else {
- return COPTER_MODE_RTL;
- }
- }
- default: return COPTER_MODE_STABILIZE;
- }
-}
-
-static APM_PLANE_MODE inavToArduPlaneMap(flightModeForTelemetry_e flightMode)
-{
- switch (flightMode)
- {
- case FLM_MANUAL: return PLANE_MODE_MANUAL;
- case FLM_ACRO: return PLANE_MODE_ACRO;
- case FLM_ACRO_AIR: return PLANE_MODE_ACRO;
- case FLM_ANGLE: return PLANE_MODE_FLY_BY_WIRE_A;
- case FLM_HORIZON: return PLANE_MODE_STABILIZE;
- case FLM_ANGLEHOLD: return PLANE_MODE_STABILIZE;
- case FLM_ALTITUDE_HOLD: return PLANE_MODE_FLY_BY_WIRE_B;
- case FLM_POSITION_HOLD:
- {
- if (isGCSValid()) {
- return PLANE_MODE_GUIDED;
- } else {
- return PLANE_MODE_LOITER;
- }
- }
- case FLM_RTH: return PLANE_MODE_RTL;
- case FLM_MISSION: return PLANE_MODE_AUTO;
- case FLM_CRUISE: return PLANE_MODE_CRUISE;
- case FLM_LAUNCH: return PLANE_MODE_TAKEOFF;
- case FLM_FAILSAFE: //failsafePhase_e
- {
- if (failsafePhase() == FAILSAFE_RETURN_TO_HOME) {
- return PLANE_MODE_RTL;
- }
- else if (failsafePhase() == FAILSAFE_LANDING) {
- return PLANE_MODE_AUTOLAND;
- }
- else {
- return PLANE_MODE_RTL;
- }
- }
- default: return PLANE_MODE_MANUAL;
- }
-}
-
-typedef struct mavlinkModeSelection_s {
- flightModeForTelemetry_e flightMode;
- uint8_t customMode;
-} mavlinkModeSelection_t;
-
-static mavlinkModeSelection_t selectMavlinkMode(bool isPlane)
-{
- mavlinkModeSelection_t modeSelection;
- modeSelection.flightMode = getFlightModeForTelemetry();
-
- if (isPlane) {
- modeSelection.customMode = (uint8_t)inavToArduPlaneMap(modeSelection.flightMode);
- } else {
- modeSelection.customMode = (uint8_t)inavToArduCopterMap(modeSelection.flightMode);
- }
-
- return modeSelection;
-}
-
static void mavlinkResetTunnelState(uint8_t ingressPortIndex)
{
resetMspPort(&mavTunnelMspPorts[ingressPortIndex], NULL);
@@ -254,66 +140,6 @@ static bool handleIncoming_TUNNEL(uint8_t ingressPortIndex)
return handled;
}
-static void mavlinkSendAutopilotVersion(void)
-{
- if (mavlinkGetProtocolVersion() == 1) return;
-
- // Capabilities aligned with what we actually support.
- uint64_t capabilities = 0;
- capabilities |= MAV_PROTOCOL_CAPABILITY_MAVLINK2;
- capabilities |= MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT;
- capabilities |= MAV_PROTOCOL_CAPABILITY_MISSION_INT;
- capabilities |= MAV_PROTOCOL_CAPABILITY_COMMAND_INT;
- capabilities |= MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_LOCAL_NED;
- capabilities |= MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_GLOBAL_INT;
-
- const uint32_t flightSwVersion =
- ((uint32_t)ARDUPILOT_VERSION_MAJOR << 24) |
- ((uint32_t)ARDUPILOT_VERSION_MINOR << 16) |
- ((uint32_t)ARDUPILOT_VERSION_PATCH << 8);
-
- // Bare minimum: caps + IDs. Everything else 0 is fine.
- mavlink_msg_autopilot_version_pack(
- mavSystemId,
- mavComponentId,
- &mavSendMsg,
- capabilities, // capabilities
- flightSwVersion, // flight_sw_version
- 0, // middleware_sw_version
- 0, // os_sw_version
- 0, // board_version
- 0ULL, // flight_custom_version
- 0ULL, // middleware_custom_version
- 0ULL, // os_custom_version
- 0ULL, // vendor_id
- 0ULL, // product_id
- (uint64_t)mavSystemId, // uid (any stable nonzero is fine)
- 0ULL // uid2
- );
- mavlinkSendMessage();
-}
-
-static void mavlinkSendProtocolVersion(void)
-{
- if (mavlinkGetProtocolVersion() == 1) return;
-
- uint8_t specHash[8] = {0};
- uint8_t libHash[8] = {0};
- const uint16_t protocolVersion = (uint16_t)mavlinkGetProtocolVersion() * 100;
-
- mavlink_msg_protocol_version_pack(
- mavSystemId,
- mavComponentId,
- &mavSendMsg,
- protocolVersion,
- protocolVersion,
- protocolVersion,
- specHash,
- libHash);
-
- mavlinkSendMessage();
-}
-
static bool mavlinkFrameIsSupported(uint8_t frame, mavFrameSupportMask_e allowedMask)
{
switch (frame) {
@@ -445,983 +271,6 @@ static uint8_t navWaypointFrame(const navWaypoint_t *wp, bool useIntMessages)
return useIntMessages ? MAV_FRAME_GLOBAL_RELATIVE_ALT_INT : MAV_FRAME_GLOBAL_RELATIVE_ALT;
}
-const mavlinkModeDescriptor_t planeModes[] = {
- { PLANE_MODE_MANUAL, "MANUAL" },
- { PLANE_MODE_ACRO, "ACRO" },
- { PLANE_MODE_STABILIZE, "STABILIZE" },
- { PLANE_MODE_FLY_BY_WIRE_A,"FBWA" },
- { PLANE_MODE_FLY_BY_WIRE_B,"FBWB" },
- { PLANE_MODE_CRUISE, "CRUISE" },
- { PLANE_MODE_AUTO, "AUTO" },
- { PLANE_MODE_RTL, "RTL" },
- { PLANE_MODE_LOITER, "LOITER" },
- { PLANE_MODE_TAKEOFF, "TAKEOFF" },
- { PLANE_MODE_GUIDED, "GUIDED" },
-};
-const uint8_t planeModesCount = (uint8_t)ARRAYLEN(planeModes);
-
-const mavlinkModeDescriptor_t copterModes[] = {
- { COPTER_MODE_ACRO, "ACRO" },
- { COPTER_MODE_STABILIZE, "STABILIZE" },
- { COPTER_MODE_ALT_HOLD, "ALT_HOLD" },
- { COPTER_MODE_POSHOLD, "POSHOLD" },
- { COPTER_MODE_LOITER, "LOITER" },
- { COPTER_MODE_AUTO, "AUTO" },
- { COPTER_MODE_GUIDED, "GUIDED" },
- { COPTER_MODE_RTL, "RTL" },
- { COPTER_MODE_LAND, "LAND" },
- { COPTER_MODE_BRAKE, "BRAKE" },
- { COPTER_MODE_THROW, "THROW" },
- { COPTER_MODE_SMART_RTL, "SMART_RTL" },
- { COPTER_MODE_DRIFT, "DRIFT" },
-};
-const uint8_t copterModesCount = (uint8_t)ARRAYLEN(copterModes);
-
-static bool mavlinkPlaneModeIsConfigured(uint8_t customMode)
-{
- switch ((APM_PLANE_MODE)customMode) {
- case PLANE_MODE_MANUAL:
- return isModeActivationConditionPresent(BOXMANUAL);
- case PLANE_MODE_ACRO:
- return true;
- case PLANE_MODE_STABILIZE:
- return isModeActivationConditionPresent(BOXHORIZON) ||
- isModeActivationConditionPresent(BOXANGLEHOLD);
- case PLANE_MODE_FLY_BY_WIRE_A:
- return isModeActivationConditionPresent(BOXANGLE);
- case PLANE_MODE_FLY_BY_WIRE_B:
- return isModeActivationConditionPresent(BOXNAVALTHOLD);
- case PLANE_MODE_CRUISE:
- return isModeActivationConditionPresent(BOXNAVCRUISE) ||
- (isModeActivationConditionPresent(BOXNAVCOURSEHOLD) &&
- isModeActivationConditionPresent(BOXNAVALTHOLD));
- case PLANE_MODE_AUTO:
- return isModeActivationConditionPresent(BOXNAVWP);
- case PLANE_MODE_RTL:
- return isModeActivationConditionPresent(BOXNAVRTH);
- case PLANE_MODE_GUIDED:
- return isModeActivationConditionPresent(BOXNAVPOSHOLD) &&
- isModeActivationConditionPresent(BOXGCSNAV);
- case PLANE_MODE_LOITER:
- return isModeActivationConditionPresent(BOXNAVPOSHOLD);
- case PLANE_MODE_TAKEOFF:
- return isModeActivationConditionPresent(BOXNAVLAUNCH);
- default:
- return false;
- }
-}
-
-static bool mavlinkCopterModeIsConfigured(uint8_t customMode)
-{
- switch ((APM_COPTER_MODE)customMode) {
- case COPTER_MODE_ACRO:
- return true;
- case COPTER_MODE_STABILIZE:
- return isModeActivationConditionPresent(BOXANGLE) ||
- isModeActivationConditionPresent(BOXHORIZON) ||
- isModeActivationConditionPresent(BOXANGLEHOLD);
- case COPTER_MODE_ALT_HOLD:
- return isModeActivationConditionPresent(BOXNAVALTHOLD);
- case COPTER_MODE_GUIDED:
- return isModeActivationConditionPresent(BOXNAVPOSHOLD) &&
- isModeActivationConditionPresent(BOXGCSNAV);
- case COPTER_MODE_POSHOLD:
- return isModeActivationConditionPresent(BOXNAVPOSHOLD);
- case COPTER_MODE_RTL:
- return isModeActivationConditionPresent(BOXNAVRTH);
- case COPTER_MODE_AUTO:
- return isModeActivationConditionPresent(BOXNAVWP);
- case COPTER_MODE_THROW:
- return isModeActivationConditionPresent(BOXNAVLAUNCH);
- case COPTER_MODE_BRAKE:
- return isModeActivationConditionPresent(BOXBRAKING);
- default:
- return false;
- }
-}
-
-static void mavlinkSendAvailableModes(const mavlinkModeDescriptor_t *modes, uint8_t count, uint8_t currentCustom,
- bool (*isModeConfigured)(uint8_t customMode))
-{
- uint8_t availableCount = 0;
- for (uint8_t i = 0; i < count; i++) {
- if (isModeConfigured(modes[i].customMode)) {
- availableCount++;
- }
- }
-
- if (availableCount == 0) {
- return;
- }
-
- uint8_t modeIndex = 0;
- for (uint8_t i = 0; i < count; i++) {
- if (!isModeConfigured(modes[i].customMode)) {
- continue;
- }
-
- modeIndex++;
- const uint8_t stdMode = MAV_STANDARD_MODE_NON_STANDARD;
- const uint32_t properties = 0;
-
- mavlink_msg_available_modes_pack(
- mavSystemId,
- mavComponentId,
- &mavSendMsg,
- availableCount,
- modeIndex,
- stdMode,
- modes[i].customMode,
- properties,
- modes[i].name);
-
- mavlinkSendMessage();
-
- if (modes[i].customMode == currentCustom) {
- mavlink_msg_current_mode_pack(
- mavSystemId,
- mavComponentId,
- &mavSendMsg,
- stdMode,
- currentCustom,
- currentCustom);
- mavlinkSendMessage();
- }
- }
-}
-
-void mavlinkSendExtendedSysState(void)
-{
- uint8_t vtolState = MAV_VTOL_STATE_UNDEFINED;
- uint8_t landedState;
-
- switch (NAV_Status.state) {
- case MW_NAV_STATE_LAND_START:
- case MW_NAV_STATE_LAND_IN_PROGRESS:
- case MW_NAV_STATE_LAND_SETTLE:
- case MW_NAV_STATE_LAND_START_DESCENT:
- case MW_NAV_STATE_EMERGENCY_LANDING:
- landedState = MAV_LANDED_STATE_LANDING;
- break;
- case MW_NAV_STATE_LANDED:
- landedState = MAV_LANDED_STATE_ON_GROUND;
- break;
- default:
- if (!ARMING_FLAG(ARMED) || STATE(LANDING_DETECTED)) {
- landedState = MAV_LANDED_STATE_ON_GROUND;
- } else {
- landedState = MAV_LANDED_STATE_IN_AIR;
- }
- break;
- }
-
- mavlink_msg_extended_sys_state_pack(
- mavSystemId,
- mavComponentId,
- &mavSendMsg,
- vtolState,
- landedState);
-
- mavlinkSendMessage();
-}
-
-void mavlinkSendSystemStatus(void)
-{
- // Receiver is assumed to be always present
- uint32_t onboard_control_sensors_present = (MAV_SYS_STATUS_SENSOR_RC_RECEIVER);
- // GYRO and RC are assumed as minimum requirements
- uint32_t onboard_control_sensors_enabled = (MAV_SYS_STATUS_SENSOR_3D_GYRO | MAV_SYS_STATUS_SENSOR_RC_RECEIVER);
- uint32_t onboard_control_sensors_health = 0;
-
- if (getHwGyroStatus() == HW_SENSOR_OK) {
- onboard_control_sensors_present |= MAV_SYS_STATUS_SENSOR_3D_GYRO;
- // Missing presence will report as sensor unhealthy
- onboard_control_sensors_health |= MAV_SYS_STATUS_SENSOR_3D_GYRO;
- }
-
- hardwareSensorStatus_e accStatus = getHwAccelerometerStatus();
- if (accStatus == HW_SENSOR_OK) {
- onboard_control_sensors_present |= MAV_SYS_STATUS_SENSOR_3D_ACCEL;
- onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_3D_ACCEL;
- onboard_control_sensors_health |= MAV_SYS_STATUS_SENSOR_3D_ACCEL;
- } else if (accStatus == HW_SENSOR_UNHEALTHY) {
- onboard_control_sensors_present |= MAV_SYS_STATUS_SENSOR_3D_ACCEL;
- onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_3D_ACCEL;
- } else if (accStatus == HW_SENSOR_UNAVAILABLE) {
- onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_3D_ACCEL;
- }
-
- hardwareSensorStatus_e compassStatus = getHwCompassStatus();
- if (compassStatus == HW_SENSOR_OK) {
- onboard_control_sensors_present |= MAV_SYS_STATUS_SENSOR_3D_MAG;
- onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_3D_MAG;
- onboard_control_sensors_health |= MAV_SYS_STATUS_SENSOR_3D_MAG;
- } else if (compassStatus == HW_SENSOR_UNHEALTHY) {
- onboard_control_sensors_present |= MAV_SYS_STATUS_SENSOR_3D_MAG;
- onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_3D_MAG;
- } else if (compassStatus == HW_SENSOR_UNAVAILABLE) {
- onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_3D_MAG;
- }
-
- hardwareSensorStatus_e baroStatus = getHwBarometerStatus();
- if (baroStatus == HW_SENSOR_OK) {
- onboard_control_sensors_present |= MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE;
- onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE;
- onboard_control_sensors_health |= MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE;
- } else if (baroStatus == HW_SENSOR_UNHEALTHY) {
- onboard_control_sensors_present |= MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE;
- onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE;
- } else if (baroStatus == HW_SENSOR_UNAVAILABLE) {
- onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE;
- }
-
- hardwareSensorStatus_e pitotStatus = getHwPitotmeterStatus();
- if (pitotStatus == HW_SENSOR_OK) {
- onboard_control_sensors_present |= MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE;
- onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE;
- onboard_control_sensors_health |= MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE;
- } else if (pitotStatus == HW_SENSOR_UNHEALTHY) {
- onboard_control_sensors_present |= MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE;
- onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE;
- } else if (pitotStatus == HW_SENSOR_UNAVAILABLE) {
- onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE;
- }
-
- hardwareSensorStatus_e gpsStatus = getHwGPSStatus();
- if (gpsStatus == HW_SENSOR_OK) {
- onboard_control_sensors_present |= MAV_SYS_STATUS_SENSOR_GPS;
- onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_GPS;
- onboard_control_sensors_health |= MAV_SYS_STATUS_SENSOR_GPS;
- } else if (gpsStatus == HW_SENSOR_UNHEALTHY) {
- onboard_control_sensors_present |= MAV_SYS_STATUS_SENSOR_GPS;
- onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_GPS;
- } else if (gpsStatus == HW_SENSOR_UNAVAILABLE) {
- onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_GPS;
- }
-
- hardwareSensorStatus_e opFlowStatus = getHwOpticalFlowStatus();
- if (opFlowStatus == HW_SENSOR_OK) {
- onboard_control_sensors_present |= MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW;
- onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW;
- onboard_control_sensors_health |= MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW;
- } else if (opFlowStatus == HW_SENSOR_UNHEALTHY) {
- onboard_control_sensors_present |= MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW;
- onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW;
- } else if (opFlowStatus == HW_SENSOR_UNAVAILABLE) {
- onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW;
- }
-
- hardwareSensorStatus_e rangefinderStatus = getHwRangefinderStatus();
- if (rangefinderStatus == HW_SENSOR_OK) {
- onboard_control_sensors_present |= MAV_SYS_STATUS_SENSOR_LASER_POSITION;
- onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_LASER_POSITION;
- onboard_control_sensors_health |= MAV_SYS_STATUS_SENSOR_LASER_POSITION;
- } else if (rangefinderStatus == HW_SENSOR_UNHEALTHY) {
- onboard_control_sensors_present |= MAV_SYS_STATUS_SENSOR_LASER_POSITION;
- onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_LASER_POSITION;
- } else if (rangefinderStatus == HW_SENSOR_UNAVAILABLE) {
- onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_LASER_POSITION;
- }
-
- if (rxIsReceivingSignal() && rxAreFlightChannelsValid()) {
- onboard_control_sensors_health |= MAV_SYS_STATUS_SENSOR_RC_RECEIVER;
- }
-
-#ifdef USE_BLACKBOX
- // BLACKBOX is assumed enabled and present for boards with capability
- onboard_control_sensors_present |= MAV_SYS_STATUS_LOGGING;
- onboard_control_sensors_enabled |= MAV_SYS_STATUS_LOGGING;
- // Unhealthy only for cases with not enough space to record
- if (!isBlackboxDeviceFull()) {
- onboard_control_sensors_health |= MAV_SYS_STATUS_LOGGING;
- }
-#endif
-
- mavlink_msg_sys_status_pack(mavSystemId, mavComponentId, &mavSendMsg,
- // onboard_control_sensors_present Bitmask showing which onboard controllers and sensors are present.
- //Value of 0: not present. Value of 1: present. Indices according MAV_SYS_STATUS_SENSOR
- onboard_control_sensors_present,
- // onboard_control_sensors_enabled Bitmask showing which onboard controllers and sensors are enabled
- onboard_control_sensors_enabled,
- // onboard_control_sensors_health Bitmask showing which onboard controllers and sensors are operational or have an error.
- onboard_control_sensors_health,
- // load Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000
- constrain(averageSystemLoadPercent*10, 0, 1000),
- // voltage_battery Battery voltage, in millivolts (1 = 1 millivolt)
- feature(FEATURE_VBAT) ? getBatteryVoltage() * 10 : 0,
- // current_battery Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current
- isAmperageConfigured() ? getAmperage() : -1,
- // battery_remaining Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery
- feature(FEATURE_VBAT) ? calculateBatteryPercentage() : 100,
- // drop_rate_comm Communication drops in percent, (0%: 0, 100%: 10'000), (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)
- 0,
- // errors_comm Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)
- 0,
- // errors_count1 Autopilot-specific errors
- 0,
- // errors_count2 Autopilot-specific errors
- 0,
- // errors_count3 Autopilot-specific errors
- 0,
- // errors_count4 Autopilot-specific errors
- 0, 0, 0, 0);
-
- mavlinkSendMessage();
-}
-
-void mavlinkSendRCChannelsAndRSSI(void)
-{
-#define GET_CHANNEL_VALUE(x) ((rxRuntimeConfig.channelCount >= (x + 1)) ? rxGetChannelValue(x) : 0)
- if (mavlinkGetProtocolVersion() == 1) {
- mavlink_msg_rc_channels_raw_pack(mavSystemId, mavComponentId, &mavSendMsg,
- // time_boot_ms Timestamp (milliseconds since system boot)
- millis(),
- // port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos.
- 0,
- // chan1_raw RC channel 1 value, in microseconds
- GET_CHANNEL_VALUE(0),
- // chan2_raw RC channel 2 value, in microseconds
- GET_CHANNEL_VALUE(1),
- // chan3_raw RC channel 3 value, in microseconds
- GET_CHANNEL_VALUE(2),
- // chan4_raw RC channel 4 value, in microseconds
- GET_CHANNEL_VALUE(3),
- // chan5_raw RC channel 5 value, in microseconds
- GET_CHANNEL_VALUE(4),
- // chan6_raw RC channel 6 value, in microseconds
- GET_CHANNEL_VALUE(5),
- // chan7_raw RC channel 7 value, in microseconds
- GET_CHANNEL_VALUE(6),
- // chan8_raw RC channel 8 value, in microseconds
- GET_CHANNEL_VALUE(7),
- // rssi Receive signal strength indicator, 0: 0%, 254: 100%
- //https://github.com/mavlink/mavlink/issues/1027
- scaleRange(getRSSI(), 0, 1023, 0, 254));
- }
- else {
- mavlink_msg_rc_channels_pack(mavSystemId, mavComponentId, &mavSendMsg,
- // time_boot_ms Timestamp (milliseconds since system boot)
- millis(),
- // Total number of RC channels being received.
- rxRuntimeConfig.channelCount,
- // chan1_raw RC channel 1 value, in microseconds
- GET_CHANNEL_VALUE(0),
- // chan2_raw RC channel 2 value, in microseconds
- GET_CHANNEL_VALUE(1),
- // chan3_raw RC channel 3 value, in microseconds
- GET_CHANNEL_VALUE(2),
- // chan4_raw RC channel 4 value, in microseconds
- GET_CHANNEL_VALUE(3),
- // chan5_raw RC channel 5 value, in microseconds
- GET_CHANNEL_VALUE(4),
- // chan6_raw RC channel 6 value, in microseconds
- GET_CHANNEL_VALUE(5),
- // chan7_raw RC channel 7 value, in microseconds
- GET_CHANNEL_VALUE(6),
- // chan8_raw RC channel 8 value, in microseconds
- GET_CHANNEL_VALUE(7),
- // chan9_raw RC channel 9 value, in microseconds
- GET_CHANNEL_VALUE(8),
- // chan10_raw RC channel 10 value, in microseconds
- GET_CHANNEL_VALUE(9),
- // chan11_raw RC channel 11 value, in microseconds
- GET_CHANNEL_VALUE(10),
- // chan12_raw RC channel 12 value, in microseconds
- GET_CHANNEL_VALUE(11),
- // chan13_raw RC channel 13 value, in microseconds
- GET_CHANNEL_VALUE(12),
- // chan14_raw RC channel 14 value, in microseconds
- GET_CHANNEL_VALUE(13),
- // chan15_raw RC channel 15 value, in microseconds
- GET_CHANNEL_VALUE(14),
- // chan16_raw RC channel 16 value, in microseconds
- GET_CHANNEL_VALUE(15),
- // chan17_raw RC channel 17 value, in microseconds
- GET_CHANNEL_VALUE(16),
- // chan18_raw RC channel 18 value, in microseconds
- GET_CHANNEL_VALUE(17),
- // rssi Receive signal strength indicator, 0: 0%, 254: 100%
- //https://github.com/mavlink/mavlink/issues/1027
- scaleRange(getRSSI(), 0, 1023, 0, 254));
- }
-#undef GET_CHANNEL_VALUE
-
- mavlinkSendMessage();
-}
-
-#if defined(USE_GPS)
-static void mavlinkSendHomePosition(void)
-{
- float q[4] = { 1.0f, 0.0f, 0.0f, 0.0f };
-
- mavlink_msg_home_position_pack(
- mavSystemId,
- mavComponentId,
- &mavSendMsg,
- GPS_home.lat,
- GPS_home.lon,
- GPS_home.alt * 10,
- 0.0f,
- 0.0f,
- 0.0f,
- q,
- 0.0f,
- 0.0f,
- 0.0f,
- ((uint64_t) millis()) * 1000);
-
- mavlinkSendMessage();
-}
-
-void mavlinkSendGpsRawInt(timeUs_t currentTimeUs)
-{
- uint8_t gpsFixType = 0;
-
- if (!(sensors(SENSOR_GPS)
-#ifdef USE_GPS_FIX_ESTIMATION
- || STATE(GPS_ESTIMATED_FIX)
-#endif
- ))
- return;
-
- if (gpsSol.fixType == GPS_NO_FIX)
- gpsFixType = 1;
- else if (gpsSol.fixType == GPS_FIX_2D)
- gpsFixType = 2;
- else if (gpsSol.fixType == GPS_FIX_3D)
- gpsFixType = 3;
-
- mavlink_msg_gps_raw_int_pack(mavSystemId, mavComponentId, &mavSendMsg,
- // time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
- currentTimeUs,
- // fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
- gpsFixType,
- // lat Latitude in 1E7 degrees
- gpsSol.llh.lat,
- // lon Longitude in 1E7 degrees
- gpsSol.llh.lon,
- // alt Altitude in 1E3 meters (millimeters) above MSL
- gpsSol.llh.alt * 10,
- // eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
- gpsSol.eph,
- // epv GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
- gpsSol.epv,
- // vel GPS ground speed (m/s * 100). If unknown, set to: 65535
- gpsSol.groundSpeed,
- // cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535
- gpsSol.groundCourse * 10,
- // satellites_visible Number of satellites visible. If unknown, set to 255
- gpsSol.numSat,
- // alt_ellipsoid Altitude (above WGS84, EGM96 ellipsoid). Positive for up
- 0,
- // h_acc Position uncertainty in mm,
- gpsSol.eph * 10,
- // v_acc Altitude uncertainty in mm,
- gpsSol.epv * 10,
- // vel_acc Speed uncertainty in mm (??)
- 0,
- // hdg_acc Heading uncertainty in degE5
- 0,
- // yaw Yaw in earth frame from north. Use 0 if this GPS does not provide yaw. Use 65535 if this GPS is configured to provide yaw and is currently unable to provide it. Use 36000 for north.
- 0);
-
- mavlinkSendMessage();
-}
-
-void mavlinkSendGlobalPositionInt(timeUs_t currentTimeUs)
-{
- if (!(sensors(SENSOR_GPS)
-#ifdef USE_GPS_FIX_ESTIMATION
- || STATE(GPS_ESTIMATED_FIX)
-#endif
- )) {
- return;
- }
-
- mavlink_msg_global_position_int_pack(mavSystemId, mavComponentId, &mavSendMsg,
- // time_boot_ms Timestamp (milliseconds since system boot)
- currentTimeUs / 1000,
- // lat Latitude in 1E7 degrees
- gpsSol.llh.lat,
- // lon Longitude in 1E7 degrees
- gpsSol.llh.lon,
- // alt Altitude in 1E3 meters (millimeters) above MSL
- gpsSol.llh.alt * 10,
- // relative_alt Altitude above ground in meters, expressed as * 1000 (millimeters)
- getEstimatedActualPosition(Z) * 10,
- // [cm/s] Ground X Speed (Latitude, positive north)
- getEstimatedActualVelocity(X),
- // [cm/s] Ground Y Speed (Longitude, positive east)
- getEstimatedActualVelocity(Y),
- // [cm/s] Ground Z Speed (Altitude, positive down)
- -getEstimatedActualVelocity(Z),
- // [cdeg] Vehicle heading (yaw angle) (0.0..359.99 degrees, 0=north)
- DECIDEGREES_TO_CENTIDEGREES(attitude.values.yaw)
- );
-
- mavlinkSendMessage();
-}
-
-void mavlinkSendGpsGlobalOrigin(void)
-{
- mavlink_msg_gps_global_origin_pack(mavSystemId, mavComponentId, &mavSendMsg,
- // latitude Latitude (WGS84), expressed as * 1E7
- GPS_home.lat,
- // longitude Longitude (WGS84), expressed as * 1E7
- GPS_home.lon,
- // altitude Altitude(WGS84), expressed as * 1000
- GPS_home.alt * 10, // FIXME
- // time_usec Timestamp (microseconds since system boot)
- // Use millis() * 1000 as micros() will overflow after 1.19 hours.
- ((uint64_t) millis()) * 1000);
-
- mavlinkSendMessage();
-}
-
-void mavlinkSendPosition(timeUs_t currentTimeUs)
-{
- mavlinkSendGpsRawInt(currentTimeUs);
- mavlinkSendGlobalPositionInt(currentTimeUs);
- mavlinkSendGpsGlobalOrigin();
-}
-#endif
-
-void mavlinkSendAttitude(void)
-{
- mavlink_msg_attitude_pack(mavSystemId, mavComponentId, &mavSendMsg,
- // time_boot_ms Timestamp (milliseconds since system boot)
- millis(),
- // roll Roll angle (rad)
- RADIANS_TO_MAVLINK_RANGE(DECIDEGREES_TO_RADIANS(attitude.values.roll)),
- // pitch Pitch angle (rad)
- RADIANS_TO_MAVLINK_RANGE(DECIDEGREES_TO_RADIANS(-attitude.values.pitch)),
- // yaw Yaw angle (rad)
- RADIANS_TO_MAVLINK_RANGE(DECIDEGREES_TO_RADIANS(attitude.values.yaw)),
- // rollspeed Roll angular speed (rad/s)
- DEGREES_TO_RADIANS(gyro.gyroADCf[FD_ROLL]),
- // pitchspeed Pitch angular speed (rad/s)
- DEGREES_TO_RADIANS(gyro.gyroADCf[FD_PITCH]),
- // yawspeed Yaw angular speed (rad/s)
- DEGREES_TO_RADIANS(gyro.gyroADCf[FD_YAW]));
-
- mavlinkSendMessage();
-}
-
-void mavlinkSendVfrHud(void)
-{
- float mavAltitude = 0;
- float mavGroundSpeed = 0;
- float mavAirSpeed = 0;
- float mavClimbRate = 0;
-
-#if defined(USE_GPS)
- // use ground speed if source available
- if (sensors(SENSOR_GPS)
-#ifdef USE_GPS_FIX_ESTIMATION
- || STATE(GPS_ESTIMATED_FIX)
-#endif
- ) {
- mavGroundSpeed = gpsSol.groundSpeed / 100.0f;
- }
-#endif
-
-#if defined(USE_PITOT)
- if (sensors(SENSOR_PITOT) && pitotIsHealthy()) {
- mavAirSpeed = getAirspeedEstimate() / 100.0f;
- }
-#endif
-
- // select best source for altitude
- mavAltitude = getEstimatedActualPosition(Z) / 100.0f;
- mavClimbRate = getEstimatedActualVelocity(Z) / 100.0f;
-
- int16_t thr = getThrottlePercent(osdUsingScaledThrottle());
- mavlink_msg_vfr_hud_pack(mavSystemId, mavComponentId, &mavSendMsg,
- // airspeed Current airspeed in m/s
- mavAirSpeed,
- // groundspeed Current ground speed in m/s
- mavGroundSpeed,
- // heading Current heading in degrees, in compass units (0..360, 0=north)
- DECIDEGREES_TO_DEGREES(attitude.values.yaw),
- // throttle Current throttle setting in integer percent, 0 to 100
- thr,
- // alt Current altitude (MSL), in meters, if we have surface or baro use them, otherwise use GPS (less accurate)
- mavAltitude,
- // climb Current climb rate in meters/second
- mavClimbRate);
-
- mavlinkSendMessage();
-}
-
-static uint8_t mavlinkGetAutopilotEnum(void);
-
-void mavlinkSendHeartbeat(void)
-{
- uint8_t mavModes = MAV_MODE_FLAG_CUSTOM_MODE_ENABLED;
-
- const bool isPlane = (STATE(FIXED_WING_LEGACY) || mixerConfig()->platformType == PLATFORM_AIRPLANE);
- const mavlinkModeSelection_t modeSelection = selectMavlinkMode(isPlane);
- flightModeForTelemetry_e flm = modeSelection.flightMode;
- uint8_t mavCustomMode = modeSelection.customMode;
- uint8_t mavSystemType;
- if (isPlane) {
- mavSystemType = MAV_TYPE_FIXED_WING;
- }
- else {
- mavSystemType = mavlinkGetVehicleType();
- }
-
- const bool manualInputAllowed = !(flm == FLM_MISSION || flm == FLM_RTH || flm == FLM_FAILSAFE);
- if (manualInputAllowed) {
- mavModes |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED;
- }
- if (flm == FLM_POSITION_HOLD && isGCSValid()) {
- mavModes |= MAV_MODE_FLAG_GUIDED_ENABLED;
- }
- else if (flm == FLM_MISSION || flm == FLM_RTH ) {
- mavModes |= MAV_MODE_FLAG_AUTO_ENABLED;
- }
- else if (flm != FLM_MANUAL && flm!= FLM_ACRO && flm!=FLM_ACRO_AIR) {
- mavModes |= MAV_MODE_FLAG_STABILIZE_ENABLED;
- }
-
- if (ARMING_FLAG(ARMED))
- mavModes |= MAV_MODE_FLAG_SAFETY_ARMED;
-
- uint8_t mavSystemState = 0;
- if (ARMING_FLAG(ARMED)) {
- if (failsafeIsActive()) {
- mavSystemState = MAV_STATE_CRITICAL;
- }
- else {
- mavSystemState = MAV_STATE_ACTIVE;
- }
- }
- else if (areSensorsCalibrating()) {
- mavSystemState = MAV_STATE_CALIBRATING;
- }
- else {
- mavSystemState = MAV_STATE_STANDBY;
- }
-
- mavlink_msg_heartbeat_pack(mavSystemId, mavComponentId, &mavSendMsg,
- // type Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
- mavSystemType,
- // autopilot Autopilot type / class. defined in MAV_AUTOPILOT ENUM
- mavlinkGetAutopilotEnum(),
- // base_mode System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h
- mavModes,
- // custom_mode A bitfield for use for autopilot-specific flags.
- mavCustomMode,
- // system_status System status flag, see MAV_STATE ENUM
- mavSystemState);
-
- mavlinkSendMessage();
-}
-
-void mavlinkSendBatteryStatus(void)
-{
- uint16_t batteryVoltages[MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_LEN];
- uint16_t batteryVoltagesExt[MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_EXT_LEN];
- memset(batteryVoltages, UINT16_MAX, sizeof(batteryVoltages));
- memset(batteryVoltagesExt, 0, sizeof(batteryVoltagesExt));
- if (feature(FEATURE_VBAT)) {
- uint8_t batteryCellCount = getBatteryCellCount();
- if (batteryCellCount > 0) {
- for (int cell=0; cell < batteryCellCount && cell < MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_LEN + MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_EXT_LEN; cell++) {
- if (cell < MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_LEN) {
- batteryVoltages[cell] = getBatteryAverageCellVoltage() * 10;
- } else {
- batteryVoltagesExt[cell-MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_LEN] = getBatteryAverageCellVoltage() * 10;
- }
- }
- }
- else {
- batteryVoltages[0] = getBatteryVoltage() * 10;
- }
- }
- else {
- batteryVoltages[0] = 0;
- }
-
- mavlink_msg_battery_status_pack(mavSystemId, mavComponentId, &mavSendMsg,
- // id Battery ID
- 0,
- // battery_function Function of the battery
- MAV_BATTERY_FUNCTION_UNKNOWN,
- // type Type (chemistry) of the battery
- MAV_BATTERY_TYPE_UNKNOWN,
- // temperature Temperature of the battery in centi-degrees celsius. INT16_MAX for unknown temperature
- INT16_MAX,
- // voltages Battery voltage of cells, in millivolts (1 = 1 millivolt). Cells above the valid cell count for this battery should have the UINT16_MAX value.
- batteryVoltages,
- // current_battery Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current
- isAmperageConfigured() ? getAmperage() : -1,
- // current_consumed Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate
- isAmperageConfigured() ? getMAhDrawn() : -1,
- // energy_consumed Consumed energy, in 100*Joules (intergrated U*I*dt) (1 = 100 Joule), -1: autopilot does not provide energy consumption estimate
- isAmperageConfigured() ? getMWhDrawn()*36 : -1,
- // battery_remaining Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery);
- feature(FEATURE_VBAT) ? calculateBatteryPercentage() : -1,
- // time_remaining Remaining battery time, 0: autopilot does not provide remaining battery time estimate
- 0, // TODO this could easily be implemented
- // charge_state State for extent of discharge, provided by autopilot for warning or external reactions
- 0,
- // voltages_ext Battery voltages for cells 11 to 14. Cells above the valid cell count for this battery should have a value of 0, where zero indicates not supported (note, this is different than for the voltages field and allows empty byte truncation). If the measured value is 0 then 1 should be sent instead.
- batteryVoltagesExt,
- // mode Battery mode. Default (0) is that battery mode reporting is not supported or battery is in normal-use mode.
- 0,
- // fault_bitmask Fault/health indications. These should be set when charge_state is MAV_BATTERY_CHARGE_STATE_FAILED or MAV_BATTERY_CHARGE_STATE_UNHEALTHY (if not, fault reporting is not supported).
- 0);
-
- mavlinkSendMessage();
-}
-
-void mavlinkSendScaledPressure(void)
-{
- int16_t temperature;
- sensors(SENSOR_BARO) ? getBaroTemperature(&temperature) : getIMUTemperature(&temperature);
- mavlink_msg_scaled_pressure_pack(mavSystemId, mavComponentId, &mavSendMsg,
- millis(),
- 0,
- 0,
- temperature * 10,
- 0);
-
- mavlinkSendMessage();
-}
-
-void mavlinkSendSystemTime(void)
-{
- mavlink_msg_system_time_pack(
- mavSystemId,
- mavComponentId,
- &mavSendMsg,
- 0,
- millis());
-
- mavlinkSendMessage();
-}
-
-bool mavlinkSendStatusText(void)
-{
-// FIXME - Status text is limited to boards with USE_OSD
-#ifdef USE_OSD
- char buff[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN] = {" "};
- textAttributes_t elemAttr = osdGetSystemMessage(buff, sizeof(buff), false);
- if (buff[0] != SYM_BLANK) {
- MAV_SEVERITY severity = MAV_SEVERITY_NOTICE;
- if (TEXT_ATTRIBUTES_HAVE_BLINK(elemAttr)) {
- severity = MAV_SEVERITY_CRITICAL;
- } else if TEXT_ATTRIBUTES_HAVE_INVERTED(elemAttr) {
- severity = MAV_SEVERITY_WARNING;
- }
-
- mavlink_msg_statustext_pack(mavSystemId, mavComponentId, &mavSendMsg,
- (uint8_t)severity,
- buff,
- 0,
- 0);
-
- mavlinkSendMessage();
- return true;
- }
-#endif
- return false;
-}
-
-void mavlinkSendBatteryTemperatureStatusText(void)
-{
- mavlinkSendBatteryStatus();
- mavlinkSendScaledPressure();
- mavlinkSendStatusText();
-}
-
-static uint8_t mavlinkGetAutopilotEnum(void)
-{
- if (mavAutopilotType == MAVLINK_AUTOPILOT_ARDUPILOT) {
- return MAV_AUTOPILOT_ARDUPILOTMEGA;
- }
-
- return MAV_AUTOPILOT_GENERIC;
-}
-
-static uint8_t mavlinkHeadingDeg2FromCd(int32_t headingCd)
-{
- return (uint8_t)(wrap_36000(headingCd) / 200);
-}
-
-static uint16_t mavlinkComputeHighLatencyFailures(void)
-{
- uint16_t flags = 0;
-
-#if defined(USE_GPS)
- if (!(sensors(SENSOR_GPS)
-#ifdef USE_GPS_FIX_ESTIMATION
- || STATE(GPS_ESTIMATED_FIX)
-#endif
- ) || gpsSol.fixType == GPS_NO_FIX) {
- flags |= HL_FAILURE_FLAG_GPS;
- }
-#endif
-
-#ifdef USE_PITOT
- if (getHwPitotmeterStatus() != HW_SENSOR_OK) {
- flags |= HL_FAILURE_FLAG_DIFFERENTIAL_PRESSURE;
- }
-#endif
-
- if (getHwBarometerStatus() != HW_SENSOR_OK) {
- flags |= HL_FAILURE_FLAG_ABSOLUTE_PRESSURE;
- }
-
- if (getHwAccelerometerStatus() != HW_SENSOR_OK) {
- flags |= HL_FAILURE_FLAG_3D_ACCEL;
- }
-
- if (getHwGyroStatus() != HW_SENSOR_OK) {
- flags |= HL_FAILURE_FLAG_3D_GYRO;
- }
-
- if (getHwCompassStatus() != HW_SENSOR_OK) {
- flags |= HL_FAILURE_FLAG_3D_MAG;
- }
-
- if (getHwRangefinderStatus() != HW_SENSOR_OK) {
- flags |= HL_FAILURE_FLAG_TERRAIN;
- }
-
- const batteryState_e batteryState = getBatteryState();
- if (batteryState == BATTERY_WARNING || batteryState == BATTERY_CRITICAL) {
- flags |= HL_FAILURE_FLAG_BATTERY;
- }
-
- if (!rxIsReceivingSignal() || !rxAreFlightChannelsValid()) {
- flags |= HL_FAILURE_FLAG_RC_RECEIVER;
- }
-
- return flags;
-}
-
-void mavlinkSendHighLatency2(timeUs_t currentTimeUs)
-{
- const bool isPlane = (STATE(FIXED_WING_LEGACY) || mixerConfig()->platformType == PLATFORM_AIRPLANE);
- const mavlinkModeSelection_t modeSelection = selectMavlinkMode(isPlane);
-
- int32_t latitude = 0;
- int32_t longitude = 0;
- int16_t altitude = (int16_t)constrain((int32_t)(getEstimatedActualPosition(Z) / 100), INT16_MIN, INT16_MAX);
- int16_t targetAltitude = (int16_t)constrain((int32_t)(posControl.desiredState.pos.z / 100), INT16_MIN, INT16_MAX);
- uint16_t targetDistance = 0;
- uint16_t wpNum = 0;
- uint8_t heading = mavlinkHeadingDeg2FromCd(DECIDEGREES_TO_CENTIDEGREES(attitude.values.yaw));
- uint8_t targetHeading = mavlinkHeadingDeg2FromCd(posControl.desiredState.yaw);
- uint8_t groundspeed = 0;
- uint8_t airspeed = 0;
- uint8_t airspeedSp = 0;
- uint8_t windspeed = 0;
- uint8_t windHeading = 0;
- uint8_t eph = UINT8_MAX;
- uint8_t epv = UINT8_MAX;
- int8_t temperatureAir = 0;
- int8_t climbRate = (int8_t)constrain(lrintf(getEstimatedActualVelocity(Z) / 10.0f), INT8_MIN, INT8_MAX);
- int8_t battery = feature(FEATURE_VBAT) ? (int8_t)calculateBatteryPercentage() : -1;
-
-#if defined(USE_GPS)
- if (sensors(SENSOR_GPS)
-#ifdef USE_GPS_FIX_ESTIMATION
- || STATE(GPS_ESTIMATED_FIX)
-#endif
- ) {
- latitude = gpsSol.llh.lat;
- longitude = gpsSol.llh.lon;
- altitude = (int16_t)constrain((int32_t)(gpsSol.llh.alt / 100), INT16_MIN, INT16_MAX);
-
- const int32_t desiredAltCm = lrintf(posControl.desiredState.pos.z);
- const int32_t targetAltCm = GPS_home.alt + desiredAltCm;
- targetAltitude = (int16_t)constrain(targetAltCm / 100, INT16_MIN, INT16_MAX);
-
- groundspeed = (uint8_t)constrain(lrintf(gpsSol.groundSpeed / 20.0f), 0, UINT8_MAX);
-
- if (gpsSol.flags.validEPE) {
- eph = (uint8_t)constrain((gpsSol.eph + 5) / 10, 0, UINT8_MAX);
- epv = (uint8_t)constrain((gpsSol.epv + 5) / 10, 0, UINT8_MAX);
- }
-
- if (posControl.activeWaypointIndex >= 0) {
- wpNum = (uint16_t)posControl.activeWaypointIndex;
- targetDistance = (uint16_t)constrain(lrintf(posControl.wpDistance / 1000.0f), 0, UINT16_MAX);
- }
- }
-#endif
-
-#if defined(USE_PITOT)
- if (sensors(SENSOR_PITOT) && pitotIsHealthy()) {
- airspeed = (uint8_t)constrain(lrintf(getAirspeedEstimate() / 20.0f), 0, UINT8_MAX);
- airspeedSp = airspeed;
- }
-#endif
-
- if (airspeedSp == 0) {
- const float desiredVelXY = calc_length_pythagorean_2D(posControl.desiredState.vel.x, posControl.desiredState.vel.y);
- airspeedSp = (uint8_t)constrain(lrintf(desiredVelXY / 20.0f), 0, UINT8_MAX);
- }
-
- if (airspeed == 0) {
- airspeed = groundspeed;
- }
-
-#ifdef USE_WIND_ESTIMATOR
- if (isEstimatedWindSpeedValid()) {
- uint16_t windAngleCd = 0;
- const float windHoriz = getEstimatedHorizontalWindSpeed(&windAngleCd);
- windspeed = (uint8_t)constrain(lrintf(windHoriz / 20.0f), 0, UINT8_MAX);
- windHeading = mavlinkHeadingDeg2FromCd(windAngleCd);
- }
-#endif
-
- int16_t temperature;
- sensors(SENSOR_BARO) ? getBaroTemperature(&temperature) : getIMUTemperature(&temperature);
- temperatureAir = (int8_t)constrain(temperature, INT8_MIN, INT8_MAX);
-
- const uint16_t failureFlags = mavlinkComputeHighLatencyFailures();
-
- mavlink_msg_high_latency2_pack(
- mavSystemId,
- mavComponentId,
- &mavSendMsg,
- (uint32_t)(currentTimeUs / 1000),
- mavlinkGetVehicleType(),
- mavlinkGetAutopilotEnum(),
- modeSelection.customMode,
- latitude,
- longitude,
- altitude,
- targetAltitude,
- heading,
- targetHeading,
- targetDistance,
- (uint8_t)constrain(getThrottlePercent(osdUsingScaledThrottle()), 0, 100),
- airspeed,
- airspeedSp,
- groundspeed,
- windspeed,
- windHeading,
- eph,
- epv,
- temperatureAir,
- climbRate,
- battery,
- wpNum,
- failureFlags,
- 0,
- 0,
- 0);
-
- mavlinkSendMessage();
-}
-
-
static void mavlinkResetIncomingMissionTransaction(void);
static bool handleIncoming_MISSION_CLEAR_ALL(void)
@@ -2061,127 +910,13 @@ static bool handleIncoming_COMMAND(uint8_t targetSystem, uint8_t targetComponent
return true;
case MAV_CMD_REQUEST_MESSAGE:
{
- bool sent = false;
- uint16_t messageId = (uint16_t)param1;
-
- switch (messageId) {
- case MAVLINK_MSG_ID_HEARTBEAT:
- mavlinkSendHeartbeat();
- sent = true;
- break;
- case MAVLINK_MSG_ID_AUTOPILOT_VERSION:
- if (mavlinkGetProtocolVersion() != 1) {
- mavlinkSendAutopilotVersion();
- sent = true;
- }
- break;
- case MAVLINK_MSG_ID_PROTOCOL_VERSION:
- if (mavlinkGetProtocolVersion() != 1) {
- mavlinkSendProtocolVersion();
- sent = true;
- }
- break;
- case MAVLINK_MSG_ID_SYS_STATUS:
- mavlinkSendSystemStatus();
- sent = true;
- break;
- case MAVLINK_MSG_ID_ATTITUDE:
- mavlinkSendAttitude();
- sent = true;
- break;
- case MAVLINK_MSG_ID_VFR_HUD:
- mavlinkSendVfrHud();
- sent = true;
- break;
- case MAVLINK_MSG_ID_AVAILABLE_MODES:
- {
- const bool isPlane = mixerConfig()->platformType == PLATFORM_AIRPLANE || STATE(FIXED_WING_LEGACY);
- const mavlinkModeSelection_t modeSelection = selectMavlinkMode(isPlane);
- if (isPlane) {
- mavlinkSendAvailableModes(planeModes, planeModesCount, modeSelection.customMode, mavlinkPlaneModeIsConfigured);
- } else {
- mavlinkSendAvailableModes(copterModes, copterModesCount, modeSelection.customMode, mavlinkCopterModeIsConfigured);
- }
- sent = true;
- }
- break;
- case MAVLINK_MSG_ID_CURRENT_MODE:
- {
- const bool isPlane = mixerConfig()->platformType == PLATFORM_AIRPLANE || STATE(FIXED_WING_LEGACY);
- const mavlinkModeSelection_t modeSelection = selectMavlinkMode(isPlane);
- mavlink_msg_current_mode_pack(
- mavSystemId,
- mavComponentId,
- &mavSendMsg,
- MAV_STANDARD_MODE_NON_STANDARD,
- modeSelection.customMode,
- modeSelection.customMode);
- mavlinkSendMessage();
- sent = true;
- }
- break;
- case MAVLINK_MSG_ID_EXTENDED_SYS_STATE:
- mavlinkSendExtendedSysState();
- sent = true;
- break;
- case MAVLINK_MSG_ID_RC_CHANNELS:
- case MAVLINK_MSG_ID_RC_CHANNELS_RAW:
- case MAVLINK_MSG_ID_RC_CHANNELS_SCALED:
- mavlinkSendRCChannelsAndRSSI();
- sent = true;
- break;
- case MAVLINK_MSG_ID_GPS_RAW_INT:
- #ifdef USE_GPS
- mavlinkSendGpsRawInt(micros());
- sent = true;
- #endif
- break;
- case MAVLINK_MSG_ID_GLOBAL_POSITION_INT:
- #ifdef USE_GPS
- mavlinkSendGlobalPositionInt(micros());
- sent = true;
- #endif
- break;
- case MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN:
- #ifdef USE_GPS
- mavlinkSendGpsGlobalOrigin();
- sent = true;
- #endif
- break;
- case MAVLINK_MSG_ID_BATTERY_STATUS:
- mavlinkSendBatteryStatus();
- sent = true;
- break;
- case MAVLINK_MSG_ID_SCALED_PRESSURE:
- mavlinkSendScaledPressure();
- sent = true;
- break;
- case MAVLINK_MSG_ID_SYSTEM_TIME:
- mavlinkSendSystemTime();
- sent = true;
- break;
- case MAVLINK_MSG_ID_STATUSTEXT:
- sent = mavlinkSendStatusText();
- break;
- case MAVLINK_MSG_ID_HOME_POSITION:
- #ifdef USE_GPS
- if (STATE(GPS_FIX_HOME)) {
- mavlinkSendHomePosition();
- sent = true;
- }
- #endif
- break;
- default:
- break;
- }
-
+ const bool sent = mavlinkSendRequestedMessage((uint16_t)param1);
mavlinkSendCommandAck(command, sent ? MAV_RESULT_ACCEPTED : MAV_RESULT_UNSUPPORTED, ackTargetSystem, ackTargetComponent);
return true;
}
#ifdef USE_GPS
case MAV_CMD_GET_HOME_POSITION:
- if (STATE(GPS_FIX_HOME)) {
- mavlinkSendHomePosition();
+ if (mavlinkSendRequestedMessage(MAVLINK_MSG_ID_HOME_POSITION)) {
mavlinkSendCommandAck(command, MAV_RESULT_ACCEPTED, ackTargetSystem, ackTargetComponent);
} else {
mavlinkSendCommandAck(command, MAV_RESULT_FAILED, ackTargetSystem, ackTargetComponent);
diff --git a/src/main/fc/fc_mavlink.h b/src/main/fc/fc_mavlink.h
index c945ba1ba14..dd4543318c9 100644
--- a/src/main/fc/fc_mavlink.h
+++ b/src/main/fc/fc_mavlink.h
@@ -1,7 +1,5 @@
#pragma once
-#include "common/time.h"
-
#include "mavlink/mavlink_types.h"
typedef enum {
@@ -10,20 +8,4 @@ typedef enum {
MAVLINK_FC_DISPATCH_HANDLED_ACTIVITY,
} mavlinkFcDispatchResult_e;
-void mavlinkSendSystemStatus(void);
-void mavlinkSendRCChannelsAndRSSI(void);
-void mavlinkSendPosition(timeUs_t currentTimeUs);
-void mavlinkSendGpsRawInt(timeUs_t currentTimeUs);
-void mavlinkSendGlobalPositionInt(timeUs_t currentTimeUs);
-void mavlinkSendGpsGlobalOrigin(void);
-void mavlinkSendAttitude(void);
-void mavlinkSendVfrHud(void);
-void mavlinkSendHeartbeat(void);
-void mavlinkSendBatteryTemperatureStatusText(void);
-void mavlinkSendExtendedSysState(void);
-void mavlinkSendBatteryStatus(void);
-void mavlinkSendScaledPressure(void);
-void mavlinkSendSystemTime(void);
-bool mavlinkSendStatusText(void);
-void mavlinkSendHighLatency2(timeUs_t currentTimeUs);
mavlinkFcDispatchResult_e mavlinkFcDispatchIncomingMessage(uint8_t ingressPortIndex);
diff --git a/src/main/mavlink/mavlink_streams.c b/src/main/mavlink/mavlink_streams.c
index a774f2ef00e..312df303137 100644
--- a/src/main/mavlink/mavlink_streams.c
+++ b/src/main/mavlink/mavlink_streams.c
@@ -1,7 +1,5 @@
#include "mavlink/mavlink_internal.h"
-#include "fc/fc_mavlink.h"
-
#include "mavlink/mavlink_runtime.h"
#include "mavlink/mavlink_streams.h"
@@ -240,6 +238,1139 @@ void configureMAVLinkStreamRates(uint8_t portIndex)
}
}
+static uint8_t mavlinkGetVehicleType(void)
+{
+ switch (mixerConfig()->platformType)
+ {
+ case PLATFORM_MULTIROTOR:
+ return MAV_TYPE_QUADROTOR;
+ case PLATFORM_TRICOPTER:
+ return MAV_TYPE_TRICOPTER;
+ case PLATFORM_AIRPLANE:
+ return MAV_TYPE_FIXED_WING;
+ case PLATFORM_ROVER:
+ return MAV_TYPE_GROUND_ROVER;
+ case PLATFORM_BOAT:
+ return MAV_TYPE_SURFACE_BOAT;
+ case PLATFORM_HELICOPTER:
+ return MAV_TYPE_HELICOPTER;
+ default:
+ return MAV_TYPE_GENERIC;
+ }
+}
+
+static APM_COPTER_MODE inavToArduCopterMap(flightModeForTelemetry_e flightMode)
+{
+ switch (flightMode)
+ {
+ case FLM_ACRO: return COPTER_MODE_ACRO;
+ case FLM_ACRO_AIR: return COPTER_MODE_ACRO;
+ case FLM_ANGLE: return COPTER_MODE_STABILIZE;
+ case FLM_HORIZON: return COPTER_MODE_STABILIZE;
+ case FLM_ANGLEHOLD: return COPTER_MODE_STABILIZE;
+ case FLM_ALTITUDE_HOLD: return COPTER_MODE_ALT_HOLD;
+ case FLM_POSITION_HOLD:
+ {
+ if (isGCSValid()) {
+ return COPTER_MODE_GUIDED;
+ } else {
+ return COPTER_MODE_POSHOLD;
+ }
+ }
+ case FLM_RTH: return COPTER_MODE_RTL;
+ case FLM_MISSION: return COPTER_MODE_AUTO;
+ case FLM_LAUNCH: return COPTER_MODE_THROW;
+ case FLM_FAILSAFE:
+ {
+ if (failsafePhase() == FAILSAFE_RETURN_TO_HOME) {
+ return COPTER_MODE_RTL;
+ } else if (failsafePhase() == FAILSAFE_LANDING) {
+ return COPTER_MODE_LAND;
+ } else {
+ return COPTER_MODE_RTL;
+ }
+ }
+ default: return COPTER_MODE_STABILIZE;
+ }
+}
+
+static APM_PLANE_MODE inavToArduPlaneMap(flightModeForTelemetry_e flightMode)
+{
+ switch (flightMode)
+ {
+ case FLM_MANUAL: return PLANE_MODE_MANUAL;
+ case FLM_ACRO: return PLANE_MODE_ACRO;
+ case FLM_ACRO_AIR: return PLANE_MODE_ACRO;
+ case FLM_ANGLE: return PLANE_MODE_FLY_BY_WIRE_A;
+ case FLM_HORIZON: return PLANE_MODE_STABILIZE;
+ case FLM_ANGLEHOLD: return PLANE_MODE_STABILIZE;
+ case FLM_ALTITUDE_HOLD: return PLANE_MODE_FLY_BY_WIRE_B;
+ case FLM_POSITION_HOLD:
+ {
+ if (isGCSValid()) {
+ return PLANE_MODE_GUIDED;
+ } else {
+ return PLANE_MODE_LOITER;
+ }
+ }
+ case FLM_RTH: return PLANE_MODE_RTL;
+ case FLM_MISSION: return PLANE_MODE_AUTO;
+ case FLM_CRUISE: return PLANE_MODE_CRUISE;
+ case FLM_LAUNCH: return PLANE_MODE_TAKEOFF;
+ case FLM_FAILSAFE:
+ {
+ if (failsafePhase() == FAILSAFE_RETURN_TO_HOME) {
+ return PLANE_MODE_RTL;
+ } else if (failsafePhase() == FAILSAFE_LANDING) {
+ return PLANE_MODE_AUTOLAND;
+ } else {
+ return PLANE_MODE_RTL;
+ }
+ }
+ default: return PLANE_MODE_MANUAL;
+ }
+}
+
+typedef struct mavlinkModeSelection_s {
+ flightModeForTelemetry_e flightMode;
+ uint8_t customMode;
+} mavlinkModeSelection_t;
+
+static mavlinkModeSelection_t selectMavlinkMode(bool isPlane)
+{
+ mavlinkModeSelection_t modeSelection;
+ modeSelection.flightMode = getFlightModeForTelemetry();
+
+ if (isPlane) {
+ modeSelection.customMode = (uint8_t)inavToArduPlaneMap(modeSelection.flightMode);
+ } else {
+ modeSelection.customMode = (uint8_t)inavToArduCopterMap(modeSelection.flightMode);
+ }
+
+ return modeSelection;
+}
+
+void mavlinkSendAutopilotVersion(void)
+{
+ if (mavlinkGetProtocolVersion() == 1) {
+ return;
+ }
+
+ // Capabilities aligned with what we actually support.
+ uint64_t capabilities = 0;
+ capabilities |= MAV_PROTOCOL_CAPABILITY_MAVLINK2;
+ capabilities |= MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT;
+ capabilities |= MAV_PROTOCOL_CAPABILITY_MISSION_INT;
+ capabilities |= MAV_PROTOCOL_CAPABILITY_COMMAND_INT;
+ capabilities |= MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_LOCAL_NED;
+ capabilities |= MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_GLOBAL_INT;
+
+ const uint32_t flightSwVersion =
+ ((uint32_t)ARDUPILOT_VERSION_MAJOR << 24) |
+ ((uint32_t)ARDUPILOT_VERSION_MINOR << 16) |
+ ((uint32_t)ARDUPILOT_VERSION_PATCH << 8);
+
+ // Bare minimum: caps + IDs. Everything else 0 is fine.
+ mavlink_msg_autopilot_version_pack(
+ mavSystemId,
+ mavComponentId,
+ &mavSendMsg,
+ capabilities,
+ flightSwVersion,
+ 0,
+ 0,
+ 0,
+ 0ULL,
+ 0ULL,
+ 0ULL,
+ 0ULL,
+ 0ULL,
+ (uint64_t)mavSystemId,
+ 0ULL
+ );
+ mavlinkSendMessage();
+}
+
+void mavlinkSendProtocolVersion(void)
+{
+ if (mavlinkGetProtocolVersion() == 1) {
+ return;
+ }
+
+ uint8_t specHash[8] = {0};
+ uint8_t libHash[8] = {0};
+ const uint16_t protocolVersion = (uint16_t)mavlinkGetProtocolVersion() * 100;
+
+ mavlink_msg_protocol_version_pack(
+ mavSystemId,
+ mavComponentId,
+ &mavSendMsg,
+ protocolVersion,
+ protocolVersion,
+ protocolVersion,
+ specHash,
+ libHash);
+
+ mavlinkSendMessage();
+}
+
+static const mavlinkModeDescriptor_t planeModes[] = {
+ { PLANE_MODE_MANUAL, "MANUAL" },
+ { PLANE_MODE_ACRO, "ACRO" },
+ { PLANE_MODE_STABILIZE, "STABILIZE" },
+ { PLANE_MODE_FLY_BY_WIRE_A,"FBWA" },
+ { PLANE_MODE_FLY_BY_WIRE_B,"FBWB" },
+ { PLANE_MODE_CRUISE, "CRUISE" },
+ { PLANE_MODE_AUTO, "AUTO" },
+ { PLANE_MODE_RTL, "RTL" },
+ { PLANE_MODE_LOITER, "LOITER" },
+ { PLANE_MODE_TAKEOFF, "TAKEOFF" },
+ { PLANE_MODE_GUIDED, "GUIDED" },
+};
+
+static const mavlinkModeDescriptor_t copterModes[] = {
+ { COPTER_MODE_ACRO, "ACRO" },
+ { COPTER_MODE_STABILIZE, "STABILIZE" },
+ { COPTER_MODE_ALT_HOLD, "ALT_HOLD" },
+ { COPTER_MODE_POSHOLD, "POSHOLD" },
+ { COPTER_MODE_LOITER, "LOITER" },
+ { COPTER_MODE_AUTO, "AUTO" },
+ { COPTER_MODE_GUIDED, "GUIDED" },
+ { COPTER_MODE_RTL, "RTL" },
+ { COPTER_MODE_LAND, "LAND" },
+ { COPTER_MODE_BRAKE, "BRAKE" },
+ { COPTER_MODE_THROW, "THROW" },
+ { COPTER_MODE_SMART_RTL, "SMART_RTL" },
+ { COPTER_MODE_DRIFT, "DRIFT" },
+};
+
+static bool mavlinkPlaneModeIsConfigured(uint8_t customMode)
+{
+ switch ((APM_PLANE_MODE)customMode) {
+ case PLANE_MODE_MANUAL:
+ return isModeActivationConditionPresent(BOXMANUAL);
+ case PLANE_MODE_ACRO:
+ return true;
+ case PLANE_MODE_STABILIZE:
+ return isModeActivationConditionPresent(BOXHORIZON) ||
+ isModeActivationConditionPresent(BOXANGLEHOLD);
+ case PLANE_MODE_FLY_BY_WIRE_A:
+ return isModeActivationConditionPresent(BOXANGLE);
+ case PLANE_MODE_FLY_BY_WIRE_B:
+ return isModeActivationConditionPresent(BOXNAVALTHOLD);
+ case PLANE_MODE_CRUISE:
+ return isModeActivationConditionPresent(BOXNAVCRUISE) ||
+ (isModeActivationConditionPresent(BOXNAVCOURSEHOLD) &&
+ isModeActivationConditionPresent(BOXNAVALTHOLD));
+ case PLANE_MODE_AUTO:
+ return isModeActivationConditionPresent(BOXNAVWP);
+ case PLANE_MODE_RTL:
+ return isModeActivationConditionPresent(BOXNAVRTH);
+ case PLANE_MODE_GUIDED:
+ return isModeActivationConditionPresent(BOXNAVPOSHOLD) &&
+ isModeActivationConditionPresent(BOXGCSNAV);
+ case PLANE_MODE_LOITER:
+ return isModeActivationConditionPresent(BOXNAVPOSHOLD);
+ case PLANE_MODE_TAKEOFF:
+ return isModeActivationConditionPresent(BOXNAVLAUNCH);
+ default:
+ return false;
+ }
+}
+
+static bool mavlinkCopterModeIsConfigured(uint8_t customMode)
+{
+ switch ((APM_COPTER_MODE)customMode) {
+ case COPTER_MODE_ACRO:
+ return true;
+ case COPTER_MODE_STABILIZE:
+ return isModeActivationConditionPresent(BOXANGLE) ||
+ isModeActivationConditionPresent(BOXHORIZON) ||
+ isModeActivationConditionPresent(BOXANGLEHOLD);
+ case COPTER_MODE_ALT_HOLD:
+ return isModeActivationConditionPresent(BOXNAVALTHOLD);
+ case COPTER_MODE_GUIDED:
+ return isModeActivationConditionPresent(BOXNAVPOSHOLD) &&
+ isModeActivationConditionPresent(BOXGCSNAV);
+ case COPTER_MODE_POSHOLD:
+ return isModeActivationConditionPresent(BOXNAVPOSHOLD);
+ case COPTER_MODE_RTL:
+ return isModeActivationConditionPresent(BOXNAVRTH);
+ case COPTER_MODE_AUTO:
+ return isModeActivationConditionPresent(BOXNAVWP);
+ case COPTER_MODE_THROW:
+ return isModeActivationConditionPresent(BOXNAVLAUNCH);
+ case COPTER_MODE_BRAKE:
+ return isModeActivationConditionPresent(BOXBRAKING);
+ default:
+ return false;
+ }
+}
+
+static void mavlinkSendAvailableModes(const mavlinkModeDescriptor_t *modes, uint8_t count, uint8_t currentCustom,
+ bool (*isModeConfigured)(uint8_t customMode))
+{
+ uint8_t availableCount = 0;
+ for (uint8_t i = 0; i < count; i++) {
+ if (isModeConfigured(modes[i].customMode)) {
+ availableCount++;
+ }
+ }
+
+ if (availableCount == 0) {
+ return;
+ }
+
+ uint8_t modeIndex = 0;
+ for (uint8_t i = 0; i < count; i++) {
+ if (!isModeConfigured(modes[i].customMode)) {
+ continue;
+ }
+
+ modeIndex++;
+ const uint8_t stdMode = MAV_STANDARD_MODE_NON_STANDARD;
+ const uint32_t properties = 0;
+
+ mavlink_msg_available_modes_pack(
+ mavSystemId,
+ mavComponentId,
+ &mavSendMsg,
+ availableCount,
+ modeIndex,
+ stdMode,
+ modes[i].customMode,
+ properties,
+ modes[i].name);
+
+ mavlinkSendMessage();
+
+ if (modes[i].customMode == currentCustom) {
+ mavlink_msg_current_mode_pack(
+ mavSystemId,
+ mavComponentId,
+ &mavSendMsg,
+ stdMode,
+ currentCustom,
+ currentCustom);
+ mavlinkSendMessage();
+ }
+ }
+}
+
+void mavlinkSendExtendedSysState(void)
+{
+ uint8_t vtolState = MAV_VTOL_STATE_UNDEFINED;
+ uint8_t landedState;
+
+ switch (NAV_Status.state) {
+ case MW_NAV_STATE_LAND_START:
+ case MW_NAV_STATE_LAND_IN_PROGRESS:
+ case MW_NAV_STATE_LAND_SETTLE:
+ case MW_NAV_STATE_LAND_START_DESCENT:
+ case MW_NAV_STATE_EMERGENCY_LANDING:
+ landedState = MAV_LANDED_STATE_LANDING;
+ break;
+ case MW_NAV_STATE_LANDED:
+ landedState = MAV_LANDED_STATE_ON_GROUND;
+ break;
+ default:
+ if (!ARMING_FLAG(ARMED) || STATE(LANDING_DETECTED)) {
+ landedState = MAV_LANDED_STATE_ON_GROUND;
+ } else {
+ landedState = MAV_LANDED_STATE_IN_AIR;
+ }
+ break;
+ }
+
+ mavlink_msg_extended_sys_state_pack(
+ mavSystemId,
+ mavComponentId,
+ &mavSendMsg,
+ vtolState,
+ landedState);
+
+ mavlinkSendMessage();
+}
+
+void mavlinkSendSystemStatus(void)
+{
+ // Receiver is assumed to be always present
+ uint32_t onboard_control_sensors_present = (MAV_SYS_STATUS_SENSOR_RC_RECEIVER);
+ // GYRO and RC are assumed as minimum requirements
+ uint32_t onboard_control_sensors_enabled = (MAV_SYS_STATUS_SENSOR_3D_GYRO | MAV_SYS_STATUS_SENSOR_RC_RECEIVER);
+ uint32_t onboard_control_sensors_health = 0;
+
+ if (getHwGyroStatus() == HW_SENSOR_OK) {
+ onboard_control_sensors_present |= MAV_SYS_STATUS_SENSOR_3D_GYRO;
+ // Missing presence will report as sensor unhealthy
+ onboard_control_sensors_health |= MAV_SYS_STATUS_SENSOR_3D_GYRO;
+ }
+
+ hardwareSensorStatus_e accStatus = getHwAccelerometerStatus();
+ if (accStatus == HW_SENSOR_OK) {
+ onboard_control_sensors_present |= MAV_SYS_STATUS_SENSOR_3D_ACCEL;
+ onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_3D_ACCEL;
+ onboard_control_sensors_health |= MAV_SYS_STATUS_SENSOR_3D_ACCEL;
+ } else if (accStatus == HW_SENSOR_UNHEALTHY) {
+ onboard_control_sensors_present |= MAV_SYS_STATUS_SENSOR_3D_ACCEL;
+ onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_3D_ACCEL;
+ } else if (accStatus == HW_SENSOR_UNAVAILABLE) {
+ onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_3D_ACCEL;
+ }
+
+ hardwareSensorStatus_e compassStatus = getHwCompassStatus();
+ if (compassStatus == HW_SENSOR_OK) {
+ onboard_control_sensors_present |= MAV_SYS_STATUS_SENSOR_3D_MAG;
+ onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_3D_MAG;
+ onboard_control_sensors_health |= MAV_SYS_STATUS_SENSOR_3D_MAG;
+ } else if (compassStatus == HW_SENSOR_UNHEALTHY) {
+ onboard_control_sensors_present |= MAV_SYS_STATUS_SENSOR_3D_MAG;
+ onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_3D_MAG;
+ } else if (compassStatus == HW_SENSOR_UNAVAILABLE) {
+ onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_3D_MAG;
+ }
+
+ hardwareSensorStatus_e baroStatus = getHwBarometerStatus();
+ if (baroStatus == HW_SENSOR_OK) {
+ onboard_control_sensors_present |= MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE;
+ onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE;
+ onboard_control_sensors_health |= MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE;
+ } else if (baroStatus == HW_SENSOR_UNHEALTHY) {
+ onboard_control_sensors_present |= MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE;
+ onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE;
+ } else if (baroStatus == HW_SENSOR_UNAVAILABLE) {
+ onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE;
+ }
+
+ hardwareSensorStatus_e pitotStatus = getHwPitotmeterStatus();
+ if (pitotStatus == HW_SENSOR_OK) {
+ onboard_control_sensors_present |= MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE;
+ onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE;
+ onboard_control_sensors_health |= MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE;
+ } else if (pitotStatus == HW_SENSOR_UNHEALTHY) {
+ onboard_control_sensors_present |= MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE;
+ onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE;
+ } else if (pitotStatus == HW_SENSOR_UNAVAILABLE) {
+ onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE;
+ }
+
+ hardwareSensorStatus_e gpsStatus = getHwGPSStatus();
+ if (gpsStatus == HW_SENSOR_OK) {
+ onboard_control_sensors_present |= MAV_SYS_STATUS_SENSOR_GPS;
+ onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_GPS;
+ onboard_control_sensors_health |= MAV_SYS_STATUS_SENSOR_GPS;
+ } else if (gpsStatus == HW_SENSOR_UNHEALTHY) {
+ onboard_control_sensors_present |= MAV_SYS_STATUS_SENSOR_GPS;
+ onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_GPS;
+ } else if (gpsStatus == HW_SENSOR_UNAVAILABLE) {
+ onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_GPS;
+ }
+
+ hardwareSensorStatus_e opFlowStatus = getHwOpticalFlowStatus();
+ if (opFlowStatus == HW_SENSOR_OK) {
+ onboard_control_sensors_present |= MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW;
+ onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW;
+ onboard_control_sensors_health |= MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW;
+ } else if (opFlowStatus == HW_SENSOR_UNHEALTHY) {
+ onboard_control_sensors_present |= MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW;
+ onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW;
+ } else if (opFlowStatus == HW_SENSOR_UNAVAILABLE) {
+ onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW;
+ }
+
+ hardwareSensorStatus_e rangefinderStatus = getHwRangefinderStatus();
+ if (rangefinderStatus == HW_SENSOR_OK) {
+ onboard_control_sensors_present |= MAV_SYS_STATUS_SENSOR_LASER_POSITION;
+ onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_LASER_POSITION;
+ onboard_control_sensors_health |= MAV_SYS_STATUS_SENSOR_LASER_POSITION;
+ } else if (rangefinderStatus == HW_SENSOR_UNHEALTHY) {
+ onboard_control_sensors_present |= MAV_SYS_STATUS_SENSOR_LASER_POSITION;
+ onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_LASER_POSITION;
+ } else if (rangefinderStatus == HW_SENSOR_UNAVAILABLE) {
+ onboard_control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_LASER_POSITION;
+ }
+
+ if (rxIsReceivingSignal() && rxAreFlightChannelsValid()) {
+ onboard_control_sensors_health |= MAV_SYS_STATUS_SENSOR_RC_RECEIVER;
+ }
+
+#ifdef USE_BLACKBOX
+ // BLACKBOX is assumed enabled and present for boards with capability
+ onboard_control_sensors_present |= MAV_SYS_STATUS_LOGGING;
+ onboard_control_sensors_enabled |= MAV_SYS_STATUS_LOGGING;
+ // Unhealthy only for cases with not enough space to record
+ if (!isBlackboxDeviceFull()) {
+ onboard_control_sensors_health |= MAV_SYS_STATUS_LOGGING;
+ }
+#endif
+
+ mavlink_msg_sys_status_pack(mavSystemId, mavComponentId, &mavSendMsg,
+ onboard_control_sensors_present,
+ onboard_control_sensors_enabled,
+ onboard_control_sensors_health,
+ constrain(averageSystemLoadPercent * 10, 0, 1000),
+ feature(FEATURE_VBAT) ? getBatteryVoltage() * 10 : 0,
+ isAmperageConfigured() ? getAmperage() : -1,
+ feature(FEATURE_VBAT) ? calculateBatteryPercentage() : 100,
+ 0,
+ 0,
+ 0,
+ 0,
+ 0,
+ 0, 0, 0, 0);
+
+ mavlinkSendMessage();
+}
+
+void mavlinkSendRCChannelsAndRSSI(void)
+{
+#define GET_CHANNEL_VALUE(x) ((rxRuntimeConfig.channelCount >= (x + 1)) ? rxGetChannelValue(x) : 0)
+ if (mavlinkGetProtocolVersion() == 1) {
+ mavlink_msg_rc_channels_raw_pack(mavSystemId, mavComponentId, &mavSendMsg,
+ millis(),
+ 0,
+ GET_CHANNEL_VALUE(0),
+ GET_CHANNEL_VALUE(1),
+ GET_CHANNEL_VALUE(2),
+ GET_CHANNEL_VALUE(3),
+ GET_CHANNEL_VALUE(4),
+ GET_CHANNEL_VALUE(5),
+ GET_CHANNEL_VALUE(6),
+ GET_CHANNEL_VALUE(7),
+ scaleRange(getRSSI(), 0, 1023, 0, 254));
+ }
+ else {
+ mavlink_msg_rc_channels_pack(mavSystemId, mavComponentId, &mavSendMsg,
+ millis(),
+ rxRuntimeConfig.channelCount,
+ GET_CHANNEL_VALUE(0),
+ GET_CHANNEL_VALUE(1),
+ GET_CHANNEL_VALUE(2),
+ GET_CHANNEL_VALUE(3),
+ GET_CHANNEL_VALUE(4),
+ GET_CHANNEL_VALUE(5),
+ GET_CHANNEL_VALUE(6),
+ GET_CHANNEL_VALUE(7),
+ GET_CHANNEL_VALUE(8),
+ GET_CHANNEL_VALUE(9),
+ GET_CHANNEL_VALUE(10),
+ GET_CHANNEL_VALUE(11),
+ GET_CHANNEL_VALUE(12),
+ GET_CHANNEL_VALUE(13),
+ GET_CHANNEL_VALUE(14),
+ GET_CHANNEL_VALUE(15),
+ GET_CHANNEL_VALUE(16),
+ GET_CHANNEL_VALUE(17),
+ scaleRange(getRSSI(), 0, 1023, 0, 254));
+ }
+#undef GET_CHANNEL_VALUE
+
+ mavlinkSendMessage();
+}
+
+#if defined(USE_GPS)
+static void mavlinkSendHomePosition(void)
+{
+ float q[4] = { 1.0f, 0.0f, 0.0f, 0.0f };
+
+ mavlink_msg_home_position_pack(
+ mavSystemId,
+ mavComponentId,
+ &mavSendMsg,
+ GPS_home.lat,
+ GPS_home.lon,
+ GPS_home.alt * 10,
+ 0.0f,
+ 0.0f,
+ 0.0f,
+ q,
+ 0.0f,
+ 0.0f,
+ 0.0f,
+ ((uint64_t) millis()) * 1000);
+
+ mavlinkSendMessage();
+}
+
+void mavlinkSendGpsRawInt(timeUs_t currentTimeUs)
+{
+ uint8_t gpsFixType = 0;
+
+ if (!(sensors(SENSOR_GPS)
+#ifdef USE_GPS_FIX_ESTIMATION
+ || STATE(GPS_ESTIMATED_FIX)
+#endif
+ )) {
+ return;
+ }
+
+ if (gpsSol.fixType == GPS_NO_FIX) {
+ gpsFixType = 1;
+ } else if (gpsSol.fixType == GPS_FIX_2D) {
+ gpsFixType = 2;
+ } else if (gpsSol.fixType == GPS_FIX_3D) {
+ gpsFixType = 3;
+ }
+
+ mavlink_msg_gps_raw_int_pack(mavSystemId, mavComponentId, &mavSendMsg,
+ currentTimeUs,
+ gpsFixType,
+ gpsSol.llh.lat,
+ gpsSol.llh.lon,
+ gpsSol.llh.alt * 10,
+ gpsSol.eph,
+ gpsSol.epv,
+ gpsSol.groundSpeed,
+ gpsSol.groundCourse * 10,
+ gpsSol.numSat,
+ 0,
+ gpsSol.eph * 10,
+ gpsSol.epv * 10,
+ 0,
+ 0,
+ 0);
+
+ mavlinkSendMessage();
+}
+
+void mavlinkSendGlobalPositionInt(timeUs_t currentTimeUs)
+{
+ if (!(sensors(SENSOR_GPS)
+#ifdef USE_GPS_FIX_ESTIMATION
+ || STATE(GPS_ESTIMATED_FIX)
+#endif
+ )) {
+ return;
+ }
+
+ mavlink_msg_global_position_int_pack(mavSystemId, mavComponentId, &mavSendMsg,
+ currentTimeUs / 1000,
+ gpsSol.llh.lat,
+ gpsSol.llh.lon,
+ gpsSol.llh.alt * 10,
+ getEstimatedActualPosition(Z) * 10,
+ getEstimatedActualVelocity(X),
+ getEstimatedActualVelocity(Y),
+ -getEstimatedActualVelocity(Z),
+ DECIDEGREES_TO_CENTIDEGREES(attitude.values.yaw)
+ );
+
+ mavlinkSendMessage();
+}
+
+void mavlinkSendGpsGlobalOrigin(void)
+{
+ mavlink_msg_gps_global_origin_pack(mavSystemId, mavComponentId, &mavSendMsg,
+ GPS_home.lat,
+ GPS_home.lon,
+ GPS_home.alt * 10,
+ ((uint64_t) millis()) * 1000);
+
+ mavlinkSendMessage();
+}
+
+void mavlinkSendPosition(timeUs_t currentTimeUs)
+{
+ mavlinkSendGpsRawInt(currentTimeUs);
+ mavlinkSendGlobalPositionInt(currentTimeUs);
+ mavlinkSendGpsGlobalOrigin();
+}
+#endif
+
+void mavlinkSendAttitude(void)
+{
+ mavlink_msg_attitude_pack(mavSystemId, mavComponentId, &mavSendMsg,
+ millis(),
+ RADIANS_TO_MAVLINK_RANGE(DECIDEGREES_TO_RADIANS(attitude.values.roll)),
+ RADIANS_TO_MAVLINK_RANGE(DECIDEGREES_TO_RADIANS(-attitude.values.pitch)),
+ RADIANS_TO_MAVLINK_RANGE(DECIDEGREES_TO_RADIANS(attitude.values.yaw)),
+ DEGREES_TO_RADIANS(gyro.gyroADCf[FD_ROLL]),
+ DEGREES_TO_RADIANS(gyro.gyroADCf[FD_PITCH]),
+ DEGREES_TO_RADIANS(gyro.gyroADCf[FD_YAW]));
+
+ mavlinkSendMessage();
+}
+
+void mavlinkSendVfrHud(void)
+{
+ float mavAltitude = 0;
+ float mavGroundSpeed = 0;
+ float mavAirSpeed = 0;
+ float mavClimbRate = 0;
+
+#if defined(USE_GPS)
+ if (sensors(SENSOR_GPS)
+#ifdef USE_GPS_FIX_ESTIMATION
+ || STATE(GPS_ESTIMATED_FIX)
+#endif
+ ) {
+ mavGroundSpeed = gpsSol.groundSpeed / 100.0f;
+ }
+#endif
+
+#if defined(USE_PITOT)
+ if (sensors(SENSOR_PITOT) && pitotIsHealthy()) {
+ mavAirSpeed = getAirspeedEstimate() / 100.0f;
+ }
+#endif
+
+ mavAltitude = getEstimatedActualPosition(Z) / 100.0f;
+ mavClimbRate = getEstimatedActualVelocity(Z) / 100.0f;
+
+ int16_t thr = getThrottlePercent(osdUsingScaledThrottle());
+ mavlink_msg_vfr_hud_pack(mavSystemId, mavComponentId, &mavSendMsg,
+ mavAirSpeed,
+ mavGroundSpeed,
+ DECIDEGREES_TO_DEGREES(attitude.values.yaw),
+ thr,
+ mavAltitude,
+ mavClimbRate);
+
+ mavlinkSendMessage();
+}
+
+static uint8_t mavlinkGetAutopilotEnum(void);
+
+void mavlinkSendHeartbeat(void)
+{
+ uint8_t mavModes = MAV_MODE_FLAG_CUSTOM_MODE_ENABLED;
+
+ const bool isPlane = (STATE(FIXED_WING_LEGACY) || mixerConfig()->platformType == PLATFORM_AIRPLANE);
+ const mavlinkModeSelection_t modeSelection = selectMavlinkMode(isPlane);
+ flightModeForTelemetry_e flm = modeSelection.flightMode;
+ uint8_t mavCustomMode = modeSelection.customMode;
+ uint8_t mavSystemType;
+ if (isPlane) {
+ mavSystemType = MAV_TYPE_FIXED_WING;
+ }
+ else {
+ mavSystemType = mavlinkGetVehicleType();
+ }
+
+ const bool manualInputAllowed = !(flm == FLM_MISSION || flm == FLM_RTH || flm == FLM_FAILSAFE);
+ if (manualInputAllowed) {
+ mavModes |= MAV_MODE_FLAG_MANUAL_INPUT_ENABLED;
+ }
+ if (flm == FLM_POSITION_HOLD && isGCSValid()) {
+ mavModes |= MAV_MODE_FLAG_GUIDED_ENABLED;
+ }
+ else if (flm == FLM_MISSION || flm == FLM_RTH ) {
+ mavModes |= MAV_MODE_FLAG_AUTO_ENABLED;
+ }
+ else if (flm != FLM_MANUAL && flm != FLM_ACRO && flm != FLM_ACRO_AIR) {
+ mavModes |= MAV_MODE_FLAG_STABILIZE_ENABLED;
+ }
+
+ if (ARMING_FLAG(ARMED)) {
+ mavModes |= MAV_MODE_FLAG_SAFETY_ARMED;
+ }
+
+ uint8_t mavSystemState = 0;
+ if (ARMING_FLAG(ARMED)) {
+ if (failsafeIsActive()) {
+ mavSystemState = MAV_STATE_CRITICAL;
+ }
+ else {
+ mavSystemState = MAV_STATE_ACTIVE;
+ }
+ }
+ else if (areSensorsCalibrating()) {
+ mavSystemState = MAV_STATE_CALIBRATING;
+ }
+ else {
+ mavSystemState = MAV_STATE_STANDBY;
+ }
+
+ mavlink_msg_heartbeat_pack(mavSystemId, mavComponentId, &mavSendMsg,
+ mavSystemType,
+ mavlinkGetAutopilotEnum(),
+ mavModes,
+ mavCustomMode,
+ mavSystemState);
+
+ mavlinkSendMessage();
+}
+
+void mavlinkSendBatteryStatus(void)
+{
+ uint16_t batteryVoltages[MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_LEN];
+ uint16_t batteryVoltagesExt[MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_EXT_LEN];
+ memset(batteryVoltages, UINT16_MAX, sizeof(batteryVoltages));
+ memset(batteryVoltagesExt, 0, sizeof(batteryVoltagesExt));
+ if (feature(FEATURE_VBAT)) {
+ uint8_t batteryCellCount = getBatteryCellCount();
+ if (batteryCellCount > 0) {
+ for (int cell = 0; cell < batteryCellCount && cell < MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_LEN + MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_EXT_LEN; cell++) {
+ if (cell < MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_LEN) {
+ batteryVoltages[cell] = getBatteryAverageCellVoltage() * 10;
+ } else {
+ batteryVoltagesExt[cell - MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_LEN] = getBatteryAverageCellVoltage() * 10;
+ }
+ }
+ }
+ else {
+ batteryVoltages[0] = getBatteryVoltage() * 10;
+ }
+ }
+ else {
+ batteryVoltages[0] = 0;
+ }
+
+ mavlink_msg_battery_status_pack(mavSystemId, mavComponentId, &mavSendMsg,
+ 0,
+ MAV_BATTERY_FUNCTION_UNKNOWN,
+ MAV_BATTERY_TYPE_UNKNOWN,
+ INT16_MAX,
+ batteryVoltages,
+ isAmperageConfigured() ? getAmperage() : -1,
+ isAmperageConfigured() ? getMAhDrawn() : -1,
+ isAmperageConfigured() ? getMWhDrawn() * 36 : -1,
+ feature(FEATURE_VBAT) ? calculateBatteryPercentage() : -1,
+ 0,
+ 0,
+ batteryVoltagesExt,
+ 0,
+ 0);
+
+ mavlinkSendMessage();
+}
+
+void mavlinkSendScaledPressure(void)
+{
+ int16_t temperature;
+ sensors(SENSOR_BARO) ? getBaroTemperature(&temperature) : getIMUTemperature(&temperature);
+ mavlink_msg_scaled_pressure_pack(mavSystemId, mavComponentId, &mavSendMsg,
+ millis(),
+ 0,
+ 0,
+ temperature * 10,
+ 0);
+
+ mavlinkSendMessage();
+}
+
+void mavlinkSendSystemTime(void)
+{
+ mavlink_msg_system_time_pack(
+ mavSystemId,
+ mavComponentId,
+ &mavSendMsg,
+ 0,
+ millis());
+
+ mavlinkSendMessage();
+}
+
+bool mavlinkSendStatusText(void)
+{
+#ifdef USE_OSD
+ char buff[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN] = {" "};
+ textAttributes_t elemAttr = osdGetSystemMessage(buff, sizeof(buff), false);
+ if (buff[0] != SYM_BLANK) {
+ MAV_SEVERITY severity = MAV_SEVERITY_NOTICE;
+ if (TEXT_ATTRIBUTES_HAVE_BLINK(elemAttr)) {
+ severity = MAV_SEVERITY_CRITICAL;
+ } else if TEXT_ATTRIBUTES_HAVE_INVERTED(elemAttr) {
+ severity = MAV_SEVERITY_WARNING;
+ }
+
+ mavlink_msg_statustext_pack(mavSystemId, mavComponentId, &mavSendMsg,
+ (uint8_t)severity,
+ buff,
+ 0,
+ 0);
+
+ mavlinkSendMessage();
+ return true;
+ }
+#endif
+ return false;
+}
+
+void mavlinkSendBatteryTemperatureStatusText(void)
+{
+ mavlinkSendBatteryStatus();
+ mavlinkSendScaledPressure();
+ mavlinkSendStatusText();
+}
+
+static uint8_t mavlinkGetAutopilotEnum(void)
+{
+ if (mavAutopilotType == MAVLINK_AUTOPILOT_ARDUPILOT) {
+ return MAV_AUTOPILOT_ARDUPILOTMEGA;
+ }
+
+ return MAV_AUTOPILOT_GENERIC;
+}
+
+static uint8_t mavlinkHeadingDeg2FromCd(int32_t headingCd)
+{
+ return (uint8_t)(wrap_36000(headingCd) / 200);
+}
+
+static uint16_t mavlinkComputeHighLatencyFailures(void)
+{
+ uint16_t flags = 0;
+
+#if defined(USE_GPS)
+ if (!(sensors(SENSOR_GPS)
+#ifdef USE_GPS_FIX_ESTIMATION
+ || STATE(GPS_ESTIMATED_FIX)
+#endif
+ ) || gpsSol.fixType == GPS_NO_FIX) {
+ flags |= HL_FAILURE_FLAG_GPS;
+ }
+#endif
+
+#ifdef USE_PITOT
+ if (getHwPitotmeterStatus() != HW_SENSOR_OK) {
+ flags |= HL_FAILURE_FLAG_DIFFERENTIAL_PRESSURE;
+ }
+#endif
+
+ if (getHwBarometerStatus() != HW_SENSOR_OK) {
+ flags |= HL_FAILURE_FLAG_ABSOLUTE_PRESSURE;
+ }
+
+ if (getHwAccelerometerStatus() != HW_SENSOR_OK) {
+ flags |= HL_FAILURE_FLAG_3D_ACCEL;
+ }
+
+ if (getHwGyroStatus() != HW_SENSOR_OK) {
+ flags |= HL_FAILURE_FLAG_3D_GYRO;
+ }
+
+ if (getHwCompassStatus() != HW_SENSOR_OK) {
+ flags |= HL_FAILURE_FLAG_3D_MAG;
+ }
+
+ if (getHwRangefinderStatus() != HW_SENSOR_OK) {
+ flags |= HL_FAILURE_FLAG_TERRAIN;
+ }
+
+ const batteryState_e batteryState = getBatteryState();
+ if (batteryState == BATTERY_WARNING || batteryState == BATTERY_CRITICAL) {
+ flags |= HL_FAILURE_FLAG_BATTERY;
+ }
+
+ if (!rxIsReceivingSignal() || !rxAreFlightChannelsValid()) {
+ flags |= HL_FAILURE_FLAG_RC_RECEIVER;
+ }
+
+ return flags;
+}
+
+void mavlinkSendHighLatency2(timeUs_t currentTimeUs)
+{
+ const bool isPlane = (STATE(FIXED_WING_LEGACY) || mixerConfig()->platformType == PLATFORM_AIRPLANE);
+ const mavlinkModeSelection_t modeSelection = selectMavlinkMode(isPlane);
+
+ int32_t latitude = 0;
+ int32_t longitude = 0;
+ int16_t altitude = (int16_t)constrain((int32_t)(getEstimatedActualPosition(Z) / 100), INT16_MIN, INT16_MAX);
+ int16_t targetAltitude = (int16_t)constrain((int32_t)(posControl.desiredState.pos.z / 100), INT16_MIN, INT16_MAX);
+ uint16_t targetDistance = 0;
+ uint16_t wpNum = 0;
+ uint8_t heading = mavlinkHeadingDeg2FromCd(DECIDEGREES_TO_CENTIDEGREES(attitude.values.yaw));
+ uint8_t targetHeading = mavlinkHeadingDeg2FromCd(posControl.desiredState.yaw);
+ uint8_t groundspeed = 0;
+ uint8_t airspeed = 0;
+ uint8_t airspeedSp = 0;
+ uint8_t windspeed = 0;
+ uint8_t windHeading = 0;
+ uint8_t eph = UINT8_MAX;
+ uint8_t epv = UINT8_MAX;
+ int8_t temperatureAir = 0;
+ int8_t climbRate = (int8_t)constrain(lrintf(getEstimatedActualVelocity(Z) / 10.0f), INT8_MIN, INT8_MAX);
+ int8_t battery = feature(FEATURE_VBAT) ? (int8_t)calculateBatteryPercentage() : -1;
+
+#if defined(USE_GPS)
+ if (sensors(SENSOR_GPS)
+#ifdef USE_GPS_FIX_ESTIMATION
+ || STATE(GPS_ESTIMATED_FIX)
+#endif
+ ) {
+ latitude = gpsSol.llh.lat;
+ longitude = gpsSol.llh.lon;
+ altitude = (int16_t)constrain((int32_t)(gpsSol.llh.alt / 100), INT16_MIN, INT16_MAX);
+
+ const int32_t desiredAltCm = lrintf(posControl.desiredState.pos.z);
+ const int32_t targetAltCm = GPS_home.alt + desiredAltCm;
+ targetAltitude = (int16_t)constrain(targetAltCm / 100, INT16_MIN, INT16_MAX);
+
+ groundspeed = (uint8_t)constrain(lrintf(gpsSol.groundSpeed / 20.0f), 0, UINT8_MAX);
+
+ if (gpsSol.flags.validEPE) {
+ eph = (uint8_t)constrain((gpsSol.eph + 5) / 10, 0, UINT8_MAX);
+ epv = (uint8_t)constrain((gpsSol.epv + 5) / 10, 0, UINT8_MAX);
+ }
+
+ if (posControl.activeWaypointIndex >= 0) {
+ wpNum = (uint16_t)posControl.activeWaypointIndex;
+ targetDistance = (uint16_t)constrain(lrintf(posControl.wpDistance / 1000.0f), 0, UINT16_MAX);
+ }
+ }
+#endif
+
+#if defined(USE_PITOT)
+ if (sensors(SENSOR_PITOT) && pitotIsHealthy()) {
+ airspeed = (uint8_t)constrain(lrintf(getAirspeedEstimate() / 20.0f), 0, UINT8_MAX);
+ airspeedSp = airspeed;
+ }
+#endif
+
+ if (airspeedSp == 0) {
+ const float desiredVelXY = calc_length_pythagorean_2D(posControl.desiredState.vel.x, posControl.desiredState.vel.y);
+ airspeedSp = (uint8_t)constrain(lrintf(desiredVelXY / 20.0f), 0, UINT8_MAX);
+ }
+
+ if (airspeed == 0) {
+ airspeed = groundspeed;
+ }
+
+#ifdef USE_WIND_ESTIMATOR
+ if (isEstimatedWindSpeedValid()) {
+ uint16_t windAngleCd = 0;
+ const float windHoriz = getEstimatedHorizontalWindSpeed(&windAngleCd);
+ windspeed = (uint8_t)constrain(lrintf(windHoriz / 20.0f), 0, UINT8_MAX);
+ windHeading = mavlinkHeadingDeg2FromCd(windAngleCd);
+ }
+#endif
+
+ int16_t temperature;
+ sensors(SENSOR_BARO) ? getBaroTemperature(&temperature) : getIMUTemperature(&temperature);
+ temperatureAir = (int8_t)constrain(temperature, INT8_MIN, INT8_MAX);
+
+ const uint16_t failureFlags = mavlinkComputeHighLatencyFailures();
+
+ mavlink_msg_high_latency2_pack(
+ mavSystemId,
+ mavComponentId,
+ &mavSendMsg,
+ (uint32_t)(currentTimeUs / 1000),
+ mavlinkGetVehicleType(),
+ mavlinkGetAutopilotEnum(),
+ modeSelection.customMode,
+ latitude,
+ longitude,
+ altitude,
+ targetAltitude,
+ heading,
+ targetHeading,
+ targetDistance,
+ (uint8_t)constrain(getThrottlePercent(osdUsingScaledThrottle()), 0, 100),
+ airspeed,
+ airspeedSp,
+ groundspeed,
+ windspeed,
+ windHeading,
+ eph,
+ epv,
+ temperatureAir,
+ climbRate,
+ battery,
+ wpNum,
+ failureFlags,
+ 0,
+ 0,
+ 0);
+
+ mavlinkSendMessage();
+}
+
+bool mavlinkSendRequestedMessage(uint16_t messageId)
+{
+ switch (messageId) {
+ case MAVLINK_MSG_ID_HEARTBEAT:
+ mavlinkSendHeartbeat();
+ return true;
+ case MAVLINK_MSG_ID_AUTOPILOT_VERSION:
+ if (mavlinkGetProtocolVersion() != 1) {
+ mavlinkSendAutopilotVersion();
+ return true;
+ }
+ return false;
+ case MAVLINK_MSG_ID_PROTOCOL_VERSION:
+ if (mavlinkGetProtocolVersion() != 1) {
+ mavlinkSendProtocolVersion();
+ return true;
+ }
+ return false;
+ case MAVLINK_MSG_ID_SYS_STATUS:
+ mavlinkSendSystemStatus();
+ return true;
+ case MAVLINK_MSG_ID_ATTITUDE:
+ mavlinkSendAttitude();
+ return true;
+ case MAVLINK_MSG_ID_VFR_HUD:
+ mavlinkSendVfrHud();
+ return true;
+ case MAVLINK_MSG_ID_AVAILABLE_MODES:
+ {
+ const bool isPlane = mixerConfig()->platformType == PLATFORM_AIRPLANE || STATE(FIXED_WING_LEGACY);
+ const mavlinkModeSelection_t modeSelection = selectMavlinkMode(isPlane);
+ if (isPlane) {
+ mavlinkSendAvailableModes(planeModes, (uint8_t)ARRAYLEN(planeModes), modeSelection.customMode, mavlinkPlaneModeIsConfigured);
+ } else {
+ mavlinkSendAvailableModes(copterModes, (uint8_t)ARRAYLEN(copterModes), modeSelection.customMode, mavlinkCopterModeIsConfigured);
+ }
+ return true;
+ }
+ case MAVLINK_MSG_ID_CURRENT_MODE:
+ {
+ const bool isPlane = mixerConfig()->platformType == PLATFORM_AIRPLANE || STATE(FIXED_WING_LEGACY);
+ const mavlinkModeSelection_t modeSelection = selectMavlinkMode(isPlane);
+ mavlink_msg_current_mode_pack(
+ mavSystemId,
+ mavComponentId,
+ &mavSendMsg,
+ MAV_STANDARD_MODE_NON_STANDARD,
+ modeSelection.customMode,
+ modeSelection.customMode);
+ mavlinkSendMessage();
+ return true;
+ }
+ case MAVLINK_MSG_ID_EXTENDED_SYS_STATE:
+ mavlinkSendExtendedSysState();
+ return true;
+ case MAVLINK_MSG_ID_RC_CHANNELS:
+ case MAVLINK_MSG_ID_RC_CHANNELS_RAW:
+ case MAVLINK_MSG_ID_RC_CHANNELS_SCALED:
+ mavlinkSendRCChannelsAndRSSI();
+ return true;
+#ifdef USE_GPS
+ case MAVLINK_MSG_ID_GPS_RAW_INT:
+ mavlinkSendGpsRawInt(micros());
+ return true;
+ case MAVLINK_MSG_ID_GLOBAL_POSITION_INT:
+ mavlinkSendGlobalPositionInt(micros());
+ return true;
+ case MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN:
+ mavlinkSendGpsGlobalOrigin();
+ return true;
+ case MAVLINK_MSG_ID_HOME_POSITION:
+ if (STATE(GPS_FIX_HOME)) {
+ mavlinkSendHomePosition();
+ return true;
+ }
+ return false;
+#endif
+ case MAVLINK_MSG_ID_BATTERY_STATUS:
+ mavlinkSendBatteryStatus();
+ return true;
+ case MAVLINK_MSG_ID_SCALED_PRESSURE:
+ mavlinkSendScaledPressure();
+ return true;
+ case MAVLINK_MSG_ID_SYSTEM_TIME:
+ mavlinkSendSystemTime();
+ return true;
+ case MAVLINK_MSG_ID_STATUSTEXT:
+ return mavlinkSendStatusText();
+ default:
+ return false;
+ }
+}
+
void processMAVLinkTelemetry(timeUs_t currentTimeUs)
{
if (mavActivePort->highLatencyEnabled && mavlinkGetProtocolVersion() != 1) {
diff --git a/src/main/mavlink/mavlink_streams.h b/src/main/mavlink/mavlink_streams.h
index e3ffc467ef5..514a8e01c38 100644
--- a/src/main/mavlink/mavlink_streams.h
+++ b/src/main/mavlink/mavlink_streams.h
@@ -6,6 +6,9 @@
extern const uint8_t mavSecondaryRates[MAVLINK_STREAM_COUNT];
+void mavlinkSendAutopilotVersion(void);
+void mavlinkSendProtocolVersion(void);
+bool mavlinkSendRequestedMessage(uint16_t messageId);
uint8_t mavlinkClampStreamRate(uint8_t rate);
int32_t mavlinkRateToIntervalUs(uint8_t rate);
bool mavlinkPeriodicMessageFromMessageId(uint16_t messageId, mavlinkPeriodicMessage_e *periodicMessage);
diff --git a/src/main/mavlink/mavlink_types.h b/src/main/mavlink/mavlink_types.h
index 09f21dc99ed..c050d319392 100644
--- a/src/main/mavlink/mavlink_types.h
+++ b/src/main/mavlink/mavlink_types.h
@@ -171,11 +171,6 @@ typedef struct mavlinkModeDescriptor_s {
const char *name;
} mavlinkModeDescriptor_t;
-extern const mavlinkModeDescriptor_t planeModes[];
-extern const uint8_t planeModesCount;
-extern const mavlinkModeDescriptor_t copterModes[];
-extern const uint8_t copterModesCount;
-
typedef struct mavlinkMissionItemData_s {
uint8_t frame;
uint16_t command;
From afa34e0b0d165276fe763ab47db36e75729acce1 Mon Sep 17 00:00:00 2001
From: frogmane <7685285+xznhj8129@users.noreply.github.com>
Date: Fri, 3 Apr 2026 18:23:19 -0400
Subject: [PATCH 37/46] Split MAVLink modes and mission helpers
---
src/main/CMakeLists.txt | 4 +
src/main/fc/fc_mavlink.c | 665 +----------------------------
src/main/mavlink/mavlink_mission.c | 621 +++++++++++++++++++++++++++
src/main/mavlink/mavlink_mission.h | 42 ++
src/main/mavlink/mavlink_modes.c | 295 +++++++++++++
src/main/mavlink/mavlink_modes.h | 82 ++++
src/main/mavlink/mavlink_streams.c | 298 +------------
src/main/mavlink/mavlink_types.h | 89 ----
src/test/unit/CMakeLists.txt | 2 +-
9 files changed, 1061 insertions(+), 1037 deletions(-)
create mode 100644 src/main/mavlink/mavlink_mission.c
create mode 100644 src/main/mavlink/mavlink_mission.h
create mode 100644 src/main/mavlink/mavlink_modes.c
create mode 100644 src/main/mavlink/mavlink_modes.h
diff --git a/src/main/CMakeLists.txt b/src/main/CMakeLists.txt
index 4fff0f3bf35..29e98de4da1 100755
--- a/src/main/CMakeLists.txt
+++ b/src/main/CMakeLists.txt
@@ -394,6 +394,10 @@ main_sources(COMMON_SRC
io/osd/custom_elements.c
mavlink/mavlink_internal.h
+ mavlink/mavlink_mission.c
+ mavlink/mavlink_mission.h
+ mavlink/mavlink_modes.c
+ mavlink/mavlink_modes.h
mavlink/mavlink_types.h
mavlink/mavlink_ports.c
mavlink/mavlink_ports.h
diff --git a/src/main/fc/fc_mavlink.c b/src/main/fc/fc_mavlink.c
index 503bc75ed43..1d413bf7e08 100644
--- a/src/main/fc/fc_mavlink.c
+++ b/src/main/fc/fc_mavlink.c
@@ -2,6 +2,7 @@
#include "fc/fc_mavlink.h"
+#include "mavlink/mavlink_mission.h"
#include "mavlink/mavlink_runtime.h"
#include "mavlink/mavlink_streams.h"
@@ -140,590 +141,6 @@ static bool handleIncoming_TUNNEL(uint8_t ingressPortIndex)
return handled;
}
-static bool mavlinkFrameIsSupported(uint8_t frame, mavFrameSupportMask_e allowedMask)
-{
- switch (frame) {
- case MAV_FRAME_GLOBAL:
- return allowedMask & MAV_FRAME_SUPPORTED_GLOBAL;
- case MAV_FRAME_GLOBAL_INT:
- return allowedMask & MAV_FRAME_SUPPORTED_GLOBAL_INT;
- case MAV_FRAME_GLOBAL_RELATIVE_ALT:
- return allowedMask & MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT;
- case MAV_FRAME_GLOBAL_RELATIVE_ALT_INT:
- return allowedMask & MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT_INT;
- default:
- return false;
- }
-}
-
-static bool mavlinkFrameUsesAbsoluteAltitude(uint8_t frame)
-{
- return frame == MAV_FRAME_GLOBAL || frame == MAV_FRAME_GLOBAL_INT;
-}
-
-static MAV_RESULT mavlinkSetAltitudeTargetFromFrame(uint8_t frame, float altitudeMeters)
-{
-#ifdef USE_BARO
- geoAltitudeDatumFlag_e datum;
-
- switch (frame) {
- case MAV_FRAME_GLOBAL:
- case MAV_FRAME_GLOBAL_INT:
- datum = NAV_WP_MSL_DATUM;
- break;
- case MAV_FRAME_GLOBAL_RELATIVE_ALT:
- case MAV_FRAME_GLOBAL_RELATIVE_ALT_INT:
- datum = NAV_WP_TAKEOFF_DATUM;
- break;
- default:
- return MAV_RESULT_UNSUPPORTED;
- }
-
- const int32_t targetAltitudeCm = (int32_t)lrintf(altitudeMeters * 100.0f);
- return navigationSetAltitudeTargetWithDatum(datum, targetAltitudeCm) ? MAV_RESULT_ACCEPTED : MAV_RESULT_DENIED;
-#else
- UNUSED(frame);
- UNUSED(altitudeMeters);
- return MAV_RESULT_UNSUPPORTED;
-#endif
-}
-
-static MAV_MISSION_RESULT mavlinkMissionResultFromCommandResult(MAV_RESULT result)
-{
- switch (result) {
- case MAV_RESULT_ACCEPTED:
- return MAV_MISSION_ACCEPTED;
- case MAV_RESULT_UNSUPPORTED:
- return MAV_MISSION_UNSUPPORTED;
- default:
- return MAV_MISSION_ERROR;
- }
-}
-
-static bool mavlinkHandleArmedGuidedMissionItem(uint8_t current, uint8_t frame, mavFrameSupportMask_e allowedFrames, int32_t latitudeE7, int32_t longitudeE7, float altitudeMeters)
-{
- if (!isGCSValid()) {
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg,
- mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid,
- MAV_MISSION_ERROR, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
- return true;
- }
-
- if (!mavlinkFrameIsSupported(frame, allowedFrames)) {
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg,
- mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid,
- MAV_MISSION_UNSUPPORTED_FRAME, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
- return true;
- }
-
- if (current == 2) {
- navWaypoint_t wp = {0};
- wp.action = NAV_WP_ACTION_WAYPOINT;
- wp.lat = latitudeE7;
- wp.lon = longitudeE7;
- wp.alt = (int32_t)lrintf(altitudeMeters * 100.0f);
- wp.p3 = mavlinkFrameUsesAbsoluteAltitude(frame) ? NAV_WP_ALTMODE : 0;
-
- setWaypoint(255, &wp);
-
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg,
- mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid,
- MAV_MISSION_ACCEPTED, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
- return true;
- }
-
- if (current == 3) {
- const MAV_RESULT result = mavlinkSetAltitudeTargetFromFrame(frame, altitudeMeters);
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg,
- mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid,
- mavlinkMissionResultFromCommandResult(result), MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
- return true;
- }
-
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg,
- mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid,
- MAV_MISSION_ERROR, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
- return true;
-}
-
-static uint8_t navWaypointFrame(const navWaypoint_t *wp, bool useIntMessages)
-{
- switch (wp->action) {
- case NAV_WP_ACTION_RTH:
- case NAV_WP_ACTION_JUMP:
- case NAV_WP_ACTION_SET_HEAD:
- return MAV_FRAME_MISSION;
- default:
- break;
- }
-
- const bool absoluteAltitude = (wp->p3 & NAV_WP_ALTMODE) == NAV_WP_ALTMODE;
-
- if (absoluteAltitude) {
- return useIntMessages ? MAV_FRAME_GLOBAL_INT : MAV_FRAME_GLOBAL;
- }
-
- return useIntMessages ? MAV_FRAME_GLOBAL_RELATIVE_ALT_INT : MAV_FRAME_GLOBAL_RELATIVE_ALT;
-}
-
-static void mavlinkResetIncomingMissionTransaction(void);
-
-static bool handleIncoming_MISSION_CLEAR_ALL(void)
-{
- mavlink_mission_clear_all_t msg;
- mavlink_msg_mission_clear_all_decode(&mavlinkContext.recvMsg, &msg);
-
- // Check if this message is for us
- if (msg.target_system == mavSystemId) {
- resetWaypointList();
- mavlinkResetIncomingMissionTransaction();
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_ACCEPTED, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
- return true;
- }
-
- return false;
-}
-
-static void mavlinkResetIncomingMissionTransaction(void)
-{
- incomingMissionWpCount = 0;
- incomingMissionWpSequence = 0;
- incomingMissionSourceSystem = 0;
- incomingMissionSourceComponent = 0;
- incomingMissionLastActivityMs = 0;
-}
-
-static void mavlinkStartIncomingMissionTransaction(int missionCount)
-{
- incomingMissionWpCount = missionCount;
- incomingMissionWpSequence = 0;
- incomingMissionSourceSystem = mavlinkContext.recvMsg.sysid;
- incomingMissionSourceComponent = mavlinkContext.recvMsg.compid;
- incomingMissionLastActivityMs = millis();
-}
-
-static void mavlinkTouchIncomingMissionTransaction(void)
-{
- incomingMissionLastActivityMs = millis();
-}
-
-static bool mavlinkIsIncomingMissionTransactionActive(void)
-{
- if (incomingMissionWpCount <= 0) {
- return false;
- }
-
- if ((timeMs_t)(millis() - incomingMissionLastActivityMs) > MAVLINK_MISSION_UPLOAD_TIMEOUT_MS) {
- mavlinkResetIncomingMissionTransaction();
- return false;
- }
-
- return true;
-}
-
-static bool mavlinkIsIncomingMissionTransactionOwner(void)
-{
- return mavlinkContext.recvMsg.sysid == incomingMissionSourceSystem &&
- mavlinkContext.recvMsg.compid == incomingMissionSourceComponent;
-}
-
-static bool mavlinkHandleMissionItemCommon(bool useIntMessages, uint8_t frame, uint16_t command, uint8_t autocontinue, uint16_t seq, float param1, float param2, float param3, float param4, int32_t lat, int32_t lon, float altMeters)
-{
- if (!mavlinkIsIncomingMissionTransactionActive() || !mavlinkIsIncomingMissionTransactionOwner()) {
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_INVALID_SEQUENCE, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
- return true;
- }
-
- mavlinkTouchIncomingMissionTransaction();
-
- const bool lastMissionItem = incomingMissionWpCount > 0 && ((int)seq + 1 >= incomingMissionWpCount);
-
- if (autocontinue == 0 && !lastMissionItem) {
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_UNSUPPORTED, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
- return true;
- }
-
- UNUSED(param3);
-
- navWaypoint_t wp;
- memset(&wp, 0, sizeof(wp));
-
- switch (command) {
- case MAV_CMD_NAV_WAYPOINT:
- if (!mavlinkFrameIsSupported(frame,
- MAV_FRAME_SUPPORTED_GLOBAL |
- MAV_FRAME_SUPPORTED_GLOBAL_INT |
- MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT |
- MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT_INT)) {
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_UNSUPPORTED_FRAME, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
- return true;
- }
- wp.action = NAV_WP_ACTION_WAYPOINT;
- wp.lat = lat;
- wp.lon = lon;
- wp.alt = (int32_t)(altMeters * 100.0f);
- wp.p1 = 0;
- wp.p2 = 0;
- wp.p3 = mavlinkFrameUsesAbsoluteAltitude(frame) ? NAV_WP_ALTMODE : 0;
- break;
-
- case MAV_CMD_NAV_LOITER_TIME:
- if (!mavlinkFrameIsSupported(frame,
- MAV_FRAME_SUPPORTED_GLOBAL |
- MAV_FRAME_SUPPORTED_GLOBAL_INT |
- MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT |
- MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT_INT)) {
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_UNSUPPORTED_FRAME, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
- return true;
- }
- wp.action = NAV_WP_ACTION_HOLD_TIME;
- wp.lat = lat;
- wp.lon = lon;
- wp.alt = (int32_t)(altMeters * 100.0f);
- wp.p1 = (int16_t)lrintf(param1);
- wp.p2 = 0;
- wp.p3 = mavlinkFrameUsesAbsoluteAltitude(frame) ? NAV_WP_ALTMODE : 0;
- break;
-
- case MAV_CMD_NAV_RETURN_TO_LAUNCH:
- {
- const bool coordinateFrame = mavlinkFrameIsSupported(frame,
- MAV_FRAME_SUPPORTED_GLOBAL |
- MAV_FRAME_SUPPORTED_GLOBAL_INT |
- MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT |
- MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT_INT);
-
- if (!coordinateFrame && frame != MAV_FRAME_MISSION) {
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_UNSUPPORTED_FRAME, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
- return true;
- }
- wp.action = NAV_WP_ACTION_RTH;
- wp.lat = 0;
- wp.lon = 0;
- wp.alt = coordinateFrame ? (int32_t)(altMeters * 100.0f) : 0;
- wp.p1 = 0; // Land if non-zero
- wp.p2 = 0;
- wp.p3 = mavlinkFrameUsesAbsoluteAltitude(frame) ? NAV_WP_ALTMODE : 0;
- break;
- }
-
- case MAV_CMD_NAV_LAND:
- if (!mavlinkFrameIsSupported(frame,
- MAV_FRAME_SUPPORTED_GLOBAL |
- MAV_FRAME_SUPPORTED_GLOBAL_INT |
- MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT |
- MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT_INT)) {
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_UNSUPPORTED_FRAME, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
- return true;
- }
- wp.action = NAV_WP_ACTION_LAND;
- wp.lat = lat;
- wp.lon = lon;
- wp.alt = (int32_t)(altMeters * 100.0f);
- wp.p1 = 0; // Speed (cm/s)
- wp.p2 = 0; // Elevation Adjustment (m): P2 defines the ground elevation (in metres) for the LAND WP. If the altitude mode is absolute, this is also absolute; for relative altitude, then it is the difference between the assumed home location and the LAND WP.
- wp.p3 = mavlinkFrameUsesAbsoluteAltitude(frame) ? NAV_WP_ALTMODE : 0; // Altitude Mode & Actions, P3 defines the altitude mode. 0 (default, legacy) = Relative to Home, 1 = Absolute (AMSL).
- break;
-
- case MAV_CMD_DO_JUMP:
- if (frame != MAV_FRAME_MISSION) {
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_UNSUPPORTED_FRAME, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
- return true;
- }
- if (param1 < 0.0f) {
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_UNSUPPORTED, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
- return true;
- }
- wp.lat = 0;
- wp.lon = 0;
- wp.alt = 0;
- wp.action = NAV_WP_ACTION_JUMP;
- wp.p1 = (int16_t)lrintf(param1 + 1.0f);
- wp.p2 = (int16_t)lrintf(param2);
- wp.p3 = 0;
- break;
-
- case MAV_CMD_DO_SET_ROI:
- if (param1 != MAV_ROI_LOCATION ||
- !mavlinkFrameIsSupported(frame,
- MAV_FRAME_SUPPORTED_GLOBAL |
- MAV_FRAME_SUPPORTED_GLOBAL_INT |
- MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT |
- MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT_INT)) {
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_UNSUPPORTED, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
- return true;
- }
- wp.action = NAV_WP_ACTION_SET_POI;
- wp.lat = lat;
- wp.lon = lon;
- wp.alt = (int32_t)(altMeters * 100.0f);
- wp.p1 = 0;
- wp.p2 = 0;
- wp.p3 = mavlinkFrameUsesAbsoluteAltitude(frame) ? NAV_WP_ALTMODE : 0;
- break;
-
- case MAV_CMD_CONDITION_YAW:
- if (frame != MAV_FRAME_MISSION) {
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_UNSUPPORTED_FRAME, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
- return true;
- }
- if (param4 != 0.0f) {
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_UNSUPPORTED, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
- return true;
- }
- wp.lat = 0;
- wp.lon = 0;
- wp.alt = 0;
- wp.action = NAV_WP_ACTION_SET_HEAD;
- wp.p1 = (int16_t)lrintf(param1);
- wp.p2 = 0;
- wp.p3 = 0;
- break;
-
- default:
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_UNSUPPORTED, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
- return true;
- }
-
- if (seq == incomingMissionWpSequence) {
- incomingMissionWpSequence++;
-
- wp.flag = (incomingMissionWpSequence >= incomingMissionWpCount) ? NAV_WP_FLAG_LAST : 0;
-
- setWaypoint(incomingMissionWpSequence, &wp);
-
- if (incomingMissionWpSequence >= incomingMissionWpCount) {
- if (isWaypointListValid()) {
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_ACCEPTED, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
- }
- else {
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_INVALID, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
- }
- mavlinkResetIncomingMissionTransaction();
- }
- else {
- if (useIntMessages) {
- mavlink_msg_mission_request_int_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, incomingMissionWpSequence, MAV_MISSION_TYPE_MISSION);
- } else {
- mavlink_msg_mission_request_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, incomingMissionWpSequence, MAV_MISSION_TYPE_MISSION);
- }
- mavlinkSendMessage();
- }
- }
- else {
- // If we get a duplicate of the last accepted item, re-request the next one instead of aborting.
- if (seq + 1 == incomingMissionWpSequence) {
- mavlinkTouchIncomingMissionTransaction();
- if (useIntMessages) {
- mavlink_msg_mission_request_int_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, incomingMissionWpSequence, MAV_MISSION_TYPE_MISSION);
- } else {
- mavlink_msg_mission_request_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, incomingMissionWpSequence, MAV_MISSION_TYPE_MISSION);
- }
- mavlinkSendMessage();
- } else {
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_INVALID_SEQUENCE, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
- }
- }
-
- return true;
-}
-
-static bool handleIncoming_MISSION_COUNT(void)
-{
- mavlink_mission_count_t msg;
- mavlink_msg_mission_count_decode(&mavlinkContext.recvMsg, &msg);
-
- // Check if this message is for us
- if (msg.target_system == mavSystemId) {
- mavlinkResetIncomingMissionTransaction();
- if (ARMING_FLAG(ARMED)) {
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_ERROR, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
- return true;
- }
- if (msg.count == 0) {
- resetWaypointList();
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_ACCEPTED, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
- return true;
- }
- if (msg.count <= NAV_MAX_WAYPOINTS) {
- mavlinkStartIncomingMissionTransaction(msg.count);
- mavlink_msg_mission_request_int_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, incomingMissionWpSequence, MAV_MISSION_TYPE_MISSION);
- mavlinkSendMessage();
- return true;
- } else {
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_NO_SPACE, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
- return true;
- }
- }
-
- return false;
-}
-
-static bool handleIncoming_MISSION_ITEM(void)
-{
- mavlink_mission_item_t msg;
- mavlink_msg_mission_item_decode(&mavlinkContext.recvMsg, &msg);
-
- if (msg.target_system != mavSystemId) {
- return false;
- }
-
- if (ARMING_FLAG(ARMED)) {
- if (msg.command == MAV_CMD_NAV_WAYPOINT) {
- return mavlinkHandleArmedGuidedMissionItem(msg.current, msg.frame,
- MAV_FRAME_SUPPORTED_GLOBAL | MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT,
- (int32_t)lrintf(msg.x * 1e7f), (int32_t)lrintf(msg.y * 1e7f), msg.z);
- }
-
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_ERROR, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
- return true;
- }
-
- return mavlinkHandleMissionItemCommon(false, msg.frame, msg.command, msg.autocontinue, msg.seq, msg.param1, msg.param2, msg.param3, msg.param4, (int32_t)(msg.x * 1e7f), (int32_t)(msg.y * 1e7f), msg.z);
-}
-
-static bool handleIncoming_MISSION_REQUEST_LIST(void)
-{
- mavlink_mission_request_list_t msg;
- mavlink_msg_mission_request_list_decode(&mavlinkContext.recvMsg, &msg);
-
- // Check if this message is for us
- if (msg.target_system == mavSystemId) {
- mavlink_msg_mission_count_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, getWaypointCount(), MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
- return true;
- }
-
- return false;
-}
-
-static bool fillMavlinkMissionItemFromWaypoint(const navWaypoint_t *wp, bool useIntMessages, mavlinkMissionItemData_t *item)
-{
- mavlinkMissionItemData_t data = {0};
-
- data.frame = navWaypointFrame(wp, useIntMessages);
-
- switch (wp->action) {
- case NAV_WP_ACTION_WAYPOINT:
- data.command = MAV_CMD_NAV_WAYPOINT;
- data.lat = wp->lat;
- data.lon = wp->lon;
- data.alt = wp->alt / 100.0f;
- break;
-
- case NAV_WP_ACTION_HOLD_TIME:
- data.command = MAV_CMD_NAV_LOITER_TIME;
- data.param1 = wp->p1;
- data.lat = wp->lat;
- data.lon = wp->lon;
- data.alt = wp->alt / 100.0f;
- break;
-
- case NAV_WP_ACTION_RTH:
- data.command = MAV_CMD_NAV_RETURN_TO_LAUNCH;
- break;
-
- case NAV_WP_ACTION_LAND:
- data.command = MAV_CMD_NAV_LAND;
- data.lat = wp->lat;
- data.lon = wp->lon;
- data.alt = wp->alt / 100.0f;
- break;
-
- case NAV_WP_ACTION_JUMP:
- data.command = MAV_CMD_DO_JUMP;
- data.param1 = (wp->p1 > 0) ? (float)(wp->p1 - 1) : 0.0f;
- data.param2 = wp->p2;
- break;
-
- case NAV_WP_ACTION_SET_POI:
- data.command = MAV_CMD_DO_SET_ROI;
- data.param1 = MAV_ROI_LOCATION;
- data.lat = wp->lat;
- data.lon = wp->lon;
- data.alt = wp->alt / 100.0f;
- break;
-
- case NAV_WP_ACTION_SET_HEAD:
- data.command = MAV_CMD_CONDITION_YAW;
- data.param1 = wp->p1;
- break;
-
- default:
- return false;
- }
-
- *item = data;
- return true;
-}
-
-static bool handleIncoming_MISSION_REQUEST(void)
-{
- mavlink_mission_request_t msg;
- mavlink_msg_mission_request_decode(&mavlinkContext.recvMsg, &msg);
-
- if (msg.target_system != mavSystemId) {
- return false;
- }
-
- int wpCount = getWaypointCount();
-
- if (msg.seq < wpCount) {
- navWaypoint_t wp;
- getWaypoint(msg.seq + 1, &wp);
-
- mavlinkMissionItemData_t item;
- if (fillMavlinkMissionItemFromWaypoint(&wp, false, &item)) {
- mavlink_msg_mission_item_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid,
- msg.seq,
- item.frame,
- item.command,
- 0,
- 1,
- item.param1, item.param2, item.param3, item.param4,
- item.lat / 1e7f,
- item.lon / 1e7f,
- item.alt,
- MAV_MISSION_TYPE_MISSION);
- mavlinkSendMessage();
- } else {
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_ERROR, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
- }
- }
- else {
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_INVALID_SEQUENCE, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
- }
-
- return true;
-}
-
static bool mavlinkIsLocalTarget(uint8_t targetSystem, uint8_t targetComponent)
{
if (targetSystem != 0 && targetSystem != mavSystemId) {
@@ -946,72 +363,6 @@ static bool handleIncoming_COMMAND_LONG(void)
return handleIncoming_COMMAND(msg.target_system, msg.target_component, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, msg.command, MAV_FRAME_GLOBAL, msg.param1, msg.param2, msg.param3, msg.param4, msg.param5, msg.param6, msg.param7);
}
-static bool handleIncoming_MISSION_ITEM_INT(void)
-{
- mavlink_mission_item_int_t msg;
- mavlink_msg_mission_item_int_decode(&mavlinkContext.recvMsg, &msg);
-
- if (msg.target_system != mavSystemId) {
- return false;
- }
-
- if (ARMING_FLAG(ARMED)) {
- if (msg.command == MAV_CMD_NAV_WAYPOINT) {
- return mavlinkHandleArmedGuidedMissionItem(msg.current, msg.frame,
- MAV_FRAME_SUPPORTED_GLOBAL_INT | MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT_INT,
- msg.x, msg.y, msg.z);
- }
-
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_ERROR, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
- return true;
- }
-
- return mavlinkHandleMissionItemCommon(true, msg.frame, msg.command, msg.autocontinue, msg.seq, msg.param1, msg.param2, msg.param3, msg.param4, msg.x, msg.y, msg.z);
-}
-
-static bool handleIncoming_MISSION_REQUEST_INT(void)
-{
- mavlink_mission_request_int_t msg;
- mavlink_msg_mission_request_int_decode(&mavlinkContext.recvMsg, &msg);
-
- if (msg.target_system != mavSystemId) {
- return false;
- }
-
- int wpCount = getWaypointCount();
-
- if (msg.seq < wpCount) {
- navWaypoint_t wp;
- getWaypoint(msg.seq + 1, &wp);
-
- mavlinkMissionItemData_t item;
- if (fillMavlinkMissionItemFromWaypoint(&wp, true, &item)) {
- mavlink_msg_mission_item_int_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid,
- msg.seq,
- item.frame,
- item.command,
- 0,
- 1,
- item.param1, item.param2, item.param3, item.param4,
- item.lat,
- item.lon,
- item.alt,
- MAV_MISSION_TYPE_MISSION);
- mavlinkSendMessage();
- } else {
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_ERROR, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
- }
- }
- else {
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_INVALID_SEQUENCE, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
- }
-
- return true;
-}
-
static bool handleIncoming_REQUEST_DATA_STREAM(void)
{
mavlink_request_data_stream_t msg;
@@ -1244,23 +595,23 @@ mavlinkFcDispatchResult_e mavlinkFcDispatchIncomingMessage(uint8_t ingressPortIn
case MAVLINK_MSG_ID_PARAM_REQUEST_LIST:
return handleIncoming_PARAM_REQUEST_LIST() ? MAVLINK_FC_DISPATCH_HANDLED_ACTIVITY : MAVLINK_FC_DISPATCH_NOT_HANDLED;
case MAVLINK_MSG_ID_MISSION_CLEAR_ALL:
- return handleIncoming_MISSION_CLEAR_ALL() ? MAVLINK_FC_DISPATCH_HANDLED_ACTIVITY : MAVLINK_FC_DISPATCH_NOT_HANDLED;
+ return mavlinkHandleIncomingMissionClearAll() ? MAVLINK_FC_DISPATCH_HANDLED_ACTIVITY : MAVLINK_FC_DISPATCH_NOT_HANDLED;
case MAVLINK_MSG_ID_MISSION_COUNT:
- return handleIncoming_MISSION_COUNT() ? MAVLINK_FC_DISPATCH_HANDLED_ACTIVITY : MAVLINK_FC_DISPATCH_NOT_HANDLED;
+ return mavlinkHandleIncomingMissionCount() ? MAVLINK_FC_DISPATCH_HANDLED_ACTIVITY : MAVLINK_FC_DISPATCH_NOT_HANDLED;
case MAVLINK_MSG_ID_MISSION_ITEM:
- return handleIncoming_MISSION_ITEM() ? MAVLINK_FC_DISPATCH_HANDLED_ACTIVITY : MAVLINK_FC_DISPATCH_NOT_HANDLED;
+ return mavlinkHandleIncomingMissionItem() ? MAVLINK_FC_DISPATCH_HANDLED_ACTIVITY : MAVLINK_FC_DISPATCH_NOT_HANDLED;
case MAVLINK_MSG_ID_MISSION_ITEM_INT:
- return handleIncoming_MISSION_ITEM_INT() ? MAVLINK_FC_DISPATCH_HANDLED_ACTIVITY : MAVLINK_FC_DISPATCH_NOT_HANDLED;
+ return mavlinkHandleIncomingMissionItemInt() ? MAVLINK_FC_DISPATCH_HANDLED_ACTIVITY : MAVLINK_FC_DISPATCH_NOT_HANDLED;
case MAVLINK_MSG_ID_MISSION_REQUEST_LIST:
- return handleIncoming_MISSION_REQUEST_LIST() ? MAVLINK_FC_DISPATCH_HANDLED_ACTIVITY : MAVLINK_FC_DISPATCH_NOT_HANDLED;
+ return mavlinkHandleIncomingMissionRequestList() ? MAVLINK_FC_DISPATCH_HANDLED_ACTIVITY : MAVLINK_FC_DISPATCH_NOT_HANDLED;
case MAVLINK_MSG_ID_COMMAND_LONG:
return handleIncoming_COMMAND_LONG() ? MAVLINK_FC_DISPATCH_HANDLED_ACTIVITY : MAVLINK_FC_DISPATCH_NOT_HANDLED;
case MAVLINK_MSG_ID_COMMAND_INT:
return handleIncoming_COMMAND_INT() ? MAVLINK_FC_DISPATCH_HANDLED_ACTIVITY : MAVLINK_FC_DISPATCH_NOT_HANDLED;
case MAVLINK_MSG_ID_MISSION_REQUEST:
- return handleIncoming_MISSION_REQUEST() ? MAVLINK_FC_DISPATCH_HANDLED_ACTIVITY : MAVLINK_FC_DISPATCH_NOT_HANDLED;
+ return mavlinkHandleIncomingMissionRequest() ? MAVLINK_FC_DISPATCH_HANDLED_ACTIVITY : MAVLINK_FC_DISPATCH_NOT_HANDLED;
case MAVLINK_MSG_ID_MISSION_REQUEST_INT:
- return handleIncoming_MISSION_REQUEST_INT() ? MAVLINK_FC_DISPATCH_HANDLED_ACTIVITY : MAVLINK_FC_DISPATCH_NOT_HANDLED;
+ return mavlinkHandleIncomingMissionRequestInt() ? MAVLINK_FC_DISPATCH_HANDLED_ACTIVITY : MAVLINK_FC_DISPATCH_NOT_HANDLED;
case MAVLINK_MSG_ID_REQUEST_DATA_STREAM:
return handleIncoming_REQUEST_DATA_STREAM() ? MAVLINK_FC_DISPATCH_HANDLED_ACTIVITY : MAVLINK_FC_DISPATCH_NOT_HANDLED;
case MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE:
diff --git a/src/main/mavlink/mavlink_mission.c b/src/main/mavlink/mavlink_mission.c
new file mode 100644
index 00000000000..6ed125c3060
--- /dev/null
+++ b/src/main/mavlink/mavlink_mission.c
@@ -0,0 +1,621 @@
+#include "mavlink/mavlink_internal.h"
+
+#include "mavlink/mavlink_mission.h"
+#include "mavlink/mavlink_runtime.h"
+
+#if defined(USE_TELEMETRY) && defined(USE_TELEMETRY_MAVLINK)
+
+bool mavlinkFrameIsSupported(uint8_t frame, mavFrameSupportMask_e allowedMask)
+{
+ switch (frame) {
+ case MAV_FRAME_GLOBAL:
+ return allowedMask & MAV_FRAME_SUPPORTED_GLOBAL;
+ case MAV_FRAME_GLOBAL_INT:
+ return allowedMask & MAV_FRAME_SUPPORTED_GLOBAL_INT;
+ case MAV_FRAME_GLOBAL_RELATIVE_ALT:
+ return allowedMask & MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT;
+ case MAV_FRAME_GLOBAL_RELATIVE_ALT_INT:
+ return allowedMask & MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT_INT;
+ default:
+ return false;
+ }
+}
+
+bool mavlinkFrameUsesAbsoluteAltitude(uint8_t frame)
+{
+ return frame == MAV_FRAME_GLOBAL || frame == MAV_FRAME_GLOBAL_INT;
+}
+
+MAV_RESULT mavlinkSetAltitudeTargetFromFrame(uint8_t frame, float altitudeMeters)
+{
+#ifdef USE_BARO
+ geoAltitudeDatumFlag_e datum;
+
+ switch (frame) {
+ case MAV_FRAME_GLOBAL:
+ case MAV_FRAME_GLOBAL_INT:
+ datum = NAV_WP_MSL_DATUM;
+ break;
+ case MAV_FRAME_GLOBAL_RELATIVE_ALT:
+ case MAV_FRAME_GLOBAL_RELATIVE_ALT_INT:
+ datum = NAV_WP_TAKEOFF_DATUM;
+ break;
+ default:
+ return MAV_RESULT_UNSUPPORTED;
+ }
+
+ const int32_t targetAltitudeCm = (int32_t)lrintf(altitudeMeters * 100.0f);
+ return navigationSetAltitudeTargetWithDatum(datum, targetAltitudeCm) ? MAV_RESULT_ACCEPTED : MAV_RESULT_DENIED;
+#else
+ UNUSED(frame);
+ UNUSED(altitudeMeters);
+ return MAV_RESULT_UNSUPPORTED;
+#endif
+}
+
+uint8_t mavlinkWaypointFrame(const navWaypoint_t *wp, bool useIntMessages)
+{
+ switch (wp->action) {
+ case NAV_WP_ACTION_RTH:
+ case NAV_WP_ACTION_JUMP:
+ case NAV_WP_ACTION_SET_HEAD:
+ return MAV_FRAME_MISSION;
+ default:
+ break;
+ }
+
+ if ((wp->p3 & NAV_WP_ALTMODE) == NAV_WP_ALTMODE) {
+ return useIntMessages ? MAV_FRAME_GLOBAL_INT : MAV_FRAME_GLOBAL;
+ }
+
+ return useIntMessages ? MAV_FRAME_GLOBAL_RELATIVE_ALT_INT : MAV_FRAME_GLOBAL_RELATIVE_ALT;
+}
+
+static MAV_MISSION_RESULT mavlinkMissionResultFromCommandResult(MAV_RESULT result)
+{
+ switch (result) {
+ case MAV_RESULT_ACCEPTED:
+ return MAV_MISSION_ACCEPTED;
+ case MAV_RESULT_UNSUPPORTED:
+ return MAV_MISSION_UNSUPPORTED;
+ default:
+ return MAV_MISSION_ERROR;
+ }
+}
+
+static void mavlinkResetIncomingMissionTransaction(void)
+{
+ incomingMissionWpCount = 0;
+ incomingMissionWpSequence = 0;
+ incomingMissionSourceSystem = 0;
+ incomingMissionSourceComponent = 0;
+ incomingMissionLastActivityMs = 0;
+}
+
+static void mavlinkStartIncomingMissionTransaction(int missionCount)
+{
+ incomingMissionWpCount = missionCount;
+ incomingMissionWpSequence = 0;
+ incomingMissionSourceSystem = mavlinkContext.recvMsg.sysid;
+ incomingMissionSourceComponent = mavlinkContext.recvMsg.compid;
+ incomingMissionLastActivityMs = millis();
+}
+
+static void mavlinkTouchIncomingMissionTransaction(void)
+{
+ incomingMissionLastActivityMs = millis();
+}
+
+static bool mavlinkIsIncomingMissionTransactionActive(void)
+{
+ if (incomingMissionWpCount <= 0) {
+ return false;
+ }
+
+ if ((timeMs_t)(millis() - incomingMissionLastActivityMs) > MAVLINK_MISSION_UPLOAD_TIMEOUT_MS) {
+ mavlinkResetIncomingMissionTransaction();
+ return false;
+ }
+
+ return true;
+}
+
+static bool mavlinkIsIncomingMissionTransactionOwner(void)
+{
+ return mavlinkContext.recvMsg.sysid == incomingMissionSourceSystem &&
+ mavlinkContext.recvMsg.compid == incomingMissionSourceComponent;
+}
+
+static bool mavlinkHandleArmedGuidedMissionItem(uint8_t current, uint8_t frame, mavFrameSupportMask_e allowedFrames, int32_t latitudeE7, int32_t longitudeE7, float altitudeMeters)
+{
+ if (!isGCSValid()) {
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg,
+ mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid,
+ MAV_MISSION_ERROR, MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
+ return true;
+ }
+
+ if (!mavlinkFrameIsSupported(frame, allowedFrames)) {
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg,
+ mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid,
+ MAV_MISSION_UNSUPPORTED_FRAME, MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
+ return true;
+ }
+
+ if (current == 2) {
+ navWaypoint_t wp = {0};
+ wp.action = NAV_WP_ACTION_WAYPOINT;
+ wp.lat = latitudeE7;
+ wp.lon = longitudeE7;
+ wp.alt = (int32_t)lrintf(altitudeMeters * 100.0f);
+ wp.p3 = mavlinkFrameUsesAbsoluteAltitude(frame) ? NAV_WP_ALTMODE : 0;
+
+ setWaypoint(255, &wp);
+
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg,
+ mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid,
+ MAV_MISSION_ACCEPTED, MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
+ return true;
+ }
+
+ if (current == 3) {
+ const MAV_RESULT result = mavlinkSetAltitudeTargetFromFrame(frame, altitudeMeters);
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg,
+ mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid,
+ mavlinkMissionResultFromCommandResult(result), MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
+ return true;
+ }
+
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg,
+ mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid,
+ MAV_MISSION_ERROR, MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
+ return true;
+}
+
+static bool mavlinkHandleMissionItemCommon(bool useIntMessages, uint8_t frame, uint16_t command, uint8_t autocontinue, uint16_t seq, float param1, float param2, float param3, float param4, int32_t lat, int32_t lon, float altMeters)
+{
+ if (!mavlinkIsIncomingMissionTransactionActive() || !mavlinkIsIncomingMissionTransactionOwner()) {
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_INVALID_SEQUENCE, MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
+ return true;
+ }
+
+ mavlinkTouchIncomingMissionTransaction();
+
+ const bool lastMissionItem = incomingMissionWpCount > 0 && ((int)seq + 1 >= incomingMissionWpCount);
+
+ if (autocontinue == 0 && !lastMissionItem) {
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_UNSUPPORTED, MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
+ return true;
+ }
+
+ UNUSED(param3);
+
+ navWaypoint_t wp = {0};
+
+ switch (command) {
+ case MAV_CMD_NAV_WAYPOINT:
+ if (!mavlinkFrameIsSupported(frame,
+ MAV_FRAME_SUPPORTED_GLOBAL |
+ MAV_FRAME_SUPPORTED_GLOBAL_INT |
+ MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT |
+ MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT_INT)) {
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_UNSUPPORTED_FRAME, MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
+ return true;
+ }
+ wp.action = NAV_WP_ACTION_WAYPOINT;
+ wp.lat = lat;
+ wp.lon = lon;
+ wp.alt = (int32_t)(altMeters * 100.0f);
+ wp.p3 = mavlinkFrameUsesAbsoluteAltitude(frame) ? NAV_WP_ALTMODE : 0;
+ break;
+
+ case MAV_CMD_NAV_LOITER_TIME:
+ if (!mavlinkFrameIsSupported(frame,
+ MAV_FRAME_SUPPORTED_GLOBAL |
+ MAV_FRAME_SUPPORTED_GLOBAL_INT |
+ MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT |
+ MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT_INT)) {
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_UNSUPPORTED_FRAME, MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
+ return true;
+ }
+ wp.action = NAV_WP_ACTION_HOLD_TIME;
+ wp.lat = lat;
+ wp.lon = lon;
+ wp.alt = (int32_t)(altMeters * 100.0f);
+ wp.p1 = (int16_t)lrintf(param1);
+ wp.p3 = mavlinkFrameUsesAbsoluteAltitude(frame) ? NAV_WP_ALTMODE : 0;
+ break;
+
+ case MAV_CMD_NAV_RETURN_TO_LAUNCH:
+ {
+ const bool coordinateFrame = mavlinkFrameIsSupported(frame,
+ MAV_FRAME_SUPPORTED_GLOBAL |
+ MAV_FRAME_SUPPORTED_GLOBAL_INT |
+ MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT |
+ MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT_INT);
+
+ if (!coordinateFrame && frame != MAV_FRAME_MISSION) {
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_UNSUPPORTED_FRAME, MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
+ return true;
+ }
+ wp.action = NAV_WP_ACTION_RTH;
+ wp.alt = coordinateFrame ? (int32_t)(altMeters * 100.0f) : 0;
+ wp.p3 = mavlinkFrameUsesAbsoluteAltitude(frame) ? NAV_WP_ALTMODE : 0;
+ break;
+ }
+
+ case MAV_CMD_NAV_LAND:
+ if (!mavlinkFrameIsSupported(frame,
+ MAV_FRAME_SUPPORTED_GLOBAL |
+ MAV_FRAME_SUPPORTED_GLOBAL_INT |
+ MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT |
+ MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT_INT)) {
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_UNSUPPORTED_FRAME, MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
+ return true;
+ }
+ wp.action = NAV_WP_ACTION_LAND;
+ wp.lat = lat;
+ wp.lon = lon;
+ wp.alt = (int32_t)(altMeters * 100.0f);
+ wp.p3 = mavlinkFrameUsesAbsoluteAltitude(frame) ? NAV_WP_ALTMODE : 0;
+ break;
+
+ case MAV_CMD_DO_JUMP:
+ if (frame != MAV_FRAME_MISSION) {
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_UNSUPPORTED_FRAME, MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
+ return true;
+ }
+ if (param1 < 0.0f) {
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_UNSUPPORTED, MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
+ return true;
+ }
+ wp.action = NAV_WP_ACTION_JUMP;
+ wp.p1 = (int16_t)lrintf(param1 + 1.0f);
+ wp.p2 = (int16_t)lrintf(param2);
+ break;
+
+ case MAV_CMD_DO_SET_ROI:
+ if (param1 != MAV_ROI_LOCATION ||
+ !mavlinkFrameIsSupported(frame,
+ MAV_FRAME_SUPPORTED_GLOBAL |
+ MAV_FRAME_SUPPORTED_GLOBAL_INT |
+ MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT |
+ MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT_INT)) {
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_UNSUPPORTED, MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
+ return true;
+ }
+ wp.action = NAV_WP_ACTION_SET_POI;
+ wp.lat = lat;
+ wp.lon = lon;
+ wp.alt = (int32_t)(altMeters * 100.0f);
+ wp.p3 = mavlinkFrameUsesAbsoluteAltitude(frame) ? NAV_WP_ALTMODE : 0;
+ break;
+
+ case MAV_CMD_CONDITION_YAW:
+ if (frame != MAV_FRAME_MISSION) {
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_UNSUPPORTED_FRAME, MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
+ return true;
+ }
+ if (param4 != 0.0f) {
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_UNSUPPORTED, MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
+ return true;
+ }
+ wp.action = NAV_WP_ACTION_SET_HEAD;
+ wp.p1 = (int16_t)lrintf(param1);
+ break;
+
+ default:
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_UNSUPPORTED, MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
+ return true;
+ }
+
+ if (seq == incomingMissionWpSequence) {
+ incomingMissionWpSequence++;
+ wp.flag = (incomingMissionWpSequence >= incomingMissionWpCount) ? NAV_WP_FLAG_LAST : 0;
+ setWaypoint(incomingMissionWpSequence, &wp);
+
+ if (incomingMissionWpSequence >= incomingMissionWpCount) {
+ if (isWaypointListValid()) {
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_ACCEPTED, MAV_MISSION_TYPE_MISSION, 0);
+ } else {
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_INVALID, MAV_MISSION_TYPE_MISSION, 0);
+ }
+ mavlinkSendMessage();
+ mavlinkResetIncomingMissionTransaction();
+ } else {
+ if (useIntMessages) {
+ mavlink_msg_mission_request_int_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, incomingMissionWpSequence, MAV_MISSION_TYPE_MISSION);
+ } else {
+ mavlink_msg_mission_request_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, incomingMissionWpSequence, MAV_MISSION_TYPE_MISSION);
+ }
+ mavlinkSendMessage();
+ }
+ } else {
+ if (seq + 1 == incomingMissionWpSequence) {
+ mavlinkTouchIncomingMissionTransaction();
+ if (useIntMessages) {
+ mavlink_msg_mission_request_int_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, incomingMissionWpSequence, MAV_MISSION_TYPE_MISSION);
+ } else {
+ mavlink_msg_mission_request_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, incomingMissionWpSequence, MAV_MISSION_TYPE_MISSION);
+ }
+ mavlinkSendMessage();
+ } else {
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_INVALID_SEQUENCE, MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
+ }
+ }
+
+ return true;
+}
+
+bool mavlinkHandleIncomingMissionClearAll(void)
+{
+ mavlink_mission_clear_all_t msg;
+ mavlink_msg_mission_clear_all_decode(&mavlinkContext.recvMsg, &msg);
+
+ if (msg.target_system == mavSystemId) {
+ resetWaypointList();
+ mavlinkResetIncomingMissionTransaction();
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_ACCEPTED, MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
+ return true;
+ }
+
+ return false;
+}
+
+bool mavlinkHandleIncomingMissionCount(void)
+{
+ mavlink_mission_count_t msg;
+ mavlink_msg_mission_count_decode(&mavlinkContext.recvMsg, &msg);
+
+ if (msg.target_system == mavSystemId) {
+ mavlinkResetIncomingMissionTransaction();
+ if (ARMING_FLAG(ARMED)) {
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_ERROR, MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
+ return true;
+ }
+ if (msg.count == 0) {
+ resetWaypointList();
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_ACCEPTED, MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
+ return true;
+ }
+ if (msg.count <= NAV_MAX_WAYPOINTS) {
+ mavlinkStartIncomingMissionTransaction(msg.count);
+ mavlink_msg_mission_request_int_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, incomingMissionWpSequence, MAV_MISSION_TYPE_MISSION);
+ mavlinkSendMessage();
+ return true;
+ }
+
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_NO_SPACE, MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
+ return true;
+ }
+
+ return false;
+}
+
+bool mavlinkHandleIncomingMissionItem(void)
+{
+ mavlink_mission_item_t msg;
+ mavlink_msg_mission_item_decode(&mavlinkContext.recvMsg, &msg);
+
+ if (msg.target_system != mavSystemId) {
+ return false;
+ }
+
+ if (ARMING_FLAG(ARMED)) {
+ if (msg.command == MAV_CMD_NAV_WAYPOINT) {
+ return mavlinkHandleArmedGuidedMissionItem(msg.current, msg.frame,
+ MAV_FRAME_SUPPORTED_GLOBAL | MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT,
+ (int32_t)lrintf(msg.x * 1e7f), (int32_t)lrintf(msg.y * 1e7f), msg.z);
+ }
+
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_ERROR, MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
+ return true;
+ }
+
+ return mavlinkHandleMissionItemCommon(false, msg.frame, msg.command, msg.autocontinue, msg.seq, msg.param1, msg.param2, msg.param3, msg.param4, (int32_t)(msg.x * 1e7f), (int32_t)(msg.y * 1e7f), msg.z);
+}
+
+bool mavlinkHandleIncomingMissionRequestList(void)
+{
+ mavlink_mission_request_list_t msg;
+ mavlink_msg_mission_request_list_decode(&mavlinkContext.recvMsg, &msg);
+
+ if (msg.target_system == mavSystemId) {
+ mavlink_msg_mission_count_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, getWaypointCount(), MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
+ return true;
+ }
+
+ return false;
+}
+
+bool mavlinkFillMissionItemFromWaypoint(const navWaypoint_t *wp, bool useIntMessages, mavlinkMissionItemData_t *item)
+{
+ mavlinkMissionItemData_t data = {0};
+
+ data.frame = mavlinkWaypointFrame(wp, useIntMessages);
+
+ switch (wp->action) {
+ case NAV_WP_ACTION_WAYPOINT:
+ data.command = MAV_CMD_NAV_WAYPOINT;
+ data.lat = wp->lat;
+ data.lon = wp->lon;
+ data.alt = wp->alt / 100.0f;
+ break;
+
+ case NAV_WP_ACTION_HOLD_TIME:
+ data.command = MAV_CMD_NAV_LOITER_TIME;
+ data.param1 = wp->p1;
+ data.lat = wp->lat;
+ data.lon = wp->lon;
+ data.alt = wp->alt / 100.0f;
+ break;
+
+ case NAV_WP_ACTION_RTH:
+ data.command = MAV_CMD_NAV_RETURN_TO_LAUNCH;
+ break;
+
+ case NAV_WP_ACTION_LAND:
+ data.command = MAV_CMD_NAV_LAND;
+ data.lat = wp->lat;
+ data.lon = wp->lon;
+ data.alt = wp->alt / 100.0f;
+ break;
+
+ case NAV_WP_ACTION_JUMP:
+ data.command = MAV_CMD_DO_JUMP;
+ data.param1 = (wp->p1 > 0) ? (float)(wp->p1 - 1) : 0.0f;
+ data.param2 = wp->p2;
+ break;
+
+ case NAV_WP_ACTION_SET_POI:
+ data.command = MAV_CMD_DO_SET_ROI;
+ data.param1 = MAV_ROI_LOCATION;
+ data.lat = wp->lat;
+ data.lon = wp->lon;
+ data.alt = wp->alt / 100.0f;
+ break;
+
+ case NAV_WP_ACTION_SET_HEAD:
+ data.command = MAV_CMD_CONDITION_YAW;
+ data.param1 = wp->p1;
+ break;
+
+ default:
+ return false;
+ }
+
+ *item = data;
+ return true;
+}
+
+bool mavlinkHandleIncomingMissionRequest(void)
+{
+ mavlink_mission_request_t msg;
+ mavlink_msg_mission_request_decode(&mavlinkContext.recvMsg, &msg);
+
+ if (msg.target_system != mavSystemId) {
+ return false;
+ }
+
+ const int wpCount = getWaypointCount();
+
+ if (msg.seq < wpCount) {
+ navWaypoint_t wp;
+ getWaypoint(msg.seq + 1, &wp);
+
+ mavlinkMissionItemData_t item;
+ if (mavlinkFillMissionItemFromWaypoint(&wp, false, &item)) {
+ mavlink_msg_mission_item_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid,
+ msg.seq,
+ item.frame,
+ item.command,
+ 0,
+ 1,
+ item.param1, item.param2, item.param3, item.param4,
+ item.lat / 1e7f,
+ item.lon / 1e7f,
+ item.alt,
+ MAV_MISSION_TYPE_MISSION);
+ mavlinkSendMessage();
+ } else {
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_ERROR, MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
+ }
+ } else {
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_INVALID_SEQUENCE, MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
+ }
+
+ return true;
+}
+
+bool mavlinkHandleIncomingMissionItemInt(void)
+{
+ mavlink_mission_item_int_t msg;
+ mavlink_msg_mission_item_int_decode(&mavlinkContext.recvMsg, &msg);
+
+ if (msg.target_system != mavSystemId) {
+ return false;
+ }
+
+ if (ARMING_FLAG(ARMED)) {
+ if (msg.command == MAV_CMD_NAV_WAYPOINT) {
+ return mavlinkHandleArmedGuidedMissionItem(msg.current, msg.frame,
+ MAV_FRAME_SUPPORTED_GLOBAL_INT | MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT_INT,
+ msg.x, msg.y, msg.z);
+ }
+
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_ERROR, MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
+ return true;
+ }
+
+ return mavlinkHandleMissionItemCommon(true, msg.frame, msg.command, msg.autocontinue, msg.seq, msg.param1, msg.param2, msg.param3, msg.param4, msg.x, msg.y, msg.z);
+}
+
+bool mavlinkHandleIncomingMissionRequestInt(void)
+{
+ mavlink_mission_request_int_t msg;
+ mavlink_msg_mission_request_int_decode(&mavlinkContext.recvMsg, &msg);
+
+ if (msg.target_system != mavSystemId) {
+ return false;
+ }
+
+ const int wpCount = getWaypointCount();
+
+ if (msg.seq < wpCount) {
+ navWaypoint_t wp;
+ getWaypoint(msg.seq + 1, &wp);
+
+ mavlinkMissionItemData_t item;
+ if (mavlinkFillMissionItemFromWaypoint(&wp, true, &item)) {
+ mavlink_msg_mission_item_int_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid,
+ msg.seq,
+ item.frame,
+ item.command,
+ 0,
+ 1,
+ item.param1, item.param2, item.param3, item.param4,
+ item.lat,
+ item.lon,
+ item.alt,
+ MAV_MISSION_TYPE_MISSION);
+ mavlinkSendMessage();
+ } else {
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_ERROR, MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
+ }
+ } else {
+ mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_INVALID_SEQUENCE, MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMessage();
+ }
+
+ return true;
+}
+
+#endif
diff --git a/src/main/mavlink/mavlink_mission.h b/src/main/mavlink/mavlink_mission.h
new file mode 100644
index 00000000000..d8139dfbc96
--- /dev/null
+++ b/src/main/mavlink/mavlink_mission.h
@@ -0,0 +1,42 @@
+#pragma once
+
+#include
+#include
+
+#include "navigation/navigation.h"
+
+#include "mavlink/mavlink_types.h"
+
+typedef enum {
+ MAV_FRAME_SUPPORTED_NONE = 0,
+ MAV_FRAME_SUPPORTED_GLOBAL = (1 << 0),
+ MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT = (1 << 1),
+ MAV_FRAME_SUPPORTED_GLOBAL_INT = (1 << 2),
+ MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT_INT = (1 << 3),
+} mavFrameSupportMask_e;
+
+typedef struct mavlinkMissionItemData_s {
+ uint8_t frame;
+ uint16_t command;
+ float param1;
+ float param2;
+ float param3;
+ float param4;
+ int32_t lat;
+ int32_t lon;
+ float alt;
+} mavlinkMissionItemData_t;
+
+bool mavlinkFrameIsSupported(uint8_t frame, mavFrameSupportMask_e allowedMask);
+bool mavlinkFrameUsesAbsoluteAltitude(uint8_t frame);
+MAV_RESULT mavlinkSetAltitudeTargetFromFrame(uint8_t frame, float altitudeMeters);
+uint8_t mavlinkWaypointFrame(const navWaypoint_t *wp, bool useIntMessages);
+bool mavlinkFillMissionItemFromWaypoint(const navWaypoint_t *wp, bool useIntMessages, mavlinkMissionItemData_t *item);
+
+bool mavlinkHandleIncomingMissionClearAll(void);
+bool mavlinkHandleIncomingMissionCount(void);
+bool mavlinkHandleIncomingMissionItem(void);
+bool mavlinkHandleIncomingMissionRequestList(void);
+bool mavlinkHandleIncomingMissionRequest(void);
+bool mavlinkHandleIncomingMissionItemInt(void);
+bool mavlinkHandleIncomingMissionRequestInt(void);
diff --git a/src/main/mavlink/mavlink_modes.c b/src/main/mavlink/mavlink_modes.c
new file mode 100644
index 00000000000..33ff0bfe1b9
--- /dev/null
+++ b/src/main/mavlink/mavlink_modes.c
@@ -0,0 +1,295 @@
+#include "mavlink/mavlink_internal.h"
+
+#include "mavlink/mavlink_modes.h"
+#include "mavlink/mavlink_runtime.h"
+
+#if defined(USE_TELEMETRY) && defined(USE_TELEMETRY_MAVLINK)
+
+typedef struct mavlinkModeDescriptor_s {
+ uint8_t customMode;
+ const char *name;
+} mavlinkModeDescriptor_t;
+
+static APM_COPTER_MODE inavToArduCopterMap(flightModeForTelemetry_e flightMode)
+{
+ switch (flightMode)
+ {
+ case FLM_ACRO: return COPTER_MODE_ACRO;
+ case FLM_ACRO_AIR: return COPTER_MODE_ACRO;
+ case FLM_ANGLE: return COPTER_MODE_STABILIZE;
+ case FLM_HORIZON: return COPTER_MODE_STABILIZE;
+ case FLM_ANGLEHOLD: return COPTER_MODE_STABILIZE;
+ case FLM_ALTITUDE_HOLD: return COPTER_MODE_ALT_HOLD;
+ case FLM_POSITION_HOLD:
+ {
+ if (isGCSValid()) {
+ return COPTER_MODE_GUIDED;
+ } else {
+ return COPTER_MODE_POSHOLD;
+ }
+ }
+ case FLM_RTH: return COPTER_MODE_RTL;
+ case FLM_MISSION: return COPTER_MODE_AUTO;
+ case FLM_LAUNCH: return COPTER_MODE_THROW;
+ case FLM_FAILSAFE:
+ {
+ if (failsafePhase() == FAILSAFE_RETURN_TO_HOME) {
+ return COPTER_MODE_RTL;
+ } else if (failsafePhase() == FAILSAFE_LANDING) {
+ return COPTER_MODE_LAND;
+ } else {
+ return COPTER_MODE_RTL;
+ }
+ }
+ default: return COPTER_MODE_STABILIZE;
+ }
+}
+
+static APM_PLANE_MODE inavToArduPlaneMap(flightModeForTelemetry_e flightMode)
+{
+ switch (flightMode)
+ {
+ case FLM_MANUAL: return PLANE_MODE_MANUAL;
+ case FLM_ACRO: return PLANE_MODE_ACRO;
+ case FLM_ACRO_AIR: return PLANE_MODE_ACRO;
+ case FLM_ANGLE: return PLANE_MODE_FLY_BY_WIRE_A;
+ case FLM_HORIZON: return PLANE_MODE_STABILIZE;
+ case FLM_ANGLEHOLD: return PLANE_MODE_STABILIZE;
+ case FLM_ALTITUDE_HOLD: return PLANE_MODE_FLY_BY_WIRE_B;
+ case FLM_POSITION_HOLD:
+ {
+ if (isGCSValid()) {
+ return PLANE_MODE_GUIDED;
+ } else {
+ return PLANE_MODE_LOITER;
+ }
+ }
+ case FLM_RTH: return PLANE_MODE_RTL;
+ case FLM_MISSION: return PLANE_MODE_AUTO;
+ case FLM_CRUISE: return PLANE_MODE_CRUISE;
+ case FLM_LAUNCH: return PLANE_MODE_TAKEOFF;
+ case FLM_FAILSAFE:
+ {
+ if (failsafePhase() == FAILSAFE_RETURN_TO_HOME) {
+ return PLANE_MODE_RTL;
+ } else if (failsafePhase() == FAILSAFE_LANDING) {
+ return PLANE_MODE_AUTOLAND;
+ } else {
+ return PLANE_MODE_RTL;
+ }
+ }
+ default: return PLANE_MODE_MANUAL;
+ }
+}
+
+static const mavlinkModeDescriptor_t planeModes[] = {
+ { PLANE_MODE_MANUAL, "MANUAL" },
+ { PLANE_MODE_ACRO, "ACRO" },
+ { PLANE_MODE_STABILIZE, "STABILIZE" },
+ { PLANE_MODE_FLY_BY_WIRE_A, "FBWA" },
+ { PLANE_MODE_FLY_BY_WIRE_B, "FBWB" },
+ { PLANE_MODE_CRUISE, "CRUISE" },
+ { PLANE_MODE_AUTO, "AUTO" },
+ { PLANE_MODE_RTL, "RTL" },
+ { PLANE_MODE_LOITER, "LOITER" },
+ { PLANE_MODE_TAKEOFF, "TAKEOFF" },
+ { PLANE_MODE_GUIDED, "GUIDED" },
+};
+
+static const mavlinkModeDescriptor_t copterModes[] = {
+ { COPTER_MODE_ACRO, "ACRO" },
+ { COPTER_MODE_STABILIZE, "STABILIZE" },
+ { COPTER_MODE_ALT_HOLD, "ALT_HOLD" },
+ { COPTER_MODE_POSHOLD, "POSHOLD" },
+ { COPTER_MODE_LOITER, "LOITER" },
+ { COPTER_MODE_AUTO, "AUTO" },
+ { COPTER_MODE_GUIDED, "GUIDED" },
+ { COPTER_MODE_RTL, "RTL" },
+ { COPTER_MODE_LAND, "LAND" },
+ { COPTER_MODE_BRAKE, "BRAKE" },
+ { COPTER_MODE_THROW, "THROW" },
+ { COPTER_MODE_SMART_RTL, "SMART_RTL" },
+ { COPTER_MODE_DRIFT, "DRIFT" },
+};
+
+static bool mavlinkPlaneModeIsConfigured(uint8_t customMode)
+{
+ switch ((APM_PLANE_MODE)customMode) {
+ case PLANE_MODE_MANUAL:
+ return isModeActivationConditionPresent(BOXMANUAL);
+ case PLANE_MODE_ACRO:
+ return true;
+ case PLANE_MODE_STABILIZE:
+ return isModeActivationConditionPresent(BOXHORIZON) ||
+ isModeActivationConditionPresent(BOXANGLEHOLD);
+ case PLANE_MODE_FLY_BY_WIRE_A:
+ return isModeActivationConditionPresent(BOXANGLE);
+ case PLANE_MODE_FLY_BY_WIRE_B:
+ return isModeActivationConditionPresent(BOXNAVALTHOLD);
+ case PLANE_MODE_CRUISE:
+ return isModeActivationConditionPresent(BOXNAVCRUISE) ||
+ (isModeActivationConditionPresent(BOXNAVCOURSEHOLD) &&
+ isModeActivationConditionPresent(BOXNAVALTHOLD));
+ case PLANE_MODE_AUTO:
+ return isModeActivationConditionPresent(BOXNAVWP);
+ case PLANE_MODE_RTL:
+ return isModeActivationConditionPresent(BOXNAVRTH);
+ case PLANE_MODE_GUIDED:
+ return isModeActivationConditionPresent(BOXNAVPOSHOLD) &&
+ isModeActivationConditionPresent(BOXGCSNAV);
+ case PLANE_MODE_LOITER:
+ return isModeActivationConditionPresent(BOXNAVPOSHOLD);
+ case PLANE_MODE_TAKEOFF:
+ return isModeActivationConditionPresent(BOXNAVLAUNCH);
+ default:
+ return false;
+ }
+}
+
+static bool mavlinkCopterModeIsConfigured(uint8_t customMode)
+{
+ switch ((APM_COPTER_MODE)customMode) {
+ case COPTER_MODE_ACRO:
+ return true;
+ case COPTER_MODE_STABILIZE:
+ return isModeActivationConditionPresent(BOXANGLE) ||
+ isModeActivationConditionPresent(BOXHORIZON) ||
+ isModeActivationConditionPresent(BOXANGLEHOLD);
+ case COPTER_MODE_ALT_HOLD:
+ return isModeActivationConditionPresent(BOXNAVALTHOLD);
+ case COPTER_MODE_GUIDED:
+ return isModeActivationConditionPresent(BOXNAVPOSHOLD) &&
+ isModeActivationConditionPresent(BOXGCSNAV);
+ case COPTER_MODE_POSHOLD:
+ return isModeActivationConditionPresent(BOXNAVPOSHOLD);
+ case COPTER_MODE_RTL:
+ return isModeActivationConditionPresent(BOXNAVRTH);
+ case COPTER_MODE_AUTO:
+ return isModeActivationConditionPresent(BOXNAVWP);
+ case COPTER_MODE_THROW:
+ return isModeActivationConditionPresent(BOXNAVLAUNCH);
+ case COPTER_MODE_BRAKE:
+ return isModeActivationConditionPresent(BOXBRAKING);
+ default:
+ return false;
+ }
+}
+
+static void mavlinkSendAvailableModes(const mavlinkModeDescriptor_t *modes, uint8_t count, uint8_t currentCustom,
+ bool (*isModeConfigured)(uint8_t customMode))
+{
+ uint8_t availableCount = 0;
+ for (uint8_t i = 0; i < count; i++) {
+ if (isModeConfigured(modes[i].customMode)) {
+ availableCount++;
+ }
+ }
+
+ if (availableCount == 0) {
+ return;
+ }
+
+ uint8_t modeIndex = 0;
+ for (uint8_t i = 0; i < count; i++) {
+ if (!isModeConfigured(modes[i].customMode)) {
+ continue;
+ }
+
+ modeIndex++;
+
+ mavlink_msg_available_modes_pack(
+ mavSystemId,
+ mavComponentId,
+ &mavSendMsg,
+ availableCount,
+ modeIndex,
+ MAV_STANDARD_MODE_NON_STANDARD,
+ modes[i].customMode,
+ 0,
+ modes[i].name);
+
+ mavlinkSendMessage();
+
+ if (modes[i].customMode == currentCustom) {
+ const mavlinkModeSelection_t modeSelection = {
+ .flightMode = FLM_MANUAL,
+ .customMode = currentCustom,
+ };
+ mavlinkSendCurrentMode(&modeSelection);
+ }
+ }
+}
+
+bool mavlinkIsFixedWingVehicle(void)
+{
+ return STATE(FIXED_WING_LEGACY) || mixerConfig()->platformType == PLATFORM_AIRPLANE;
+}
+
+uint8_t mavlinkGetVehicleType(void)
+{
+ switch (mixerConfig()->platformType)
+ {
+ case PLATFORM_MULTIROTOR:
+ return MAV_TYPE_QUADROTOR;
+ case PLATFORM_TRICOPTER:
+ return MAV_TYPE_TRICOPTER;
+ case PLATFORM_AIRPLANE:
+ return MAV_TYPE_FIXED_WING;
+ case PLATFORM_ROVER:
+ return MAV_TYPE_GROUND_ROVER;
+ case PLATFORM_BOAT:
+ return MAV_TYPE_SURFACE_BOAT;
+ case PLATFORM_HELICOPTER:
+ return MAV_TYPE_HELICOPTER;
+ default:
+ return MAV_TYPE_GENERIC;
+ }
+}
+
+uint8_t mavlinkGetAutopilotEnum(void)
+{
+ if (mavAutopilotType == MAVLINK_AUTOPILOT_ARDUPILOT) {
+ return MAV_AUTOPILOT_ARDUPILOTMEGA;
+ }
+
+ return MAV_AUTOPILOT_GENERIC;
+}
+
+mavlinkModeSelection_t mavlinkSelectMode(void)
+{
+ mavlinkModeSelection_t modeSelection;
+ modeSelection.flightMode = getFlightModeForTelemetry();
+
+ if (mavlinkIsFixedWingVehicle()) {
+ modeSelection.customMode = (uint8_t)inavToArduPlaneMap(modeSelection.flightMode);
+ } else {
+ modeSelection.customMode = (uint8_t)inavToArduCopterMap(modeSelection.flightMode);
+ }
+
+ return modeSelection;
+}
+
+void mavlinkSendAvailableModesForCurrentMode(void)
+{
+ const mavlinkModeSelection_t modeSelection = mavlinkSelectMode();
+
+ if (mavlinkIsFixedWingVehicle()) {
+ mavlinkSendAvailableModes(planeModes, (uint8_t)ARRAYLEN(planeModes), modeSelection.customMode, mavlinkPlaneModeIsConfigured);
+ } else {
+ mavlinkSendAvailableModes(copterModes, (uint8_t)ARRAYLEN(copterModes), modeSelection.customMode, mavlinkCopterModeIsConfigured);
+ }
+}
+
+void mavlinkSendCurrentMode(const mavlinkModeSelection_t *modeSelection)
+{
+ mavlink_msg_current_mode_pack(
+ mavSystemId,
+ mavComponentId,
+ &mavSendMsg,
+ MAV_STANDARD_MODE_NON_STANDARD,
+ modeSelection->customMode,
+ modeSelection->customMode);
+ mavlinkSendMessage();
+}
+
+#endif
diff --git a/src/main/mavlink/mavlink_modes.h b/src/main/mavlink/mavlink_modes.h
new file mode 100644
index 00000000000..a793f4a834f
--- /dev/null
+++ b/src/main/mavlink/mavlink_modes.h
@@ -0,0 +1,82 @@
+#pragma once
+
+#include
+#include
+
+#include "fc/runtime_config.h"
+
+/** @brief A mapping of plane flight modes for custom_mode field of heartbeat. */
+typedef enum APM_PLANE_MODE
+{
+ PLANE_MODE_MANUAL=0,
+ PLANE_MODE_CIRCLE=1,
+ PLANE_MODE_STABILIZE=2,
+ PLANE_MODE_TRAINING=3,
+ PLANE_MODE_ACRO=4,
+ PLANE_MODE_FLY_BY_WIRE_A=5,
+ PLANE_MODE_FLY_BY_WIRE_B=6,
+ PLANE_MODE_CRUISE=7,
+ PLANE_MODE_AUTOTUNE=8,
+ PLANE_MODE_AUTO=10,
+ PLANE_MODE_RTL=11,
+ PLANE_MODE_LOITER=12,
+ PLANE_MODE_TAKEOFF=13,
+ PLANE_MODE_AVOID_ADSB=14,
+ PLANE_MODE_GUIDED=15,
+ PLANE_MODE_INITIALIZING=16,
+ PLANE_MODE_QSTABILIZE=17,
+ PLANE_MODE_QHOVER=18,
+ PLANE_MODE_QLOITER=19,
+ PLANE_MODE_QLAND=20,
+ PLANE_MODE_QRTL=21,
+ PLANE_MODE_QAUTOTUNE=22,
+ PLANE_MODE_QACRO=23,
+ PLANE_MODE_THERMAL=24,
+ PLANE_MODE_LOITER_ALT_QLAND=25,
+ PLANE_MODE_AUTOLAND=26,
+ PLANE_MODE_ENUM_END=27,
+} APM_PLANE_MODE;
+
+/** @brief A mapping of copter flight modes for custom_mode field of heartbeat. */
+typedef enum APM_COPTER_MODE
+{
+ COPTER_MODE_STABILIZE=0,
+ COPTER_MODE_ACRO=1,
+ COPTER_MODE_ALT_HOLD=2,
+ COPTER_MODE_AUTO=3,
+ COPTER_MODE_GUIDED=4,
+ COPTER_MODE_LOITER=5,
+ COPTER_MODE_RTL=6,
+ COPTER_MODE_CIRCLE=7,
+ COPTER_MODE_LAND=9,
+ COPTER_MODE_DRIFT=11,
+ COPTER_MODE_SPORT=13,
+ COPTER_MODE_FLIP=14,
+ COPTER_MODE_AUTOTUNE=15,
+ COPTER_MODE_POSHOLD=16,
+ COPTER_MODE_BRAKE=17,
+ COPTER_MODE_THROW=18,
+ COPTER_MODE_AVOID_ADSB=19,
+ COPTER_MODE_GUIDED_NOGPS=20,
+ COPTER_MODE_SMART_RTL=21,
+ COPTER_MODE_FLOWHOLD=22,
+ COPTER_MODE_FOLLOW=23,
+ COPTER_MODE_ZIGZAG=24,
+ COPTER_MODE_SYSTEMID=25,
+ COPTER_MODE_AUTOROTATE=26,
+ COPTER_MODE_AUTO_RTL=27,
+ COPTER_MODE_TURTLE=28,
+ COPTER_MODE_ENUM_END=29,
+} APM_COPTER_MODE;
+
+typedef struct mavlinkModeSelection_s {
+ flightModeForTelemetry_e flightMode;
+ uint8_t customMode;
+} mavlinkModeSelection_t;
+
+bool mavlinkIsFixedWingVehicle(void);
+uint8_t mavlinkGetVehicleType(void);
+uint8_t mavlinkGetAutopilotEnum(void);
+mavlinkModeSelection_t mavlinkSelectMode(void);
+void mavlinkSendAvailableModesForCurrentMode(void);
+void mavlinkSendCurrentMode(const mavlinkModeSelection_t *modeSelection);
diff --git a/src/main/mavlink/mavlink_streams.c b/src/main/mavlink/mavlink_streams.c
index 312df303137..15a6630f25c 100644
--- a/src/main/mavlink/mavlink_streams.c
+++ b/src/main/mavlink/mavlink_streams.c
@@ -1,5 +1,6 @@
#include "mavlink/mavlink_internal.h"
+#include "mavlink/mavlink_modes.h"
#include "mavlink/mavlink_runtime.h"
#include "mavlink/mavlink_streams.h"
@@ -238,118 +239,6 @@ void configureMAVLinkStreamRates(uint8_t portIndex)
}
}
-static uint8_t mavlinkGetVehicleType(void)
-{
- switch (mixerConfig()->platformType)
- {
- case PLATFORM_MULTIROTOR:
- return MAV_TYPE_QUADROTOR;
- case PLATFORM_TRICOPTER:
- return MAV_TYPE_TRICOPTER;
- case PLATFORM_AIRPLANE:
- return MAV_TYPE_FIXED_WING;
- case PLATFORM_ROVER:
- return MAV_TYPE_GROUND_ROVER;
- case PLATFORM_BOAT:
- return MAV_TYPE_SURFACE_BOAT;
- case PLATFORM_HELICOPTER:
- return MAV_TYPE_HELICOPTER;
- default:
- return MAV_TYPE_GENERIC;
- }
-}
-
-static APM_COPTER_MODE inavToArduCopterMap(flightModeForTelemetry_e flightMode)
-{
- switch (flightMode)
- {
- case FLM_ACRO: return COPTER_MODE_ACRO;
- case FLM_ACRO_AIR: return COPTER_MODE_ACRO;
- case FLM_ANGLE: return COPTER_MODE_STABILIZE;
- case FLM_HORIZON: return COPTER_MODE_STABILIZE;
- case FLM_ANGLEHOLD: return COPTER_MODE_STABILIZE;
- case FLM_ALTITUDE_HOLD: return COPTER_MODE_ALT_HOLD;
- case FLM_POSITION_HOLD:
- {
- if (isGCSValid()) {
- return COPTER_MODE_GUIDED;
- } else {
- return COPTER_MODE_POSHOLD;
- }
- }
- case FLM_RTH: return COPTER_MODE_RTL;
- case FLM_MISSION: return COPTER_MODE_AUTO;
- case FLM_LAUNCH: return COPTER_MODE_THROW;
- case FLM_FAILSAFE:
- {
- if (failsafePhase() == FAILSAFE_RETURN_TO_HOME) {
- return COPTER_MODE_RTL;
- } else if (failsafePhase() == FAILSAFE_LANDING) {
- return COPTER_MODE_LAND;
- } else {
- return COPTER_MODE_RTL;
- }
- }
- default: return COPTER_MODE_STABILIZE;
- }
-}
-
-static APM_PLANE_MODE inavToArduPlaneMap(flightModeForTelemetry_e flightMode)
-{
- switch (flightMode)
- {
- case FLM_MANUAL: return PLANE_MODE_MANUAL;
- case FLM_ACRO: return PLANE_MODE_ACRO;
- case FLM_ACRO_AIR: return PLANE_MODE_ACRO;
- case FLM_ANGLE: return PLANE_MODE_FLY_BY_WIRE_A;
- case FLM_HORIZON: return PLANE_MODE_STABILIZE;
- case FLM_ANGLEHOLD: return PLANE_MODE_STABILIZE;
- case FLM_ALTITUDE_HOLD: return PLANE_MODE_FLY_BY_WIRE_B;
- case FLM_POSITION_HOLD:
- {
- if (isGCSValid()) {
- return PLANE_MODE_GUIDED;
- } else {
- return PLANE_MODE_LOITER;
- }
- }
- case FLM_RTH: return PLANE_MODE_RTL;
- case FLM_MISSION: return PLANE_MODE_AUTO;
- case FLM_CRUISE: return PLANE_MODE_CRUISE;
- case FLM_LAUNCH: return PLANE_MODE_TAKEOFF;
- case FLM_FAILSAFE:
- {
- if (failsafePhase() == FAILSAFE_RETURN_TO_HOME) {
- return PLANE_MODE_RTL;
- } else if (failsafePhase() == FAILSAFE_LANDING) {
- return PLANE_MODE_AUTOLAND;
- } else {
- return PLANE_MODE_RTL;
- }
- }
- default: return PLANE_MODE_MANUAL;
- }
-}
-
-typedef struct mavlinkModeSelection_s {
- flightModeForTelemetry_e flightMode;
- uint8_t customMode;
-} mavlinkModeSelection_t;
-
-static mavlinkModeSelection_t selectMavlinkMode(bool isPlane)
-{
- mavlinkModeSelection_t modeSelection;
- modeSelection.flightMode = getFlightModeForTelemetry();
-
- if (isPlane) {
- modeSelection.customMode = (uint8_t)inavToArduPlaneMap(modeSelection.flightMode);
- } else {
- modeSelection.customMode = (uint8_t)inavToArduCopterMap(modeSelection.flightMode);
- }
-
- return modeSelection;
-}
-
void mavlinkSendAutopilotVersion(void)
{
if (mavlinkGetProtocolVersion() == 1) {
@@ -414,149 +303,6 @@ void mavlinkSendProtocolVersion(void)
mavlinkSendMessage();
}
-static const mavlinkModeDescriptor_t planeModes[] = {
- { PLANE_MODE_MANUAL, "MANUAL" },
- { PLANE_MODE_ACRO, "ACRO" },
- { PLANE_MODE_STABILIZE, "STABILIZE" },
- { PLANE_MODE_FLY_BY_WIRE_A,"FBWA" },
- { PLANE_MODE_FLY_BY_WIRE_B,"FBWB" },
- { PLANE_MODE_CRUISE, "CRUISE" },
- { PLANE_MODE_AUTO, "AUTO" },
- { PLANE_MODE_RTL, "RTL" },
- { PLANE_MODE_LOITER, "LOITER" },
- { PLANE_MODE_TAKEOFF, "TAKEOFF" },
- { PLANE_MODE_GUIDED, "GUIDED" },
-};
-
-static const mavlinkModeDescriptor_t copterModes[] = {
- { COPTER_MODE_ACRO, "ACRO" },
- { COPTER_MODE_STABILIZE, "STABILIZE" },
- { COPTER_MODE_ALT_HOLD, "ALT_HOLD" },
- { COPTER_MODE_POSHOLD, "POSHOLD" },
- { COPTER_MODE_LOITER, "LOITER" },
- { COPTER_MODE_AUTO, "AUTO" },
- { COPTER_MODE_GUIDED, "GUIDED" },
- { COPTER_MODE_RTL, "RTL" },
- { COPTER_MODE_LAND, "LAND" },
- { COPTER_MODE_BRAKE, "BRAKE" },
- { COPTER_MODE_THROW, "THROW" },
- { COPTER_MODE_SMART_RTL, "SMART_RTL" },
- { COPTER_MODE_DRIFT, "DRIFT" },
-};
-
-static bool mavlinkPlaneModeIsConfigured(uint8_t customMode)
-{
- switch ((APM_PLANE_MODE)customMode) {
- case PLANE_MODE_MANUAL:
- return isModeActivationConditionPresent(BOXMANUAL);
- case PLANE_MODE_ACRO:
- return true;
- case PLANE_MODE_STABILIZE:
- return isModeActivationConditionPresent(BOXHORIZON) ||
- isModeActivationConditionPresent(BOXANGLEHOLD);
- case PLANE_MODE_FLY_BY_WIRE_A:
- return isModeActivationConditionPresent(BOXANGLE);
- case PLANE_MODE_FLY_BY_WIRE_B:
- return isModeActivationConditionPresent(BOXNAVALTHOLD);
- case PLANE_MODE_CRUISE:
- return isModeActivationConditionPresent(BOXNAVCRUISE) ||
- (isModeActivationConditionPresent(BOXNAVCOURSEHOLD) &&
- isModeActivationConditionPresent(BOXNAVALTHOLD));
- case PLANE_MODE_AUTO:
- return isModeActivationConditionPresent(BOXNAVWP);
- case PLANE_MODE_RTL:
- return isModeActivationConditionPresent(BOXNAVRTH);
- case PLANE_MODE_GUIDED:
- return isModeActivationConditionPresent(BOXNAVPOSHOLD) &&
- isModeActivationConditionPresent(BOXGCSNAV);
- case PLANE_MODE_LOITER:
- return isModeActivationConditionPresent(BOXNAVPOSHOLD);
- case PLANE_MODE_TAKEOFF:
- return isModeActivationConditionPresent(BOXNAVLAUNCH);
- default:
- return false;
- }
-}
-
-static bool mavlinkCopterModeIsConfigured(uint8_t customMode)
-{
- switch ((APM_COPTER_MODE)customMode) {
- case COPTER_MODE_ACRO:
- return true;
- case COPTER_MODE_STABILIZE:
- return isModeActivationConditionPresent(BOXANGLE) ||
- isModeActivationConditionPresent(BOXHORIZON) ||
- isModeActivationConditionPresent(BOXANGLEHOLD);
- case COPTER_MODE_ALT_HOLD:
- return isModeActivationConditionPresent(BOXNAVALTHOLD);
- case COPTER_MODE_GUIDED:
- return isModeActivationConditionPresent(BOXNAVPOSHOLD) &&
- isModeActivationConditionPresent(BOXGCSNAV);
- case COPTER_MODE_POSHOLD:
- return isModeActivationConditionPresent(BOXNAVPOSHOLD);
- case COPTER_MODE_RTL:
- return isModeActivationConditionPresent(BOXNAVRTH);
- case COPTER_MODE_AUTO:
- return isModeActivationConditionPresent(BOXNAVWP);
- case COPTER_MODE_THROW:
- return isModeActivationConditionPresent(BOXNAVLAUNCH);
- case COPTER_MODE_BRAKE:
- return isModeActivationConditionPresent(BOXBRAKING);
- default:
- return false;
- }
-}
-
-static void mavlinkSendAvailableModes(const mavlinkModeDescriptor_t *modes, uint8_t count, uint8_t currentCustom,
- bool (*isModeConfigured)(uint8_t customMode))
-{
- uint8_t availableCount = 0;
- for (uint8_t i = 0; i < count; i++) {
- if (isModeConfigured(modes[i].customMode)) {
- availableCount++;
- }
- }
-
- if (availableCount == 0) {
- return;
- }
-
- uint8_t modeIndex = 0;
- for (uint8_t i = 0; i < count; i++) {
- if (!isModeConfigured(modes[i].customMode)) {
- continue;
- }
-
- modeIndex++;
- const uint8_t stdMode = MAV_STANDARD_MODE_NON_STANDARD;
- const uint32_t properties = 0;
-
- mavlink_msg_available_modes_pack(
- mavSystemId,
- mavComponentId,
- &mavSendMsg,
- availableCount,
- modeIndex,
- stdMode,
- modes[i].customMode,
- properties,
- modes[i].name);
-
- mavlinkSendMessage();
-
- if (modes[i].customMode == currentCustom) {
- mavlink_msg_current_mode_pack(
- mavSystemId,
- mavComponentId,
- &mavSendMsg,
- stdMode,
- currentCustom,
- currentCustom);
- mavlinkSendMessage();
- }
- }
-}
-
void mavlinkSendExtendedSysState(void)
{
uint8_t vtolState = MAV_VTOL_STATE_UNDEFINED;
@@ -929,14 +675,12 @@ void mavlinkSendVfrHud(void)
mavlinkSendMessage();
}
-static uint8_t mavlinkGetAutopilotEnum(void);
-
void mavlinkSendHeartbeat(void)
{
uint8_t mavModes = MAV_MODE_FLAG_CUSTOM_MODE_ENABLED;
- const bool isPlane = (STATE(FIXED_WING_LEGACY) || mixerConfig()->platformType == PLATFORM_AIRPLANE);
- const mavlinkModeSelection_t modeSelection = selectMavlinkMode(isPlane);
+ const bool isPlane = mavlinkIsFixedWingVehicle();
+ const mavlinkModeSelection_t modeSelection = mavlinkSelectMode();
flightModeForTelemetry_e flm = modeSelection.flightMode;
uint8_t mavCustomMode = modeSelection.customMode;
uint8_t mavSystemType;
@@ -1094,15 +838,6 @@ void mavlinkSendBatteryTemperatureStatusText(void)
mavlinkSendStatusText();
}
-static uint8_t mavlinkGetAutopilotEnum(void)
-{
- if (mavAutopilotType == MAVLINK_AUTOPILOT_ARDUPILOT) {
- return MAV_AUTOPILOT_ARDUPILOTMEGA;
- }
-
- return MAV_AUTOPILOT_GENERIC;
-}
-
static uint8_t mavlinkHeadingDeg2FromCd(int32_t headingCd)
{
return (uint8_t)(wrap_36000(headingCd) / 200);
@@ -1162,8 +897,7 @@ static uint16_t mavlinkComputeHighLatencyFailures(void)
void mavlinkSendHighLatency2(timeUs_t currentTimeUs)
{
- const bool isPlane = (STATE(FIXED_WING_LEGACY) || mixerConfig()->platformType == PLATFORM_AIRPLANE);
- const mavlinkModeSelection_t modeSelection = selectMavlinkMode(isPlane);
+ const mavlinkModeSelection_t modeSelection = mavlinkSelectMode();
int32_t latitude = 0;
int32_t longitude = 0;
@@ -1306,28 +1040,12 @@ bool mavlinkSendRequestedMessage(uint16_t messageId)
mavlinkSendVfrHud();
return true;
case MAVLINK_MSG_ID_AVAILABLE_MODES:
- {
- const bool isPlane = mixerConfig()->platformType == PLATFORM_AIRPLANE || STATE(FIXED_WING_LEGACY);
- const mavlinkModeSelection_t modeSelection = selectMavlinkMode(isPlane);
- if (isPlane) {
- mavlinkSendAvailableModes(planeModes, (uint8_t)ARRAYLEN(planeModes), modeSelection.customMode, mavlinkPlaneModeIsConfigured);
- } else {
- mavlinkSendAvailableModes(copterModes, (uint8_t)ARRAYLEN(copterModes), modeSelection.customMode, mavlinkCopterModeIsConfigured);
- }
- return true;
- }
+ mavlinkSendAvailableModesForCurrentMode();
+ return true;
case MAVLINK_MSG_ID_CURRENT_MODE:
{
- const bool isPlane = mixerConfig()->platformType == PLATFORM_AIRPLANE || STATE(FIXED_WING_LEGACY);
- const mavlinkModeSelection_t modeSelection = selectMavlinkMode(isPlane);
- mavlink_msg_current_mode_pack(
- mavSystemId,
- mavComponentId,
- &mavSendMsg,
- MAV_STANDARD_MODE_NON_STANDARD,
- modeSelection.customMode,
- modeSelection.customMode);
- mavlinkSendMessage();
+ const mavlinkModeSelection_t modeSelection = mavlinkSelectMode();
+ mavlinkSendCurrentMode(&modeSelection);
return true;
}
case MAVLINK_MSG_ID_EXTENDED_SYS_STATE:
diff --git a/src/main/mavlink/mavlink_types.h b/src/main/mavlink/mavlink_types.h
index c050d319392..342479815ba 100644
--- a/src/main/mavlink/mavlink_types.h
+++ b/src/main/mavlink/mavlink_types.h
@@ -61,84 +61,12 @@ typedef enum {
MAVLINK_PERIODIC_MESSAGE_COUNT
} mavlinkPeriodicMessage_e;
-typedef enum {
- MAV_FRAME_SUPPORTED_NONE = 0,
- MAV_FRAME_SUPPORTED_GLOBAL = (1 << 0),
- MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT = (1 << 1),
- MAV_FRAME_SUPPORTED_GLOBAL_INT = (1 << 2),
- MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT_INT = (1 << 3),
-} mavFrameSupportMask_e;
-
/**
* MAVLink requires angles to be in the range -Pi..Pi.
* This converts angles from a range of 0..Pi to -Pi..Pi
*/
#define RADIANS_TO_MAVLINK_RANGE(angle) (((angle) > M_PIf) ? ((angle) - (2 * M_PIf)) : (angle))
-/** @brief A mapping of plane flight modes for custom_mode field of heartbeat. */
-typedef enum APM_PLANE_MODE
-{
- PLANE_MODE_MANUAL=0,
- PLANE_MODE_CIRCLE=1,
- PLANE_MODE_STABILIZE=2,
- PLANE_MODE_TRAINING=3,
- PLANE_MODE_ACRO=4,
- PLANE_MODE_FLY_BY_WIRE_A=5,
- PLANE_MODE_FLY_BY_WIRE_B=6,
- PLANE_MODE_CRUISE=7,
- PLANE_MODE_AUTOTUNE=8,
- PLANE_MODE_AUTO=10,
- PLANE_MODE_RTL=11,
- PLANE_MODE_LOITER=12,
- PLANE_MODE_TAKEOFF=13,
- PLANE_MODE_AVOID_ADSB=14,
- PLANE_MODE_GUIDED=15,
- PLANE_MODE_INITIALIZING=16,
- PLANE_MODE_QSTABILIZE=17,
- PLANE_MODE_QHOVER=18,
- PLANE_MODE_QLOITER=19,
- PLANE_MODE_QLAND=20,
- PLANE_MODE_QRTL=21,
- PLANE_MODE_QAUTOTUNE=22,
- PLANE_MODE_QACRO=23,
- PLANE_MODE_THERMAL=24,
- PLANE_MODE_LOITER_ALT_QLAND=25,
- PLANE_MODE_AUTOLAND=26,
- PLANE_MODE_ENUM_END=27,
-} APM_PLANE_MODE;
-
-/** @brief A mapping of copter flight modes for custom_mode field of heartbeat. */
-typedef enum APM_COPTER_MODE
-{
- COPTER_MODE_STABILIZE=0,
- COPTER_MODE_ACRO=1,
- COPTER_MODE_ALT_HOLD=2,
- COPTER_MODE_AUTO=3,
- COPTER_MODE_GUIDED=4,
- COPTER_MODE_LOITER=5,
- COPTER_MODE_RTL=6,
- COPTER_MODE_CIRCLE=7,
- COPTER_MODE_LAND=9,
- COPTER_MODE_DRIFT=11,
- COPTER_MODE_SPORT=13,
- COPTER_MODE_FLIP=14,
- COPTER_MODE_AUTOTUNE=15,
- COPTER_MODE_POSHOLD=16,
- COPTER_MODE_BRAKE=17,
- COPTER_MODE_THROW=18,
- COPTER_MODE_AVOID_ADSB=19,
- COPTER_MODE_GUIDED_NOGPS=20,
- COPTER_MODE_SMART_RTL=21,
- COPTER_MODE_FLOWHOLD=22,
- COPTER_MODE_FOLLOW=23,
- COPTER_MODE_ZIGZAG=24,
- COPTER_MODE_SYSTEMID=25,
- COPTER_MODE_AUTOROTATE=26,
- COPTER_MODE_AUTO_RTL=27,
- COPTER_MODE_TURTLE=28,
- COPTER_MODE_ENUM_END=29,
-} APM_COPTER_MODE;
-
typedef struct mavlinkRouteEntry_s {
uint8_t sysid;
uint8_t compid;
@@ -165,20 +93,3 @@ typedef struct mavlinkPortRuntime_s {
mavlink_message_t mavRecvMsg;
mavlink_status_t mavRecvStatus;
} mavlinkPortRuntime_t;
-
-typedef struct mavlinkModeDescriptor_s {
- uint8_t customMode;
- const char *name;
-} mavlinkModeDescriptor_t;
-
-typedef struct mavlinkMissionItemData_s {
- uint8_t frame;
- uint16_t command;
- float param1;
- float param2;
- float param3;
- float param4;
- int32_t lat;
- int32_t lon;
- float alt;
-} mavlinkMissionItemData_t;
diff --git a/src/test/unit/CMakeLists.txt b/src/test/unit/CMakeLists.txt
index 04527fd7046..e8de17e9959 100644
--- a/src/test/unit/CMakeLists.txt
+++ b/src/test/unit/CMakeLists.txt
@@ -44,7 +44,7 @@ set_property(SOURCE gimbal_serial_unittest.cc PROPERTY depends "io/gimbal_serial
set_property(SOURCE gimbal_serial_unittest.cc PROPERTY definitions USE_SERIAL_GIMBAL GIMBAL_UNIT_TEST USE_HEADTRACKER)
set_property(SOURCE mavlink_unittest.cc PROPERTY depends
- "fc/fc_mavlink.c" "mavlink/mavlink_ports.c" "mavlink/mavlink_routing.c" "mavlink/mavlink_runtime.c"
+ "fc/fc_mavlink.c" "mavlink/mavlink_mission.c" "mavlink/mavlink_modes.c" "mavlink/mavlink_ports.c" "mavlink/mavlink_routing.c" "mavlink/mavlink_runtime.c"
"mavlink/mavlink_streams.c" "telemetry/mavlink.c" "common/crc.c" "common/maths.c" "common/streambuf.c" "msp/msp_serial.c")
set_property(SOURCE mavlink_unittest.cc PROPERTY definitions USE_TELEMETRY USE_TELEMETRY_MAVLINK)
set_property(SOURCE mavlink_unittest.cc PROPERTY includes
From 6e20c117cd03c6d4e81b633a3ee67bef4bac0dcc Mon Sep 17 00:00:00 2001
From: frogmane <7685285+xznhj8129@users.noreply.github.com>
Date: Fri, 3 Apr 2026 18:36:46 -0400
Subject: [PATCH 38/46] Fix MAVLink user docs
---
docs/Mavlink.md | 4 +++-
1 file changed, 3 insertions(+), 1 deletion(-)
diff --git a/docs/Mavlink.md b/docs/Mavlink.md
index 5194881c29f..7f02c00151b 100644
--- a/docs/Mavlink.md
+++ b/docs/Mavlink.md
@@ -51,7 +51,7 @@ Ports 2..N use a secondary startup profile (heartbeat at 1 Hz, other streams dis
| `EXTENDED_STATUS` | `SYS_STATUS` | 2 Hz |
| `RC_CHANNELS` | `RC_CHANNELS_RAW` (v1) / `RC_CHANNELS` (v2) | 1 Hz |
| `POSITION` | `GPS_RAW_INT`, `GLOBAL_POSITION_INT`, `GPS_GLOBAL_ORIGIN` | 2 Hz |
-| `EXTRA1` | `ATTITUDE` | 3 Hz |
+| `EXTRA1` | `ATTITUDE` | 2 Hz |
| `EXTRA2` | `VFR_HUD` | 2 Hz |
| `HEARTBEAT` | `HEARTBEAT` | 1 Hz (independent of stream groups) |
| `EXT_SYS_STATE` | `EXTENDED_SYS_STATE` | 1 Hz (defaults to `mavlink_port1_extra3_rate`) |
@@ -113,12 +113,14 @@ Messages are organized into MAVLink datastream groups. Each group sends **one me
Limited implementation of the Command protocol.
- `MAV_CMD_DO_REPOSITION`: sets the Follow Me/GCS Nav waypoint when GCS NAV is valid. Accepts `MAV_FRAME_GLOBAL`, `MAV_FRAME_GLOBAL_INT`, `MAV_FRAME_GLOBAL_RELATIVE_ALT`, `MAV_FRAME_GLOBAL_RELATIVE_ALT_INT`; otherwise `UNSUPPORTED`.
+- `MAV_CMD_DO_CHANGE_ALTITUDE`: changes the current altitude target. `param1` is the target altitude in meters and `param2` is interpreted as the MAVLink frame (`MAV_FRAME_GLOBAL`, `MAV_FRAME_GLOBAL_INT`, `MAV_FRAME_GLOBAL_RELATIVE_ALT`, `MAV_FRAME_GLOBAL_RELATIVE_ALT_INT`); unsupported frames are rejected.
- `MAV_CMD_CONDITION_YAW`: changes the current heading target when the active navigation state has yaw control. Accepts absolute heading (`param4=0`) and relative turns (`param4!=0`); turn-rate is ignored.
- `MAV_CMD_SET_MESSAGE_INTERVAL` / `MAV_CMD_GET_MESSAGE_INTERVAL`: adjust or query per-message periodic output for `HEARTBEAT`, `SYS_STATUS`, `EXTENDED_SYS_STATE`, RC channels, `GPS_RAW_INT`, `GLOBAL_POSITION_INT`, `GPS_GLOBAL_ORIGIN`, `ATTITUDE`, `VFR_HUD`, `BATTERY_STATUS`, `SCALED_PRESSURE`, and `SYSTEM_TIME`. `REQUEST_DATA_STREAM` still controls the legacy base stream groups; `SET_MESSAGE_INTERVAL` overrides individual messages on top.
- `MAV_CMD_GET_HOME_POSITION`: replies with `HOME_POSITION` when home fix exists.
- `MAV_CMD_REQUEST_MESSAGE`: emits one selected message (`HEARTBEAT`, `SYS_STATUS`, `ATTITUDE`, `VFR_HUD`, `AVAILABLE_MODES`, `CURRENT_MODE`, `EXTENDED_SYS_STATE`, RC channels, `GPS_RAW_INT`, `GLOBAL_POSITION_INT`, `GPS_GLOBAL_ORIGIN`, `BATTERY_STATUS`, `SCALED_PRESSURE`, `SYSTEM_TIME`, and `HOME_POSITION` when available) or `UNSUPPORTED`.
- `MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES`: returns stub `AUTOPILOT_VERSION` (v2 only; v1 returns `UNSUPPORTED`) advertising `SET_POSITION_TARGET_GLOBAL_INT` and `SET_POSITION_TARGET_LOCAL_NED`.
- `MAV_CMD_REQUEST_PROTOCOL_VERSION`: returns stub `PROTOCOL_VERSION` (v2 only; v1 returns `UNSUPPORTED`).
+- `MAV_CMD_CONTROL_HIGH_LATENCY`: enables or disables `HIGH_LATENCY2` scheduling on the ingress MAVLink port (`param1` = `0` or `1`). Enabling is rejected on MAVLink1 links.
## Mode mappings (INAV → MAVLink/ArduPilot)
From a412f8cc93d4fb9ef35d55adc052552edfcfb59c Mon Sep 17 00:00:00 2001
From: frogmane <7685285+xznhj8129@users.noreply.github.com>
Date: Fri, 3 Apr 2026 18:48:17 -0400
Subject: [PATCH 39/46] Fix MAVLink half-duplex RX backoff
Scope MAVLink half-duplex to serial RX
---
docs/Mavlink.md | 5 +++--
src/main/mavlink/mavlink_ports.c | 2 ++
src/main/mavlink/mavlink_runtime.c | 27 +++++++++++++++++++--------
src/main/mavlink/mavlink_types.h | 1 +
4 files changed, 25 insertions(+), 10 deletions(-)
diff --git a/docs/Mavlink.md b/docs/Mavlink.md
index 7f02c00151b..75fb61fa47a 100644
--- a/docs/Mavlink.md
+++ b/docs/Mavlink.md
@@ -11,11 +11,12 @@ INAV supports up to 4 concurrent MAVLink telemetry ports (`MAX_MAVLINK_PORTS`),
- **Mission handling**: uploads are rejected while armed (except legacy guided waypoint writes). Mission frames are validated per command and unsupported frames are rejected.
- **Mode reporting**: `custom_mode` approximates ArduPilot modes and may not match all INAV states.
- **Flow control expectations**: INAV honours `RADIO_STATUS.txbuf` to avoid overrunning radios; without it, packets are simply paced at 20 ms intervals.
-- **Half‑duplex etiquette**: when half‑duplex is enabled, INAV waits one telemetry tick after any received frame before transmitting to reduce collisions.
+- **Half‑duplex etiquette**: on a MAVLink serial RX port configured for `serialrx_halfduplex`, INAV waits one telemetry tick after any received frame before transmitting to reduce collisions.
### Usage guidance
-- If you rely on RC via MAVLink, ensure the serial receiver type is set to `SERIALRX_MAVLINK` and consider enabling `telemetry_halfduplex` when RX shares the port.
+- If you rely on RC via MAVLink, ensure the serial receiver type is set to `SERIALRX_MAVLINK`.
+- If MAVLink RX and telemetry intentionally share one half-duplex wire, enable `serialrx_halfduplex` for that setup.
- To reduce bandwidth, lower the stream rates for groups you do not need, or disable them entirely by setting the rate to 0.
- If a GCS or companion needs telemetry on ports 2..4, explicitly request streams (`REQUEST_DATA_STREAM` or `MAV_CMD_SET_MESSAGE_INTERVAL`) because only heartbeat is enabled by default.
- If you depend on directed forwarding between links, ensure each remote endpoint transmits at least one frame early so route learning is populated.
diff --git a/src/main/mavlink/mavlink_ports.c b/src/main/mavlink/mavlink_ports.c
index 9d499071a51..c3b9f81706e 100644
--- a/src/main/mavlink/mavlink_ports.c
+++ b/src/main/mavlink/mavlink_ports.c
@@ -19,6 +19,7 @@ void freeMAVLinkTelemetryPortByIndex(uint8_t portIndex)
state->txbuffValid = false;
state->txbuffFree = 100;
state->lastMavlinkMessageUs = 0;
+ state->lastRxFrameUs = 0;
state->lastHighLatencyMessageUs = 0;
state->highLatencyEnabled = mavlinkGetPortConfig(portIndex)->high_latency;
state->txSeq = 0;
@@ -56,6 +57,7 @@ void configureMAVLinkTelemetryPort(uint8_t portIndex)
state->txbuffValid = false;
state->txbuffFree = 100;
state->lastMavlinkMessageUs = 0;
+ state->lastRxFrameUs = 0;
state->lastHighLatencyMessageUs = 0;
state->highLatencyEnabled = mavlinkGetPortConfig(portIndex)->high_latency;
state->txSeq = 0;
diff --git a/src/main/mavlink/mavlink_runtime.c b/src/main/mavlink/mavlink_runtime.c
index 0c780e0f7f3..e4c77a68d3d 100644
--- a/src/main/mavlink/mavlink_runtime.c
+++ b/src/main/mavlink/mavlink_runtime.c
@@ -171,7 +171,7 @@ void mavlinkSendMessage(void)
}
}
-static bool processMAVLinkIncomingTelemetry(uint8_t ingressPortIndex)
+static bool processMAVLinkIncomingTelemetry(uint8_t ingressPortIndex, timeUs_t currentTimeUs)
{
mavlinkPortRuntime_t *state = &mavPortStates[ingressPortIndex];
@@ -180,6 +180,7 @@ static bool processMAVLinkIncomingTelemetry(uint8_t ingressPortIndex)
const char c = serialRead(state->port);
const uint8_t result = mavlink_parse_char(ingressPortIndex, c, &state->mavRecvMsg, &state->mavRecvStatus);
if (result == MAVLINK_FRAMING_OK) {
+ state->lastRxFrameUs = currentTimeUs;
mavlinkContext.recvMsg = state->mavRecvMsg;
if (mavlinkIsFromLocalIdentity(mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid)) {
@@ -234,10 +235,15 @@ static bool processMAVLinkIncomingTelemetry(uint8_t ingressPortIndex)
return false;
}
-static bool isMAVLinkTelemetryHalfDuplex(void)
+static bool isMAVLinkTelemetryHalfDuplex(uint8_t portIndex)
{
- return telemetryConfig()->halfDuplex ||
- (rxConfig()->receiverType == RX_TYPE_SERIAL && rxConfig()->serialrx_provider == SERIALRX_MAVLINK && tristateWithDefaultOffIsActive(rxConfig()->halfDuplex));
+ const mavlinkPortRuntime_t *state = &mavPortStates[portIndex];
+
+ return state->portConfig &&
+ (state->portConfig->functionMask & FUNCTION_RX_SERIAL) &&
+ rxConfig()->receiverType == RX_TYPE_SERIAL &&
+ rxConfig()->serialrx_provider == SERIALRX_MAVLINK &&
+ tristateWithDefaultOffIsActive(rxConfig()->halfDuplex);
}
void mavlinkRuntimeHandle(timeUs_t currentTimeUs)
@@ -251,19 +257,24 @@ void mavlinkRuntimeHandle(timeUs_t currentTimeUs)
mavlinkSetActivePortContext(portIndex);
// Process incoming MAVLink on this port and forward when needed.
- const bool receivedMessage = processMAVLinkIncomingTelemetry(portIndex);
+ processMAVLinkIncomingTelemetry(portIndex, currentTimeUs);
// Restore context back to this port before periodic send decisions.
mavlinkSetActivePortContext(portIndex);
bool shouldSendTelemetry = false;
+ const bool halfDuplexBackoff = isMAVLinkTelemetryHalfDuplex(portIndex) &&
+ ((currentTimeUs - state->lastRxFrameUs) < TELEMETRY_MAVLINK_DELAY);
+
+ if (halfDuplexBackoff) {
+ continue;
+ }
if (state->txbuffValid) {
// Use flow control if available.
shouldSendTelemetry = state->txbuffFree >= mavActiveConfig->min_txbuff;
} else {
- // If not, use blind frame pacing and half-duplex backoff after RX activity.
- const bool halfDuplexBackoff = isMAVLinkTelemetryHalfDuplex() && receivedMessage;
- shouldSendTelemetry = ((currentTimeUs - state->lastMavlinkMessageUs) >= TELEMETRY_MAVLINK_DELAY) && !halfDuplexBackoff;
+ // If not, use blind frame pacing.
+ shouldSendTelemetry = (currentTimeUs - state->lastMavlinkMessageUs) >= TELEMETRY_MAVLINK_DELAY;
}
if (!shouldSendTelemetry) {
diff --git a/src/main/mavlink/mavlink_types.h b/src/main/mavlink/mavlink_types.h
index 342479815ba..70a2e5d1157 100644
--- a/src/main/mavlink/mavlink_types.h
+++ b/src/main/mavlink/mavlink_types.h
@@ -81,6 +81,7 @@ typedef struct mavlinkPortRuntime_s {
bool txbuffValid;
uint8_t txbuffFree;
timeUs_t lastMavlinkMessageUs;
+ timeUs_t lastRxFrameUs;
timeUs_t lastHighLatencyMessageUs;
bool highLatencyEnabled;
uint8_t mavRates[MAVLINK_STREAM_COUNT];
From 756c03174548c3a019632cc0607458822dc5312b Mon Sep 17 00:00:00 2001
From: frogmane <7685285+xznhj8129@users.noreply.github.com>
Date: Fri, 3 Apr 2026 19:09:02 -0400
Subject: [PATCH 40/46] Add MAVLink mission reached message
---
docs/Mavlink.md | 2 +-
src/main/mavlink/mavlink_mission.c | 24 ++++++++++++++++
src/main/mavlink/mavlink_mission.h | 1 +
src/main/mavlink/mavlink_runtime.c | 3 ++
src/main/navigation/navigation.c | 33 ++++++++++++++++++++++
src/main/navigation/navigation.h | 1 +
src/main/navigation/navigation_private.h | 2 ++
src/test/unit/mavlink_unittest.cc | 36 ++++++++++++++++++++++++
8 files changed, 101 insertions(+), 1 deletion(-)
diff --git a/docs/Mavlink.md b/docs/Mavlink.md
index 75fb61fa47a..e115abb6cc5 100644
--- a/docs/Mavlink.md
+++ b/docs/Mavlink.md
@@ -89,7 +89,7 @@ Messages are organized into MAVLink datastream groups. Each group sends **one me
- `SCALED_PRESSURE`: for IMU/baro temperature.
- `SYSTEM_TIME`: with `time_boot_ms = millis()` and `time_unix_usec = 0`.
- `STATUSTEXT`: when the OSD has a pending system message; severity follows OSD attributes (notice/warning/critical).
-- On-demand (command-triggered) messages: `AUTOPILOT_VERSION`, `PROTOCOL_VERSION`, `MESSAGE_INTERVAL`, `HOME_POSITION`, `AVAILABLE_MODES`, and `CURRENT_MODE`.
+- Event/on-demand messages: `MISSION_ITEM_REACHED` when a mission item is reached, plus `AUTOPILOT_VERSION`, `PROTOCOL_VERSION`, `MESSAGE_INTERVAL`, `HOME_POSITION`, `AVAILABLE_MODES`, and `CURRENT_MODE`.
## Supported Incoming Messages
diff --git a/src/main/mavlink/mavlink_mission.c b/src/main/mavlink/mavlink_mission.c
index 6ed125c3060..368dd39bfc9 100644
--- a/src/main/mavlink/mavlink_mission.c
+++ b/src/main/mavlink/mavlink_mission.c
@@ -5,6 +5,30 @@
#if defined(USE_TELEMETRY) && defined(USE_TELEMETRY_MAVLINK)
+void mavlinkSendPendingMissionItemReached(void)
+{
+ uint16_t seq;
+ if (!navigationConsumeWaypointReached(&seq)) {
+ return;
+ }
+
+ uint8_t sendMask = 0;
+ for (uint8_t portIndex = 0; portIndex < mavPortCount; portIndex++) {
+ if (mavPortStates[portIndex].telemetryEnabled && mavPortStates[portIndex].port) {
+ sendMask |= MAVLINK_PORT_MASK(portIndex);
+ }
+ }
+
+ if (sendMask == 0) {
+ return;
+ }
+
+ mavSendMask = sendMask;
+ mavlink_msg_mission_item_reached_pack(mavlinkGetCommonConfig()->sysid, MAV_COMP_ID_AUTOPILOT1, &mavSendMsg, seq);
+ mavlinkSendMessage();
+ mavSendMask = 0;
+}
+
bool mavlinkFrameIsSupported(uint8_t frame, mavFrameSupportMask_e allowedMask)
{
switch (frame) {
diff --git a/src/main/mavlink/mavlink_mission.h b/src/main/mavlink/mavlink_mission.h
index d8139dfbc96..650bdd06338 100644
--- a/src/main/mavlink/mavlink_mission.h
+++ b/src/main/mavlink/mavlink_mission.h
@@ -32,6 +32,7 @@ bool mavlinkFrameUsesAbsoluteAltitude(uint8_t frame);
MAV_RESULT mavlinkSetAltitudeTargetFromFrame(uint8_t frame, float altitudeMeters);
uint8_t mavlinkWaypointFrame(const navWaypoint_t *wp, bool useIntMessages);
bool mavlinkFillMissionItemFromWaypoint(const navWaypoint_t *wp, bool useIntMessages, mavlinkMissionItemData_t *item);
+void mavlinkSendPendingMissionItemReached(void);
bool mavlinkHandleIncomingMissionClearAll(void);
bool mavlinkHandleIncomingMissionCount(void);
diff --git a/src/main/mavlink/mavlink_runtime.c b/src/main/mavlink/mavlink_runtime.c
index e4c77a68d3d..6905f0a0209 100644
--- a/src/main/mavlink/mavlink_runtime.c
+++ b/src/main/mavlink/mavlink_runtime.c
@@ -2,6 +2,7 @@
#include "fc/fc_mavlink.h"
+#include "mavlink/mavlink_mission.h"
#include "mavlink/mavlink_ports.h"
#include "mavlink/mavlink_routing.h"
#include "mavlink/mavlink_runtime.h"
@@ -248,6 +249,8 @@ static bool isMAVLinkTelemetryHalfDuplex(uint8_t portIndex)
void mavlinkRuntimeHandle(timeUs_t currentTimeUs)
{
+ mavlinkSendPendingMissionItemReached();
+
for (uint8_t portIndex = 0; portIndex < mavPortCount; portIndex++) {
mavlinkPortRuntime_t *state = &mavPortStates[portIndex];
if (!state->telemetryEnabled || !state->port) {
diff --git a/src/main/navigation/navigation.c b/src/main/navigation/navigation.c
index 55d6ccb8af7..33bd9ba4802 100644
--- a/src/main/navigation/navigation.c
+++ b/src/main/navigation/navigation.c
@@ -2075,6 +2075,8 @@ static navigationFSMEvent_t navOnEnteringState_NAV_STATE_WAYPOINT_IN_PROGRESS(na
return NAV_FSM_EVENT_NONE; // will re-process state in >10ms
}
+static void navMarkWaypointReached(int8_t waypointIndex);
+
static navigationFSMEvent_t navOnEnteringState_NAV_STATE_WAYPOINT_REACHED(navigationFSMState_t previousState)
{
UNUSED(previousState);
@@ -2103,12 +2105,23 @@ static navigationFSMEvent_t navOnEnteringState_NAV_STATE_WAYPOINT_REACHED(naviga
case NAV_WP_ACTION_HOLD_TIME:
// Save the current time for the time the waypoint was reached
posControl.wpReachedTime = millis();
+ navMarkWaypointReached(posControl.activeWaypointIndex);
return NAV_FSM_EVENT_SWITCH_TO_WAYPOINT_HOLD_TIME;
}
UNREACHABLE();
}
+static void navMarkWaypointReached(int8_t waypointIndex)
+{
+ if (waypointIndex < posControl.startWpIndex) {
+ return;
+ }
+
+ posControl.wpReachedSeq = (uint16_t)(waypointIndex - posControl.startWpIndex);
+ posControl.wpReachedNotificationPending = true;
+}
+
static navigationFSMEvent_t navOnEnteringState_NAV_STATE_WAYPOINT_HOLD_TIME(navigationFSMState_t previousState)
{
UNUSED(previousState);
@@ -2126,6 +2139,7 @@ static navigationFSMEvent_t navOnEnteringState_NAV_STATE_WAYPOINT_HOLD_TIME(navi
if (posControl.wpAltitudeReached) {
posControl.wpReachedTime = millis();
+ navMarkWaypointReached(posControl.activeWaypointIndex);
} else {
return NAV_FSM_EVENT_NONE;
}
@@ -2165,6 +2179,10 @@ static navigationFSMEvent_t navOnEnteringState_NAV_STATE_WAYPOINT_NEXT(navigatio
{
UNUSED(previousState);
+ if (!posControl.wpReachedNotificationPending) {
+ navMarkWaypointReached(posControl.activeWaypointIndex);
+ }
+
if (isLastMissionWaypoint()) { // Last waypoint reached
return NAV_FSM_EVENT_SWITCH_TO_WAYPOINT_FINISHED;
}
@@ -3953,6 +3971,7 @@ void resetWaypointList(void)
posControl.waypointListValid = false;
posControl.geoWaypointCount = 0;
posControl.startWpIndex = 0;
+ posControl.wpReachedNotificationPending = false;
#ifdef USE_MULTI_MISSION
posControl.totalMultiMissionWpCount = 0;
posControl.loadedMultiMissionIndex = 0;
@@ -4015,6 +4034,7 @@ void loadSelectedMultiMission(uint8_t missionIndex)
posControl.loadedMultiMissionIndex = posControl.multiMissionCount ? missionIndex : 0;
posControl.activeWaypointIndex = posControl.startWpIndex;
+ posControl.wpReachedNotificationPending = false;
}
bool updateWpMissionChange(void)
@@ -5011,6 +5031,8 @@ void navigationInit(void)
posControl.waypointCount = 0;
posControl.activeWaypointIndex = 0;
posControl.waypointListValid = false;
+ posControl.wpReachedSeq = 0;
+ posControl.wpReachedNotificationPending = false;
posControl.wpPlannerActiveWPIndex = 0;
posControl.flags.wpMissionPlannerActive = false;
posControl.startWpIndex = 0;
@@ -5282,6 +5304,17 @@ const navigationPIDControllers_t* getNavigationPIDControllers(void) {
return &posControl.pids;
}
+bool navigationConsumeWaypointReached(uint16_t *seq)
+{
+ if (!posControl.wpReachedNotificationPending) {
+ return false;
+ }
+
+ *seq = posControl.wpReachedSeq;
+ posControl.wpReachedNotificationPending = false;
+ return true;
+}
+
bool isAdjustingPosition(void) {
return posControl.flags.isAdjustingPosition;
}
diff --git a/src/main/navigation/navigation.h b/src/main/navigation/navigation.h
index 810fdc26ef8..572b8ff2cde 100644
--- a/src/main/navigation/navigation.h
+++ b/src/main/navigation/navigation.h
@@ -781,6 +781,7 @@ bool navigationIsFlyingAutonomousMode(void);
bool navigationIsExecutingAnEmergencyLanding(void);
bool navigationIsControllingAltitude(void);
bool navigationSetAltitudeTargetWithDatum(geoAltitudeDatumFlag_e datumFlag, int32_t targetAltitudeCm);
+bool navigationConsumeWaypointReached(uint16_t *seq);
/* Returns true if navConfig()->general.flags.rth_allow_landing is NAV_RTH_ALLOW_LANDING_ALWAYS
* or if it's NAV_RTH_ALLOW_LANDING_FAILSAFE and failsafe mode is active.
*/
diff --git a/src/main/navigation/navigation_private.h b/src/main/navigation/navigation_private.h
index f6cf9329e98..b838e6e88ee 100644
--- a/src/main/navigation/navigation_private.h
+++ b/src/main/navigation/navigation_private.h
@@ -497,6 +497,8 @@ typedef struct {
float wpDistance; // Distance to active WP
timeMs_t wpReachedTime; // Time the waypoint was reached
bool wpAltitudeReached; // WP altitude achieved
+ uint16_t wpReachedSeq; // Last reached mission item sequence relative to startWpIndex
+ bool wpReachedNotificationPending;
#ifdef USE_FW_AUTOLAND
/* Fixedwing autoland */
diff --git a/src/test/unit/mavlink_unittest.cc b/src/test/unit/mavlink_unittest.cc
index 846ed7efd0f..ba62200e3c7 100644
--- a/src/test/unit/mavlink_unittest.cc
+++ b/src/test/unit/mavlink_unittest.cc
@@ -302,6 +302,8 @@ static void initMavlinkTestState(void)
memset(&GPS_home, 0, sizeof(GPS_home));
memset(waypointStore, 0, sizeof(waypointStore));
memset(&rxLinkStatistics, 0, sizeof(rxLinkStatistics));
+ posControl.wpReachedSeq = 0;
+ posControl.wpReachedNotificationPending = false;
telemetryConfigMutable()->mavlink_common.sysid = 1;
telemetryConfigMutable()->mavlink_common.autopilot_type = MAVLINK_AUTOPILOT_ARDUPILOT;
@@ -909,6 +911,29 @@ TEST(MavlinkTelemetryTest, MissionRequestSendsWaypoint)
EXPECT_NEAR(item.z, 12.34f, 1e-4f);
}
+TEST(MavlinkTelemetryTest, MissionItemReachedIsBroadcastOnceWhenPending)
+{
+ initMavlinkTestState();
+
+ posControl.wpReachedSeq = 3;
+ posControl.wpReachedNotificationPending = true;
+
+ handleMAVLinkTelemetry(1000);
+
+ mavlink_message_t reachedMsg;
+ ASSERT_TRUE(findTxMessageById(MAVLINK_MSG_ID_MISSION_ITEM_REACHED, &reachedMsg));
+
+ mavlink_mission_item_reached_t reached;
+ mavlink_msg_mission_item_reached_decode(&reachedMsg, &reached);
+
+ EXPECT_EQ(reached.seq, 3);
+
+ resetSerialBuffers();
+ handleMAVLinkTelemetry(1000);
+
+ EXPECT_FALSE(findTxMessageById(MAVLINK_MSG_ID_MISSION_ITEM_REACHED, &reachedMsg));
+}
+
TEST(MavlinkTelemetryTest, LegacyGuidedMissionItemUsesAbsoluteAltitude)
{
initMavlinkTestState();
@@ -2035,6 +2060,17 @@ bool navigationSetAltitudeTargetWithDatum(geoAltitudeDatumFlag_e datumFlag, int3
return altitudeTargetSetResult;
}
+bool navigationConsumeWaypointReached(uint16_t *seq)
+{
+ if (!posControl.wpReachedNotificationPending) {
+ return false;
+ }
+
+ *seq = posControl.wpReachedSeq;
+ posControl.wpReachedNotificationPending = false;
+ return true;
+}
+
navigationFSMStateFlags_t navGetCurrentStateFlags(void)
{
return (navigationFSMStateFlags_t)0;
From 4a433a614485e6f0bba12acf8cdf773d17759352 Mon Sep 17 00:00:00 2001
From: frogmane <7685285+xznhj8129@users.noreply.github.com>
Date: Sat, 4 Apr 2026 13:57:00 -0400
Subject: [PATCH 41/46] Lightened fc_mavlink + command/guided files + small
refactor
---
docs/development/msp/README.md | 14 +-
docs/development/msp/inav_enums.json | 121 +++----
docs/development/msp/inav_enums_ref.md | 129 +++----
docs/development/msp/msp_messages.checksum | 2 +-
src/main/CMakeLists.txt | 4 +
src/main/fc/fc_mavlink.c | 385 +--------------------
src/main/mavlink/mavlink_command.c | 245 +++++++++++++
src/main/mavlink/mavlink_command.h | 7 +
src/main/mavlink/mavlink_guided.c | 153 ++++++++
src/main/mavlink/mavlink_guided.h | 13 +
src/main/mavlink/mavlink_mission.c | 240 ++++++-------
src/main/mavlink/mavlink_mission.h | 4 -
src/main/mavlink/mavlink_streams.c | 62 ++++
src/main/mavlink/mavlink_streams.h | 2 +
14 files changed, 745 insertions(+), 636 deletions(-)
create mode 100644 src/main/mavlink/mavlink_command.c
create mode 100644 src/main/mavlink/mavlink_command.h
create mode 100644 src/main/mavlink/mavlink_guided.c
create mode 100644 src/main/mavlink/mavlink_guided.h
diff --git a/docs/development/msp/README.md b/docs/development/msp/README.md
index b0f871fa65a..a573591766b 100644
--- a/docs/development/msp/README.md
+++ b/docs/development/msp/README.md
@@ -66,6 +66,7 @@ For list of enums, see [Enum documentation page](https://github.com/iNavFlight/i
**variable_len**: Optional boolean, if true, message does not have a predefined fixed length and needs appropriate handling\
**variants**: Optional special case, message has different cases of reply/request. Key/description is not a strict expression or code; just a readable condition\
**not_implemented**: Optional special case, message is not implemented (never or deprecated)\
+**replaced_by**: Optional array of MSP message names that replace this command. Present when a command is deprecated and scheduled for removal. Empty array if no replacement is needed\
**notes**: String with details of message
## Data dict fields:
@@ -419,8 +420,8 @@ For list of enums, see [Enum documentation page](https://github.com/iNavFlight/i
[8730 - MSP2_INAV_SET_GLOBAL_TARGET](#msp2_inav_set_global_target)
[8731 - MSP2_INAV_NAV_TARGET](#msp2_inav_nav_target)
[8736 - MSP2_INAV_FULL_LOCAL_POSE](#msp2_inav_full_local_pose)
-[12288 - MSP2_BETAFLIGHT_BIND](#msp2_betaflight_bind)
-[12289 - MSP2_RX_BIND](#msp2_rx_bind)
+[12288 - MSP2_BETAFLIGHT_BIND](#msp2_betaflight_bind)
+[12289 - MSP2_RX_BIND](#msp2_rx_bind)
## `MSP_API_VERSION (1 / 0x1)`
**Description:** Provides the MSP protocol version and the INAV API version.
@@ -2213,7 +2214,7 @@ For list of enums, see [Enum documentation page](https://github.com/iNavFlight/i
| `armingFlags` | `uint16_t` | 2 | Bitmask | Bitmask: Flight controller arming flags (`armingFlags`). Note: Truncated to 16 bits |
| `accCalibAxisFlags` | `uint8_t` | 1 | Bitmask | Bitmask: Accelerometer calibrated axes flags (`accGetCalibrationAxisFlags()`) |
-**Notes:** Superseded by `MSP2_INAV_STATUS` which provides the full 32-bit `armingFlags` and other enhancements.
+**Notes:** Superseded by `MSP2_INAV_STATUS` which provides the full 32-bit `armingFlags` and other enhancements. The `accCalibAxisFlags` field is not present in `MSP2_INAV_STATUS` but is available via `MSP_CALIBRATION_DATA`.
## `MSP_SENSOR_STATUS (151 / 0x97)`
**Description:** Provides the hardware status for each individual sensor system.
@@ -2280,6 +2281,7 @@ For list of enums, see [Enum documentation page](https://github.com/iNavFlight/i
| `hdop` | `uint16_t` | 2 | HDOP * 100 | Horizontal Dilution of Precision (`gpsSol.hdop`) |
| `eph` | `uint16_t` | 2 | cm | Estimated Horizontal Position Accuracy (`gpsSol.eph`) |
| `epv` | `uint16_t` | 2 | cm | Estimated Vertical Position Accuracy (`gpsSol.epv`) |
+| `hwVersion` | `uint32_t` | 4 | Version code | GPS hardware version (`gpsState.hwVersion`). Values: 500=UBLOX5, 600=UBLOX6, 700=UBLOX7, 800=UBLOX8, 900=UBLOX9, 1000=UBLOX10, 0=UNKNOWN |
**Notes:** Requires `USE_GPS`.
@@ -4650,14 +4652,14 @@ For list of enums, see [Enum documentation page](https://github.com/iNavFlight/i
**Notes:** Requires `rxConfig()->receiverType == RX_TYPE_SERIAL`. Requires `USE_SERIALRX_CRSF` or `USE_SERIALRX_SRXL2`. Calls `crsfBind()` or `srxl2Bind()` respectively. Returns error if receiver type or provider is not supported for binding.
## `MSP2_RX_BIND (12289 / 0x3001)`
-**Description:** Initiates binding for MSP receivers (mLRS).
-
+**Description:** Initiates binding for MSP receivers (mLRS).
+
**Request Payload:**
|Field|C Type|Size (Bytes)|Description|
|---|---|---|---|
| `port_id` | `uint8_t` | 1 | Port ID |
| `reserved_for_custom_use` | `uint8_t[3]` | 3 | Reserved for custom use |
-
+
**Reply Payload:**
|Field|C Type|Size (Bytes)|Description|
|---|---|---|---|
diff --git a/docs/development/msp/inav_enums.json b/docs/development/msp/inav_enums.json
index 63121588b83..eeaa393b7ef 100644
--- a/docs/development/msp/inav_enums.json
+++ b/docs/development/msp/inav_enums.json
@@ -12,7 +12,8 @@
"ACC_ICM42605": "8",
"ACC_BMI270": "9",
"ACC_LSM6DXX": "10",
- "ACC_FAKE": "11",
+ "ACC_ICM45686": "11",
+ "ACC_FAKE": "12",
"ACC_MAX": "ACC_FAKE"
},
"accEvent_t": {
@@ -801,53 +802,54 @@
"DEVHW_ICM42605": "7",
"DEVHW_BMI270": "8",
"DEVHW_LSM6D": "9",
- "DEVHW_MPU9250": "10",
- "DEVHW_BMP085": "11",
- "DEVHW_BMP280": "12",
- "DEVHW_MS5611": "13",
- "DEVHW_MS5607": "14",
- "DEVHW_LPS25H": "15",
- "DEVHW_SPL06": "16",
- "DEVHW_BMP388": "17",
- "DEVHW_DPS310": "18",
- "DEVHW_B2SMPB": "19",
- "DEVHW_HMC5883": "20",
- "DEVHW_AK8963": "21",
- "DEVHW_AK8975": "22",
- "DEVHW_IST8310_0": "23",
- "DEVHW_IST8310_1": "24",
- "DEVHW_IST8308": "25",
- "DEVHW_QMC5883": "26",
- "DEVHW_QMC5883P": "27",
- "DEVHW_MAG3110": "28",
- "DEVHW_LIS3MDL": "29",
- "DEVHW_RM3100": "30",
- "DEVHW_VCM5883": "31",
- "DEVHW_MLX90393": "32",
- "DEVHW_LM75_0": "33",
- "DEVHW_LM75_1": "34",
- "DEVHW_LM75_2": "35",
- "DEVHW_LM75_3": "36",
- "DEVHW_LM75_4": "37",
- "DEVHW_LM75_5": "38",
- "DEVHW_LM75_6": "39",
- "DEVHW_LM75_7": "40",
- "DEVHW_DS2482": "41",
- "DEVHW_MAX7456": "42",
- "DEVHW_SRF10": "43",
- "DEVHW_VL53L0X": "44",
- "DEVHW_VL53L1X": "45",
- "DEVHW_US42": "46",
- "DEVHW_TOF10120_I2C": "47",
- "DEVHW_TERARANGER_EVO_I2C": "48",
- "DEVHW_MS4525": "49",
- "DEVHW_DLVR": "50",
- "DEVHW_M25P16": "51",
- "DEVHW_W25N": "52",
- "DEVHW_UG2864": "53",
- "DEVHW_SDCARD": "54",
- "DEVHW_IRLOCK": "55",
- "DEVHW_PCF8574": "56"
+ "DEVHW_ICM45686": "10",
+ "DEVHW_MPU9250": "11",
+ "DEVHW_BMP085": "12",
+ "DEVHW_BMP280": "13",
+ "DEVHW_MS5611": "14",
+ "DEVHW_MS5607": "15",
+ "DEVHW_LPS25H": "16",
+ "DEVHW_SPL06": "17",
+ "DEVHW_BMP388": "18",
+ "DEVHW_DPS310": "19",
+ "DEVHW_B2SMPB": "20",
+ "DEVHW_HMC5883": "21",
+ "DEVHW_AK8963": "22",
+ "DEVHW_AK8975": "23",
+ "DEVHW_IST8310_0": "24",
+ "DEVHW_IST8310_1": "25",
+ "DEVHW_IST8308": "26",
+ "DEVHW_QMC5883": "27",
+ "DEVHW_QMC5883P": "28",
+ "DEVHW_MAG3110": "29",
+ "DEVHW_LIS3MDL": "30",
+ "DEVHW_RM3100": "31",
+ "DEVHW_VCM5883": "32",
+ "DEVHW_MLX90393": "33",
+ "DEVHW_LM75_0": "34",
+ "DEVHW_LM75_1": "35",
+ "DEVHW_LM75_2": "36",
+ "DEVHW_LM75_3": "37",
+ "DEVHW_LM75_4": "38",
+ "DEVHW_LM75_5": "39",
+ "DEVHW_LM75_6": "40",
+ "DEVHW_LM75_7": "41",
+ "DEVHW_DS2482": "42",
+ "DEVHW_MAX7456": "43",
+ "DEVHW_SRF10": "44",
+ "DEVHW_VL53L0X": "45",
+ "DEVHW_VL53L1X": "46",
+ "DEVHW_US42": "47",
+ "DEVHW_TOF10120_I2C": "48",
+ "DEVHW_TERARANGER_EVO_I2C": "49",
+ "DEVHW_MS4525": "50",
+ "DEVHW_DLVR": "51",
+ "DEVHW_M25P16": "52",
+ "DEVHW_W25N": "53",
+ "DEVHW_UG2864": "54",
+ "DEVHW_SDCARD": "55",
+ "DEVHW_IRLOCK": "56",
+ "DEVHW_PCF8574": "57"
},
"deviceFlags_e": {
"_source": "inav/src/main/drivers/bus.h",
@@ -1528,7 +1530,8 @@
"GYRO_ICM42605": "8",
"GYRO_BMI270": "9",
"GYRO_LSM6DXX": "10",
- "GYRO_FAKE": "11"
+ "GYRO_ICM45686": "11",
+ "GYRO_FAKE": "12"
},
"HardwareMotorTypes_e": {
"_source": "inav/src/main/drivers/pwm_esc_detect.h",
@@ -1862,7 +1865,8 @@
"LED_MODE_ANGLE": "3",
"LED_MODE_MAG": "4",
"LED_MODE_BARO": "5",
- "LED_SPECIAL": "6"
+ "LED_MODE_LOITER": "6",
+ "LED_SPECIAL": "7"
},
"ledOverlayId_e": {
"_source": "inav/src/main/io/ledstrip.h",
@@ -2238,19 +2242,17 @@
"MAG_FAKE": "16",
"MAG_MAX": "MAG_FAKE"
},
- "mavFrameSupportMask_e": {
- "_source": "inav/src/main/telemetry/mavlink.h",
- "MAV_FRAME_SUPPORTED_NONE": "0",
- "MAV_FRAME_SUPPORTED_GLOBAL": "(1 << 0)",
- "MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT": "(1 << 1)",
- "MAV_FRAME_SUPPORTED_GLOBAL_INT": "(1 << 2)",
- "MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT_INT": "(1 << 3)"
- },
"mavlinkAutopilotType_e": {
"_source": "inav/src/main/telemetry/telemetry.h",
"MAVLINK_AUTOPILOT_GENERIC": "0",
"MAVLINK_AUTOPILOT_ARDUPILOT": "1"
},
+ "mavlinkFcDispatchResult_e": {
+ "_source": "inav/src/main/fc/fc_mavlink.h",
+ "MAVLINK_FC_DISPATCH_NOT_HANDLED": "0",
+ "MAVLINK_FC_DISPATCH_HANDLED_NO_ACTIVITY": "1",
+ "MAVLINK_FC_DISPATCH_HANDLED_ACTIVITY": "2"
+ },
"mavlinkRadio_e": {
"_source": "inav/src/main/telemetry/telemetry.h",
"MAVLINK_RADIO_GENERIC": "0",
@@ -2336,8 +2338,7 @@
"MULTI_FUNC_3": "3",
"MULTI_FUNC_4": "4",
"MULTI_FUNC_5": "5",
- "MULTI_FUNC_6": "6",
- "MULTI_FUNC_END": "7"
+ "MULTI_FUNC_END": "6"
},
"multiFunctionFlags_e": {
"_source": "inav/src/main/fc/multifunction.h",
diff --git a/docs/development/msp/inav_enums_ref.md b/docs/development/msp/inav_enums_ref.md
index a12fd374756..e0048e8c621 100644
--- a/docs/development/msp/inav_enums_ref.md
+++ b/docs/development/msp/inav_enums_ref.md
@@ -173,8 +173,8 @@
- [ltm_modes_e](#enum-ltm_modes_e)
- [ltmUpdateRate_e](#enum-ltmupdaterate_e)
- [magSensor_e](#enum-magsensor_e)
-- [mavFrameSupportMask_e](#enum-mavframesupportmask_e)
- [mavlinkAutopilotType_e](#enum-mavlinkautopilottype_e)
+- [mavlinkFcDispatchResult_e](#enum-mavlinkfcdispatchresult_e)
- [mavlinkRadio_e](#enum-mavlinkradio_e)
- [measurementSteps_e](#enum-measurementsteps_e)
- [mixerProfileATRequest_e](#enum-mixerprofileatrequest_e)
@@ -371,7 +371,8 @@
| `ACC_ICM42605` | 8 | |
| `ACC_BMI270` | 9 | |
| `ACC_LSM6DXX` | 10 | |
-| `ACC_FAKE` | 11 | |
+| `ACC_ICM45686` | 11 | |
+| `ACC_FAKE` | 12 | |
| `ACC_MAX` | ACC_FAKE | |
---
@@ -1408,53 +1409,54 @@
| `DEVHW_ICM42605` | 7 | |
| `DEVHW_BMI270` | 8 | |
| `DEVHW_LSM6D` | 9 | |
-| `DEVHW_MPU9250` | 10 | |
-| `DEVHW_BMP085` | 11 | |
-| `DEVHW_BMP280` | 12 | |
-| `DEVHW_MS5611` | 13 | |
-| `DEVHW_MS5607` | 14 | |
-| `DEVHW_LPS25H` | 15 | |
-| `DEVHW_SPL06` | 16 | |
-| `DEVHW_BMP388` | 17 | |
-| `DEVHW_DPS310` | 18 | |
-| `DEVHW_B2SMPB` | 19 | |
-| `DEVHW_HMC5883` | 20 | |
-| `DEVHW_AK8963` | 21 | |
-| `DEVHW_AK8975` | 22 | |
-| `DEVHW_IST8310_0` | 23 | |
-| `DEVHW_IST8310_1` | 24 | |
-| `DEVHW_IST8308` | 25 | |
-| `DEVHW_QMC5883` | 26 | |
-| `DEVHW_QMC5883P` | 27 | |
-| `DEVHW_MAG3110` | 28 | |
-| `DEVHW_LIS3MDL` | 29 | |
-| `DEVHW_RM3100` | 30 | |
-| `DEVHW_VCM5883` | 31 | |
-| `DEVHW_MLX90393` | 32 | |
-| `DEVHW_LM75_0` | 33 | |
-| `DEVHW_LM75_1` | 34 | |
-| `DEVHW_LM75_2` | 35 | |
-| `DEVHW_LM75_3` | 36 | |
-| `DEVHW_LM75_4` | 37 | |
-| `DEVHW_LM75_5` | 38 | |
-| `DEVHW_LM75_6` | 39 | |
-| `DEVHW_LM75_7` | 40 | |
-| `DEVHW_DS2482` | 41 | |
-| `DEVHW_MAX7456` | 42 | |
-| `DEVHW_SRF10` | 43 | |
-| `DEVHW_VL53L0X` | 44 | |
-| `DEVHW_VL53L1X` | 45 | |
-| `DEVHW_US42` | 46 | |
-| `DEVHW_TOF10120_I2C` | 47 | |
-| `DEVHW_TERARANGER_EVO_I2C` | 48 | |
-| `DEVHW_MS4525` | 49 | |
-| `DEVHW_DLVR` | 50 | |
-| `DEVHW_M25P16` | 51 | |
-| `DEVHW_W25N` | 52 | |
-| `DEVHW_UG2864` | 53 | |
-| `DEVHW_SDCARD` | 54 | |
-| `DEVHW_IRLOCK` | 55 | |
-| `DEVHW_PCF8574` | 56 | |
+| `DEVHW_ICM45686` | 10 | |
+| `DEVHW_MPU9250` | 11 | |
+| `DEVHW_BMP085` | 12 | |
+| `DEVHW_BMP280` | 13 | |
+| `DEVHW_MS5611` | 14 | |
+| `DEVHW_MS5607` | 15 | |
+| `DEVHW_LPS25H` | 16 | |
+| `DEVHW_SPL06` | 17 | |
+| `DEVHW_BMP388` | 18 | |
+| `DEVHW_DPS310` | 19 | |
+| `DEVHW_B2SMPB` | 20 | |
+| `DEVHW_HMC5883` | 21 | |
+| `DEVHW_AK8963` | 22 | |
+| `DEVHW_AK8975` | 23 | |
+| `DEVHW_IST8310_0` | 24 | |
+| `DEVHW_IST8310_1` | 25 | |
+| `DEVHW_IST8308` | 26 | |
+| `DEVHW_QMC5883` | 27 | |
+| `DEVHW_QMC5883P` | 28 | |
+| `DEVHW_MAG3110` | 29 | |
+| `DEVHW_LIS3MDL` | 30 | |
+| `DEVHW_RM3100` | 31 | |
+| `DEVHW_VCM5883` | 32 | |
+| `DEVHW_MLX90393` | 33 | |
+| `DEVHW_LM75_0` | 34 | |
+| `DEVHW_LM75_1` | 35 | |
+| `DEVHW_LM75_2` | 36 | |
+| `DEVHW_LM75_3` | 37 | |
+| `DEVHW_LM75_4` | 38 | |
+| `DEVHW_LM75_5` | 39 | |
+| `DEVHW_LM75_6` | 40 | |
+| `DEVHW_LM75_7` | 41 | |
+| `DEVHW_DS2482` | 42 | |
+| `DEVHW_MAX7456` | 43 | |
+| `DEVHW_SRF10` | 44 | |
+| `DEVHW_VL53L0X` | 45 | |
+| `DEVHW_VL53L1X` | 46 | |
+| `DEVHW_US42` | 47 | |
+| `DEVHW_TOF10120_I2C` | 48 | |
+| `DEVHW_TERARANGER_EVO_I2C` | 49 | |
+| `DEVHW_MS4525` | 50 | |
+| `DEVHW_DLVR` | 51 | |
+| `DEVHW_M25P16` | 52 | |
+| `DEVHW_W25N` | 53 | |
+| `DEVHW_UG2864` | 54 | |
+| `DEVHW_SDCARD` | 55 | |
+| `DEVHW_IRLOCK` | 56 | |
+| `DEVHW_PCF8574` | 57 | |
---
## `deviceFlags_e`
@@ -2490,7 +2492,8 @@
| `GYRO_ICM42605` | 8 | |
| `GYRO_BMI270` | 9 | |
| `GYRO_LSM6DXX` | 10 | |
-| `GYRO_FAKE` | 11 | |
+| `GYRO_ICM45686` | 11 | |
+| `GYRO_FAKE` | 12 | |
---
## `HardwareMotorTypes_e`
@@ -2926,7 +2929,8 @@
| `LED_MODE_ANGLE` | 3 | |
| `LED_MODE_MAG` | 4 | |
| `LED_MODE_BARO` | 5 | |
-| `LED_SPECIAL` | 6 | |
+| `LED_MODE_LOITER` | 6 | |
+| `LED_SPECIAL` | 7 | |
---
## `ledOverlayId_e`
@@ -3376,27 +3380,25 @@
| `MAG_MAX` | MAG_FAKE | |
---
-## `mavFrameSupportMask_e`
+## `mavlinkAutopilotType_e`
-> Source: ../../../src/main/telemetry/mavlink.h
+> Source: ../../../src/main/telemetry/telemetry.h
| Enumerator | Value | Condition |
|---|---:|---|
-| `MAV_FRAME_SUPPORTED_NONE` | 0 | |
-| `MAV_FRAME_SUPPORTED_GLOBAL` | (1 << 0) | |
-| `MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT` | (1 << 1) | |
-| `MAV_FRAME_SUPPORTED_GLOBAL_INT` | (1 << 2) | |
-| `MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT_INT` | (1 << 3) | |
+| `MAVLINK_AUTOPILOT_GENERIC` | 0 | |
+| `MAVLINK_AUTOPILOT_ARDUPILOT` | 1 | |
---
-## `mavlinkAutopilotType_e`
+## `mavlinkFcDispatchResult_e`
-> Source: ../../../src/main/telemetry/telemetry.h
+> Source: ../../../src/main/fc/fc_mavlink.h
| Enumerator | Value | Condition |
|---|---:|---|
-| `MAVLINK_AUTOPILOT_GENERIC` | 0 | |
-| `MAVLINK_AUTOPILOT_ARDUPILOT` | 1 | |
+| `MAVLINK_FC_DISPATCH_NOT_HANDLED` | 0 | |
+| `MAVLINK_FC_DISPATCH_HANDLED_NO_ACTIVITY` | 1 | |
+| `MAVLINK_FC_DISPATCH_HANDLED_ACTIVITY` | 2 | |
---
## `mavlinkRadio_e`
@@ -3548,8 +3550,7 @@
| `MULTI_FUNC_3` | 3 | |
| `MULTI_FUNC_4` | 4 | |
| `MULTI_FUNC_5` | 5 | |
-| `MULTI_FUNC_6` | 6 | |
-| `MULTI_FUNC_END` | 7 | |
+| `MULTI_FUNC_END` | 6 | |
---
## `multiFunctionFlags_e`
diff --git a/docs/development/msp/msp_messages.checksum b/docs/development/msp/msp_messages.checksum
index 14e143e04b9..60780228071 100644
--- a/docs/development/msp/msp_messages.checksum
+++ b/docs/development/msp/msp_messages.checksum
@@ -1 +1 @@
-7146802c1d6c89bce6aeda0d5e95c137
+fd564ac26b85f236c4cf3f41bfa0e7c1
diff --git a/src/main/CMakeLists.txt b/src/main/CMakeLists.txt
index eab317a2366..b8303915eaf 100755
--- a/src/main/CMakeLists.txt
+++ b/src/main/CMakeLists.txt
@@ -395,6 +395,10 @@ main_sources(COMMON_SRC
io/osd/custom_elements.c
+ mavlink/mavlink_command.c
+ mavlink/mavlink_command.h
+ mavlink/mavlink_guided.c
+ mavlink/mavlink_guided.h
mavlink/mavlink_internal.h
mavlink/mavlink_mission.c
mavlink/mavlink_mission.h
diff --git a/src/main/fc/fc_mavlink.c b/src/main/fc/fc_mavlink.c
index 1d413bf7e08..f59b91cd690 100644
--- a/src/main/fc/fc_mavlink.c
+++ b/src/main/fc/fc_mavlink.c
@@ -2,6 +2,8 @@
#include "fc/fc_mavlink.h"
+#include "mavlink/mavlink_command.h"
+#include "mavlink/mavlink_guided.h"
#include "mavlink/mavlink_mission.h"
#include "mavlink/mavlink_runtime.h"
#include "mavlink/mavlink_streams.h"
@@ -141,345 +143,6 @@ static bool handleIncoming_TUNNEL(uint8_t ingressPortIndex)
return handled;
}
-static bool mavlinkIsLocalTarget(uint8_t targetSystem, uint8_t targetComponent)
-{
- if (targetSystem != 0 && targetSystem != mavSystemId) {
- return false;
- }
-
- if (targetComponent != 0 && targetComponent != mavComponentId) {
- return false;
- }
-
- return true;
-}
-
-static void mavlinkSendCommandAck(uint16_t command, MAV_RESULT result, uint8_t ackTargetSystem, uint8_t ackTargetComponent)
-{
- mavlink_msg_command_ack_pack(mavSystemId, mavComponentId, &mavSendMsg,
- command,
- result,
- 0,
- 0,
- ackTargetSystem,
- ackTargetComponent);
- mavlinkSendMessage();
-}
-
-static bool handleIncoming_COMMAND(uint8_t targetSystem, uint8_t targetComponent, uint8_t ackTargetSystem, uint8_t ackTargetComponent, uint16_t command, uint8_t frame, float param1, float param2, float param3, float param4, float latitudeDeg, float longitudeDeg, float altitudeMeters)
-{
- if (!mavlinkIsLocalTarget(targetSystem, targetComponent)) {
- return false;
- }
- UNUSED(param3);
-
- switch (command) {
- case MAV_CMD_DO_REPOSITION:
- if (!mavlinkFrameIsSupported(frame,
- MAV_FRAME_SUPPORTED_GLOBAL |
- MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT |
- MAV_FRAME_SUPPORTED_GLOBAL_INT |
- MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT_INT)) {
- mavlinkSendCommandAck(command, MAV_RESULT_UNSUPPORTED, ackTargetSystem, ackTargetComponent);
- return true;
- }
-
- if (isnan(latitudeDeg) || isnan(longitudeDeg)) {
- mavlinkSendCommandAck(command, MAV_RESULT_FAILED, ackTargetSystem, ackTargetComponent);
- return true;
- }
-
- if (isGCSValid()) {
- navWaypoint_t wp = {0};
- wp.action = NAV_WP_ACTION_WAYPOINT;
- wp.lat = (int32_t)(latitudeDeg * 1e7f);
- wp.lon = (int32_t)(longitudeDeg * 1e7f);
- wp.alt = (int32_t)(altitudeMeters * 100.0f);
- if (!isnan(param4) && param4 >= 0.0f && param4 < 360.0f) {
- wp.p1 = (int16_t)param4;
- } else {
- wp.p1 = 0;
- }
- wp.p2 = 0;
- wp.p3 = mavlinkFrameUsesAbsoluteAltitude(frame) ? NAV_WP_ALTMODE : 0;
- wp.flag = 0;
-
- setWaypoint(255, &wp);
-
- mavlinkSendCommandAck(command, MAV_RESULT_ACCEPTED, ackTargetSystem, ackTargetComponent);
- } else {
- mavlinkSendCommandAck(command, MAV_RESULT_DENIED, ackTargetSystem, ackTargetComponent);
- }
- return true;
- case MAV_CMD_DO_CHANGE_ALTITUDE:
- {
- const MAV_RESULT result = mavlinkSetAltitudeTargetFromFrame((uint8_t)lrintf(param2), param1);
- mavlinkSendCommandAck(command, result, ackTargetSystem, ackTargetComponent);
- return true;
- }
- case MAV_CMD_CONDITION_YAW:
- {
- if (!(navGetCurrentStateFlags() & NAV_CTL_YAW)) {
- mavlinkSendCommandAck(command, MAV_RESULT_DENIED, ackTargetSystem, ackTargetComponent);
- return true;
- }
-
- int32_t targetHeadingCd = wrap_36000((int32_t)lrintf(param1 * 100.0f));
-
- if (param4 != 0.0f) {
- const int32_t currentHeadingCd = STATE(AIRPLANE) ? posControl.actualState.cog : posControl.actualState.yaw;
- const int32_t headingChangeCd = (int32_t)lrintf(fabsf(param1) * 100.0f);
-
- if (param3 < 0.0f) {
- targetHeadingCd = wrap_36000(currentHeadingCd - headingChangeCd);
- } else {
- targetHeadingCd = wrap_36000(currentHeadingCd + headingChangeCd);
- }
- }
-
- updateHeadingHoldTarget(CENTIDEGREES_TO_DEGREES(targetHeadingCd));
- posControl.desiredState.yaw = targetHeadingCd;
- posControl.cruise.course = targetHeadingCd;
- posControl.cruise.previousCourse = targetHeadingCd;
-
- mavlinkSendCommandAck(command, MAV_RESULT_ACCEPTED, ackTargetSystem, ackTargetComponent);
- return true;
- }
- case MAV_CMD_SET_MESSAGE_INTERVAL:
- {
- mavlinkPeriodicMessage_e periodicMessage;
- MAV_RESULT result = MAV_RESULT_UNSUPPORTED;
-
- if (mavlinkPeriodicMessageFromMessageId((uint16_t)param1, &periodicMessage)) {
- if (param2 == 0.0f) {
- mavlinkSetMessageOverrideIntervalUs(periodicMessage, 0);
- result = MAV_RESULT_ACCEPTED;
- } else if (param2 < 0.0f) {
- mavlinkSetMessageOverrideIntervalUs(periodicMessage, -1);
- result = MAV_RESULT_ACCEPTED;
- } else {
- uint32_t intervalUs = (uint32_t)param2;
- if (intervalUs > 0) {
- const uint32_t minIntervalUs = 1000000UL / TELEMETRY_MAVLINK_MAXRATE;
- if (intervalUs < minIntervalUs) {
- intervalUs = minIntervalUs;
- }
-
- mavlinkSetMessageOverrideIntervalUs(periodicMessage, (int32_t)intervalUs);
- result = MAV_RESULT_ACCEPTED;
- }
- }
- }
-
- mavlinkSendCommandAck(command, result, ackTargetSystem, ackTargetComponent);
- return true;
- }
- case MAV_CMD_GET_MESSAGE_INTERVAL:
- {
- mavlinkPeriodicMessage_e periodicMessage;
- if (!mavlinkPeriodicMessageFromMessageId((uint16_t)param1, &periodicMessage)) {
- mavlinkSendCommandAck(command, MAV_RESULT_UNSUPPORTED, ackTargetSystem, ackTargetComponent);
- return true;
- }
-
- mavlink_msg_message_interval_pack(
- mavSystemId,
- mavComponentId,
- &mavSendMsg,
- (uint16_t)param1,
- mavlinkMessageIntervalUs(periodicMessage));
- mavlinkSendMessage();
-
- mavlinkSendCommandAck(command, MAV_RESULT_ACCEPTED, ackTargetSystem, ackTargetComponent);
- return true;
- }
- case MAV_CMD_CONTROL_HIGH_LATENCY:
- if (param1 == 0.0f || param1 == 1.0f) {
- if (mavlinkGetProtocolVersion() == 1 && param1 > 0.5f) {
- mavlinkSendCommandAck(command, MAV_RESULT_UNSUPPORTED, ackTargetSystem, ackTargetComponent);
- return true;
- }
-
- mavActivePort->highLatencyEnabled = param1 > 0.5f;
- if (mavActivePort->highLatencyEnabled) {
- mavActivePort->lastHighLatencyMessageUs = 0;
- }
- mavlinkSendCommandAck(command, MAV_RESULT_ACCEPTED, ackTargetSystem, ackTargetComponent);
- } else {
- mavlinkSendCommandAck(command, MAV_RESULT_FAILED, ackTargetSystem, ackTargetComponent);
- }
- return true;
- case MAV_CMD_REQUEST_PROTOCOL_VERSION:
- if (mavlinkGetProtocolVersion() == 1) {
- mavlinkSendCommandAck(command, MAV_RESULT_UNSUPPORTED, ackTargetSystem, ackTargetComponent);
- } else {
- mavlinkSendProtocolVersion();
- mavlinkSendCommandAck(command, MAV_RESULT_ACCEPTED, ackTargetSystem, ackTargetComponent);
- }
- return true;
- case MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES:
- if (mavlinkGetProtocolVersion() == 1) {
- mavlinkSendCommandAck(command, MAV_RESULT_UNSUPPORTED, ackTargetSystem, ackTargetComponent);
- } else {
- mavlinkSendAutopilotVersion();
- mavlinkSendCommandAck(command, MAV_RESULT_ACCEPTED, ackTargetSystem, ackTargetComponent);
- }
- return true;
- case MAV_CMD_REQUEST_MESSAGE:
- {
- const bool sent = mavlinkSendRequestedMessage((uint16_t)param1);
- mavlinkSendCommandAck(command, sent ? MAV_RESULT_ACCEPTED : MAV_RESULT_UNSUPPORTED, ackTargetSystem, ackTargetComponent);
- return true;
- }
-#ifdef USE_GPS
- case MAV_CMD_GET_HOME_POSITION:
- if (mavlinkSendRequestedMessage(MAVLINK_MSG_ID_HOME_POSITION)) {
- mavlinkSendCommandAck(command, MAV_RESULT_ACCEPTED, ackTargetSystem, ackTargetComponent);
- } else {
- mavlinkSendCommandAck(command, MAV_RESULT_FAILED, ackTargetSystem, ackTargetComponent);
- }
- return true;
-#endif
- default:
- mavlinkSendCommandAck(command, MAV_RESULT_UNSUPPORTED, ackTargetSystem, ackTargetComponent);
- return true;
- }
-}
-
-static bool handleIncoming_COMMAND_INT(void)
-{
- mavlink_command_int_t msg;
- mavlink_msg_command_int_decode(&mavlinkContext.recvMsg, &msg);
-
- return handleIncoming_COMMAND(msg.target_system, msg.target_component, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, msg.command, msg.frame, msg.param1, msg.param2, msg.param3, msg.param4, (float)msg.x / 1e7f, (float)msg.y / 1e7f, msg.z);
-}
-
-static bool handleIncoming_COMMAND_LONG(void)
-{
- mavlink_command_long_t msg;
- mavlink_msg_command_long_decode(&mavlinkContext.recvMsg, &msg);
-
- // COMMAND_LONG has no frame field; location commands are WGS84 global by definition.
- return handleIncoming_COMMAND(msg.target_system, msg.target_component, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, msg.command, MAV_FRAME_GLOBAL, msg.param1, msg.param2, msg.param3, msg.param4, msg.param5, msg.param6, msg.param7);
-}
-
-static bool handleIncoming_REQUEST_DATA_STREAM(void)
-{
- mavlink_request_data_stream_t msg;
- mavlink_msg_request_data_stream_decode(&mavlinkContext.recvMsg, &msg);
-
- if (!mavlinkIsLocalTarget(msg.target_system, msg.target_component)) {
- return false;
- }
-
- uint8_t rate = 0;
- if (msg.start_stop != 0) {
- rate = (uint8_t)msg.req_message_rate;
- if (rate > TELEMETRY_MAVLINK_MAXRATE) {
- rate = TELEMETRY_MAVLINK_MAXRATE;
- }
- }
-
- if (msg.req_stream_id == MAV_DATA_STREAM_ALL) {
- mavlinkSetStreamRate(MAV_DATA_STREAM_EXTENDED_STATUS, rate);
- mavlinkSetStreamRate(MAV_DATA_STREAM_RC_CHANNELS, rate);
- mavlinkSetStreamRate(MAV_DATA_STREAM_POSITION, rate);
- mavlinkSetStreamRate(MAV_DATA_STREAM_EXTRA1, rate);
- mavlinkSetStreamRate(MAV_DATA_STREAM_EXTRA2, rate);
- mavlinkSetStreamRate(MAV_DATA_STREAM_EXTRA3, rate);
- mavlinkSetStreamRate(MAV_DATA_STREAM_EXTENDED_SYS_STATE, rate);
- return true;
- }
-
- mavlinkSetStreamRate(msg.req_stream_id, rate);
- return true;
-}
-
-static bool handleIncoming_SET_POSITION_TARGET_GLOBAL_INT(void)
-{
- mavlink_set_position_target_global_int_t msg;
- mavlink_msg_set_position_target_global_int_decode(&mavlinkContext.recvMsg, &msg);
-
- if (!mavlinkIsLocalTarget(msg.target_system, msg.target_component)) {
- return false;
- }
-
- uint8_t frame = msg.coordinate_frame;
- if (!mavlinkFrameIsSupported(frame,
- MAV_FRAME_SUPPORTED_GLOBAL |
- MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT |
- MAV_FRAME_SUPPORTED_GLOBAL_INT |
- MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT_INT)) {
- return true;
- }
-
- const uint16_t typeMask = msg.type_mask;
- const bool xIgnored = (typeMask & POSITION_TARGET_TYPEMASK_X_IGNORE) != 0;
- const bool yIgnored = (typeMask & POSITION_TARGET_TYPEMASK_Y_IGNORE) != 0;
- const bool zIgnored = (typeMask & POSITION_TARGET_TYPEMASK_Z_IGNORE) != 0;
-
- // Altitude-only SET_POSITION_TARGET_GLOBAL_INT mirrors MAV_CMD_DO_CHANGE_ALTITUDE semantics.
- if (xIgnored && yIgnored && !zIgnored) {
- if (isGCSValid()) {
- mavlinkSetAltitudeTargetFromFrame(frame, msg.alt);
- }
- return true;
- }
-
- if (xIgnored || yIgnored) {
- return true;
- }
-
- if (isGCSValid()) {
- navWaypoint_t wp = {0};
- wp.action = NAV_WP_ACTION_WAYPOINT;
- wp.lat = msg.lat_int;
- wp.lon = msg.lon_int;
- wp.alt = zIgnored ? 0 : (int32_t)(msg.alt * 100.0f);
- wp.p1 = 0;
- wp.p2 = 0;
- wp.p3 = mavlinkFrameUsesAbsoluteAltitude(frame) ? NAV_WP_ALTMODE : 0;
- wp.flag = 0;
-
- setWaypoint(255, &wp);
- }
-
- return true;
-}
-
-static bool handleIncoming_SET_POSITION_TARGET_LOCAL_NED(void)
-{
- mavlink_set_position_target_local_ned_t msg;
- mavlink_msg_set_position_target_local_ned_decode(&mavlinkContext.recvMsg, &msg);
-
- if (!mavlinkIsLocalTarget(msg.target_system, msg.target_component)) {
- return false;
- }
-
- if (msg.coordinate_frame != MAV_FRAME_LOCAL_OFFSET_NED) {
- return true;
- }
-
- const uint16_t typeMask = msg.type_mask;
- const bool xIgnored = (typeMask & POSITION_TARGET_TYPEMASK_X_IGNORE) != 0;
- const bool yIgnored = (typeMask & POSITION_TARGET_TYPEMASK_Y_IGNORE) != 0;
- const bool zIgnored = (typeMask & POSITION_TARGET_TYPEMASK_Z_IGNORE) != 0;
-
- if (!isGCSValid() || zIgnored) {
- return true;
- }
-
- if ((!xIgnored && fabsf(msg.x) > 0.01f) || (!yIgnored && fabsf(msg.y) > 0.01f)) {
- return true;
- }
-
- const int32_t targetAltitudeCm = (int32_t)lrintf((float)getEstimatedActualPosition(Z) - (msg.z * 100.0f));
- navigationSetAltitudeTargetWithDatum(NAV_WP_TAKEOFF_DATUM, targetAltitudeCm);
-
- return true;
-}
-
-
static bool handleIncoming_RC_CHANNELS_OVERRIDE(void) {
mavlink_rc_channels_override_t msg;
mavlink_msg_rc_channels_override_decode(&mavlinkContext.recvMsg, &msg);
@@ -491,12 +154,15 @@ static bool handleIncoming_PARAM_REQUEST_LIST(void) {
mavlink_param_request_list_t msg;
mavlink_msg_param_request_list_decode(&mavlinkContext.recvMsg, &msg);
- // Respond that we don't have any parameters to force Mission Planner to give up quickly
- if (mavlinkIsLocalTarget(msg.target_system, msg.target_component)) {
- // mavlink_msg_param_value_pack(system_id, component_id, msg, param_value->param_id, param_value->param_value, param_value->param_type, param_value->param_count, param_value->param_index);
- mavlink_msg_param_value_pack(mavSystemId, mavComponentId, &mavSendMsg, 0, 0, 0, 0, 0);
- mavlinkSendMessage();
+ if (msg.target_system != 0 && msg.target_system != mavSystemId) {
+ return false;
+ }
+ if (msg.target_component != 0 && msg.target_component != mavComponentId) {
+ return false;
}
+
+ mavlink_msg_param_value_pack(mavSystemId, mavComponentId, &mavSendMsg, 0, 0, 0, 0, 0);
+ mavlinkSendMessage();
return true;
}
@@ -505,7 +171,6 @@ static void mavlinkParseRxStats(const mavlink_radio_status_t *msg) {
case MAVLINK_RADIO_NONE:
break;
case MAVLINK_RADIO_SIK:
- // rssi scaling info from: https://ardupilot.org/rover/docs/common-3dr-radio-advanced-configuration-and-technical-information.html
rxLinkStatistics.uplinkRSSI = (msg->rssi / 1.9) - 127;
rxLinkStatistics.uplinkSNR = msg->noise / 1.9;
rxLinkStatistics.uplinkLQ = msg->rssi != 255 ? scaleRange(msg->rssi, 0, 254, 0, 100) : 0;
@@ -534,7 +199,7 @@ static bool handleIncoming_RADIO_STATUS(void) {
mavActivePort->txbuffValid = false;
mavActivePort->txbuffFree = 100;
}
-
+
if (rxConfig()->receiverType == RX_TYPE_SERIAL &&
rxConfig()->serialrx_provider == SERIALRX_MAVLINK) {
mavlinkParseRxStats(&msg);
@@ -543,22 +208,6 @@ static bool handleIncoming_RADIO_STATUS(void) {
return true;
}
-static bool handleIncoming_HEARTBEAT(void) {
- mavlink_heartbeat_t msg;
- mavlink_msg_heartbeat_decode(&mavlinkContext.recvMsg, &msg);
-
- switch (msg.type) {
-#ifdef USE_ADSB
- case MAV_TYPE_ADSB:
- return adsbHeartbeat();
-#endif
- default:
- break;
- }
-
- return false;
-}
-
#ifdef USE_ADSB
static bool handleIncoming_ADSB_VEHICLE(void) {
mavlink_adsb_vehicle_t msg;
@@ -591,7 +240,7 @@ mavlinkFcDispatchResult_e mavlinkFcDispatchIncomingMessage(uint8_t ingressPortIn
switch (mavlinkContext.recvMsg.msgid) {
case MAVLINK_MSG_ID_HEARTBEAT:
- return handleIncoming_HEARTBEAT() ? MAVLINK_FC_DISPATCH_HANDLED_ACTIVITY : MAVLINK_FC_DISPATCH_NOT_HANDLED;
+ return mavlinkHandleIncomingHeartbeat() ? MAVLINK_FC_DISPATCH_HANDLED_ACTIVITY : MAVLINK_FC_DISPATCH_NOT_HANDLED;
case MAVLINK_MSG_ID_PARAM_REQUEST_LIST:
return handleIncoming_PARAM_REQUEST_LIST() ? MAVLINK_FC_DISPATCH_HANDLED_ACTIVITY : MAVLINK_FC_DISPATCH_NOT_HANDLED;
case MAVLINK_MSG_ID_MISSION_CLEAR_ALL:
@@ -605,22 +254,22 @@ mavlinkFcDispatchResult_e mavlinkFcDispatchIncomingMessage(uint8_t ingressPortIn
case MAVLINK_MSG_ID_MISSION_REQUEST_LIST:
return mavlinkHandleIncomingMissionRequestList() ? MAVLINK_FC_DISPATCH_HANDLED_ACTIVITY : MAVLINK_FC_DISPATCH_NOT_HANDLED;
case MAVLINK_MSG_ID_COMMAND_LONG:
- return handleIncoming_COMMAND_LONG() ? MAVLINK_FC_DISPATCH_HANDLED_ACTIVITY : MAVLINK_FC_DISPATCH_NOT_HANDLED;
+ return mavlinkHandleIncomingCommandLong() ? MAVLINK_FC_DISPATCH_HANDLED_ACTIVITY : MAVLINK_FC_DISPATCH_NOT_HANDLED;
case MAVLINK_MSG_ID_COMMAND_INT:
- return handleIncoming_COMMAND_INT() ? MAVLINK_FC_DISPATCH_HANDLED_ACTIVITY : MAVLINK_FC_DISPATCH_NOT_HANDLED;
+ return mavlinkHandleIncomingCommandInt() ? MAVLINK_FC_DISPATCH_HANDLED_ACTIVITY : MAVLINK_FC_DISPATCH_NOT_HANDLED;
case MAVLINK_MSG_ID_MISSION_REQUEST:
return mavlinkHandleIncomingMissionRequest() ? MAVLINK_FC_DISPATCH_HANDLED_ACTIVITY : MAVLINK_FC_DISPATCH_NOT_HANDLED;
case MAVLINK_MSG_ID_MISSION_REQUEST_INT:
return mavlinkHandleIncomingMissionRequestInt() ? MAVLINK_FC_DISPATCH_HANDLED_ACTIVITY : MAVLINK_FC_DISPATCH_NOT_HANDLED;
case MAVLINK_MSG_ID_REQUEST_DATA_STREAM:
- return handleIncoming_REQUEST_DATA_STREAM() ? MAVLINK_FC_DISPATCH_HANDLED_ACTIVITY : MAVLINK_FC_DISPATCH_NOT_HANDLED;
+ return mavlinkHandleIncomingRequestDataStream() ? MAVLINK_FC_DISPATCH_HANDLED_ACTIVITY : MAVLINK_FC_DISPATCH_NOT_HANDLED;
case MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE:
handleIncoming_RC_CHANNELS_OVERRIDE();
return MAVLINK_FC_DISPATCH_HANDLED_NO_ACTIVITY;
case MAVLINK_MSG_ID_SET_POSITION_TARGET_LOCAL_NED:
- return handleIncoming_SET_POSITION_TARGET_LOCAL_NED() ? MAVLINK_FC_DISPATCH_HANDLED_ACTIVITY : MAVLINK_FC_DISPATCH_NOT_HANDLED;
+ return mavlinkHandleIncomingSetPositionTargetLocalNed() ? MAVLINK_FC_DISPATCH_HANDLED_ACTIVITY : MAVLINK_FC_DISPATCH_NOT_HANDLED;
case MAVLINK_MSG_ID_SET_POSITION_TARGET_GLOBAL_INT:
- return handleIncoming_SET_POSITION_TARGET_GLOBAL_INT() ? MAVLINK_FC_DISPATCH_HANDLED_ACTIVITY : MAVLINK_FC_DISPATCH_NOT_HANDLED;
+ return mavlinkHandleIncomingSetPositionTargetGlobalInt() ? MAVLINK_FC_DISPATCH_HANDLED_ACTIVITY : MAVLINK_FC_DISPATCH_NOT_HANDLED;
#ifdef USE_ADSB
case MAVLINK_MSG_ID_ADSB_VEHICLE:
return handleIncoming_ADSB_VEHICLE() ? MAVLINK_FC_DISPATCH_HANDLED_ACTIVITY : MAVLINK_FC_DISPATCH_NOT_HANDLED;
diff --git a/src/main/mavlink/mavlink_command.c b/src/main/mavlink/mavlink_command.c
new file mode 100644
index 00000000000..94127c1fe7d
--- /dev/null
+++ b/src/main/mavlink/mavlink_command.c
@@ -0,0 +1,245 @@
+#include "mavlink/mavlink_internal.h"
+
+#include "mavlink/mavlink_command.h"
+#include "mavlink/mavlink_guided.h"
+#include "mavlink/mavlink_runtime.h"
+#include "mavlink/mavlink_streams.h"
+
+#if defined(USE_TELEMETRY) && defined(USE_TELEMETRY_MAVLINK)
+
+static bool mavlinkIsLocalTarget(uint8_t targetSystem, uint8_t targetComponent)
+{
+ if (targetSystem != 0 && targetSystem != mavSystemId) {
+ return false;
+ }
+
+ if (targetComponent != 0 && targetComponent != mavComponentId) {
+ return false;
+ }
+
+ return true;
+}
+
+static void mavlinkSendCommandAck(uint16_t command, MAV_RESULT result, uint8_t ackTargetSystem, uint8_t ackTargetComponent)
+{
+ mavlink_msg_command_ack_pack(mavSystemId, mavComponentId, &mavSendMsg,
+ command,
+ result,
+ 0,
+ 0,
+ ackTargetSystem,
+ ackTargetComponent);
+ mavlinkSendMessage();
+}
+
+static bool handleIncoming_COMMAND(
+ uint8_t targetSystem,
+ uint8_t targetComponent,
+ uint8_t ackTargetSystem,
+ uint8_t ackTargetComponent,
+ uint16_t command,
+ uint8_t frame,
+ float param1,
+ float param2,
+ float param3,
+ float param4,
+ float latitudeDeg,
+ float longitudeDeg,
+ float altitudeMeters)
+{
+ if (!mavlinkIsLocalTarget(targetSystem, targetComponent)) {
+ return false;
+ }
+ UNUSED(param3);
+
+ switch (command) {
+ case MAV_CMD_DO_REPOSITION:
+ if (!mavlinkFrameIsSupported(frame,
+ MAV_FRAME_SUPPORTED_GLOBAL |
+ MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT |
+ MAV_FRAME_SUPPORTED_GLOBAL_INT |
+ MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT_INT)) {
+ mavlinkSendCommandAck(command, MAV_RESULT_UNSUPPORTED, ackTargetSystem, ackTargetComponent);
+ return true;
+ }
+
+ if (isnan(latitudeDeg) || isnan(longitudeDeg)) {
+ mavlinkSendCommandAck(command, MAV_RESULT_FAILED, ackTargetSystem, ackTargetComponent);
+ return true;
+ }
+
+ if (isGCSValid()) {
+ navWaypoint_t wp = {0};
+ wp.action = NAV_WP_ACTION_WAYPOINT;
+ wp.lat = (int32_t)(latitudeDeg * 1e7f);
+ wp.lon = (int32_t)(longitudeDeg * 1e7f);
+ wp.alt = (int32_t)(altitudeMeters * 100.0f);
+ if (!isnan(param4) && param4 >= 0.0f && param4 < 360.0f) {
+ wp.p1 = (int16_t)param4;
+ } else {
+ wp.p1 = 0;
+ }
+ wp.p2 = 0;
+ wp.p3 = mavlinkFrameUsesAbsoluteAltitude(frame) ? NAV_WP_ALTMODE : 0;
+ wp.flag = 0;
+
+ setWaypoint(255, &wp);
+
+ mavlinkSendCommandAck(command, MAV_RESULT_ACCEPTED, ackTargetSystem, ackTargetComponent);
+ } else {
+ mavlinkSendCommandAck(command, MAV_RESULT_DENIED, ackTargetSystem, ackTargetComponent);
+ }
+ return true;
+ case MAV_CMD_DO_CHANGE_ALTITUDE:
+ {
+ const MAV_RESULT result = mavlinkSetAltitudeTargetFromFrame((uint8_t)lrintf(param2), param1);
+ mavlinkSendCommandAck(command, result, ackTargetSystem, ackTargetComponent);
+ return true;
+ }
+ case MAV_CMD_CONDITION_YAW:
+ {
+ if (!(navGetCurrentStateFlags() & NAV_CTL_YAW)) {
+ mavlinkSendCommandAck(command, MAV_RESULT_DENIED, ackTargetSystem, ackTargetComponent);
+ return true;
+ }
+
+ int32_t targetHeadingCd = wrap_36000((int32_t)lrintf(param1 * 100.0f));
+
+ if (param4 != 0.0f) {
+ const int32_t currentHeadingCd = STATE(AIRPLANE) ? posControl.actualState.cog : posControl.actualState.yaw;
+ const int32_t headingChangeCd = (int32_t)lrintf(fabsf(param1) * 100.0f);
+
+ if (param3 < 0.0f) {
+ targetHeadingCd = wrap_36000(currentHeadingCd - headingChangeCd);
+ } else {
+ targetHeadingCd = wrap_36000(currentHeadingCd + headingChangeCd);
+ }
+ }
+
+ updateHeadingHoldTarget(CENTIDEGREES_TO_DEGREES(targetHeadingCd));
+ posControl.desiredState.yaw = targetHeadingCd;
+ posControl.cruise.course = targetHeadingCd;
+ posControl.cruise.previousCourse = targetHeadingCd;
+
+ mavlinkSendCommandAck(command, MAV_RESULT_ACCEPTED, ackTargetSystem, ackTargetComponent);
+ return true;
+ }
+ case MAV_CMD_SET_MESSAGE_INTERVAL:
+ {
+ mavlinkPeriodicMessage_e periodicMessage;
+ MAV_RESULT result = MAV_RESULT_UNSUPPORTED;
+
+ if (mavlinkPeriodicMessageFromMessageId((uint16_t)param1, &periodicMessage)) {
+ if (param2 == 0.0f) {
+ mavlinkSetMessageOverrideIntervalUs(periodicMessage, 0);
+ result = MAV_RESULT_ACCEPTED;
+ } else if (param2 < 0.0f) {
+ mavlinkSetMessageOverrideIntervalUs(periodicMessage, -1);
+ result = MAV_RESULT_ACCEPTED;
+ } else {
+ uint32_t intervalUs = (uint32_t)param2;
+ if (intervalUs > 0) {
+ const uint32_t minIntervalUs = 1000000UL / TELEMETRY_MAVLINK_MAXRATE;
+ if (intervalUs < minIntervalUs) {
+ intervalUs = minIntervalUs;
+ }
+
+ mavlinkSetMessageOverrideIntervalUs(periodicMessage, (int32_t)intervalUs);
+ result = MAV_RESULT_ACCEPTED;
+ }
+ }
+ }
+
+ mavlinkSendCommandAck(command, result, ackTargetSystem, ackTargetComponent);
+ return true;
+ }
+ case MAV_CMD_GET_MESSAGE_INTERVAL:
+ {
+ mavlinkPeriodicMessage_e periodicMessage;
+ if (!mavlinkPeriodicMessageFromMessageId((uint16_t)param1, &periodicMessage)) {
+ mavlinkSendCommandAck(command, MAV_RESULT_UNSUPPORTED, ackTargetSystem, ackTargetComponent);
+ return true;
+ }
+
+ mavlink_msg_message_interval_pack(
+ mavSystemId,
+ mavComponentId,
+ &mavSendMsg,
+ (uint16_t)param1,
+ mavlinkMessageIntervalUs(periodicMessage));
+ mavlinkSendMessage();
+
+ mavlinkSendCommandAck(command, MAV_RESULT_ACCEPTED, ackTargetSystem, ackTargetComponent);
+ return true;
+ }
+ case MAV_CMD_CONTROL_HIGH_LATENCY:
+ if (param1 == 0.0f || param1 == 1.0f) {
+ if (mavlinkGetProtocolVersion() == 1 && param1 > 0.5f) {
+ mavlinkSendCommandAck(command, MAV_RESULT_UNSUPPORTED, ackTargetSystem, ackTargetComponent);
+ return true;
+ }
+
+ mavActivePort->highLatencyEnabled = param1 > 0.5f;
+ if (mavActivePort->highLatencyEnabled) {
+ mavActivePort->lastHighLatencyMessageUs = 0;
+ }
+ mavlinkSendCommandAck(command, MAV_RESULT_ACCEPTED, ackTargetSystem, ackTargetComponent);
+ } else {
+ mavlinkSendCommandAck(command, MAV_RESULT_FAILED, ackTargetSystem, ackTargetComponent);
+ }
+ return true;
+ case MAV_CMD_REQUEST_PROTOCOL_VERSION:
+ if (mavlinkGetProtocolVersion() == 1) {
+ mavlinkSendCommandAck(command, MAV_RESULT_UNSUPPORTED, ackTargetSystem, ackTargetComponent);
+ } else {
+ mavlinkSendProtocolVersion();
+ mavlinkSendCommandAck(command, MAV_RESULT_ACCEPTED, ackTargetSystem, ackTargetComponent);
+ }
+ return true;
+ case MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES:
+ if (mavlinkGetProtocolVersion() == 1) {
+ mavlinkSendCommandAck(command, MAV_RESULT_UNSUPPORTED, ackTargetSystem, ackTargetComponent);
+ } else {
+ mavlinkSendAutopilotVersion();
+ mavlinkSendCommandAck(command, MAV_RESULT_ACCEPTED, ackTargetSystem, ackTargetComponent);
+ }
+ return true;
+ case MAV_CMD_REQUEST_MESSAGE:
+ {
+ const bool sent = mavlinkSendRequestedMessage((uint16_t)param1);
+ mavlinkSendCommandAck(command, sent ? MAV_RESULT_ACCEPTED : MAV_RESULT_UNSUPPORTED, ackTargetSystem, ackTargetComponent);
+ return true;
+ }
+#ifdef USE_GPS
+ case MAV_CMD_GET_HOME_POSITION:
+ if (mavlinkSendRequestedMessage(MAVLINK_MSG_ID_HOME_POSITION)) {
+ mavlinkSendCommandAck(command, MAV_RESULT_ACCEPTED, ackTargetSystem, ackTargetComponent);
+ } else {
+ mavlinkSendCommandAck(command, MAV_RESULT_FAILED, ackTargetSystem, ackTargetComponent);
+ }
+ return true;
+#endif
+ default:
+ mavlinkSendCommandAck(command, MAV_RESULT_UNSUPPORTED, ackTargetSystem, ackTargetComponent);
+ return true;
+ }
+}
+
+bool mavlinkHandleIncomingCommandInt(void)
+{
+ mavlink_command_int_t msg;
+ mavlink_msg_command_int_decode(&mavlinkContext.recvMsg, &msg);
+
+ return handleIncoming_COMMAND(msg.target_system, msg.target_component, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, msg.command, msg.frame, msg.param1, msg.param2, msg.param3, msg.param4, (float)msg.x / 1e7f, (float)msg.y / 1e7f, msg.z);
+}
+
+bool mavlinkHandleIncomingCommandLong(void)
+{
+ mavlink_command_long_t msg;
+ mavlink_msg_command_long_decode(&mavlinkContext.recvMsg, &msg);
+
+ // COMMAND_LONG has no frame field; location commands are WGS84 global by definition.
+ return handleIncoming_COMMAND(msg.target_system, msg.target_component, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, msg.command, MAV_FRAME_GLOBAL, msg.param1, msg.param2, msg.param3, msg.param4, msg.param5, msg.param6, msg.param7);
+}
+
+#endif
diff --git a/src/main/mavlink/mavlink_command.h b/src/main/mavlink/mavlink_command.h
new file mode 100644
index 00000000000..fb468e696f7
--- /dev/null
+++ b/src/main/mavlink/mavlink_command.h
@@ -0,0 +1,7 @@
+#pragma once
+
+#include
+#include
+
+bool mavlinkHandleIncomingCommandLong(void);
+bool mavlinkHandleIncomingCommandInt(void);
diff --git a/src/main/mavlink/mavlink_guided.c b/src/main/mavlink/mavlink_guided.c
new file mode 100644
index 00000000000..9bdb719c716
--- /dev/null
+++ b/src/main/mavlink/mavlink_guided.c
@@ -0,0 +1,153 @@
+#include "mavlink/mavlink_internal.h"
+
+#include "mavlink/mavlink_guided.h"
+#include "mavlink/mavlink_runtime.h"
+
+#if defined(USE_TELEMETRY) && defined(USE_TELEMETRY_MAVLINK)
+
+bool mavlinkFrameIsSupported(uint8_t frame, mavFrameSupportMask_e allowedMask)
+{
+ switch (frame) {
+ case MAV_FRAME_GLOBAL:
+ return allowedMask & MAV_FRAME_SUPPORTED_GLOBAL;
+ case MAV_FRAME_GLOBAL_INT:
+ return allowedMask & MAV_FRAME_SUPPORTED_GLOBAL_INT;
+ case MAV_FRAME_GLOBAL_RELATIVE_ALT:
+ return allowedMask & MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT;
+ case MAV_FRAME_GLOBAL_RELATIVE_ALT_INT:
+ return allowedMask & MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT_INT;
+ default:
+ return false;
+ }
+}
+
+bool mavlinkFrameUsesAbsoluteAltitude(uint8_t frame)
+{
+ return frame == MAV_FRAME_GLOBAL || frame == MAV_FRAME_GLOBAL_INT;
+}
+
+MAV_RESULT mavlinkSetAltitudeTargetFromFrame(uint8_t frame, float altitudeMeters)
+{
+#ifdef USE_BARO
+ geoAltitudeDatumFlag_e datum;
+
+ switch (frame) {
+ case MAV_FRAME_GLOBAL:
+ case MAV_FRAME_GLOBAL_INT:
+ datum = NAV_WP_MSL_DATUM;
+ break;
+ case MAV_FRAME_GLOBAL_RELATIVE_ALT:
+ case MAV_FRAME_GLOBAL_RELATIVE_ALT_INT:
+ datum = NAV_WP_TAKEOFF_DATUM;
+ break;
+ default:
+ return MAV_RESULT_UNSUPPORTED;
+ }
+
+ const int32_t targetAltitudeCm = (int32_t)lrintf(altitudeMeters * 100.0f);
+ return navigationSetAltitudeTargetWithDatum(datum, targetAltitudeCm) ? MAV_RESULT_ACCEPTED : MAV_RESULT_DENIED;
+#else
+ UNUSED(frame);
+ UNUSED(altitudeMeters);
+ return MAV_RESULT_UNSUPPORTED;
+#endif
+}
+
+static bool mavlinkIsLocalTarget(uint8_t targetSystem, uint8_t targetComponent)
+{
+ if (targetSystem != 0 && targetSystem != mavSystemId) {
+ return false;
+ }
+
+ if (targetComponent != 0 && targetComponent != mavComponentId) {
+ return false;
+ }
+
+ return true;
+}
+
+bool mavlinkHandleIncomingSetPositionTargetGlobalInt(void)
+{
+ mavlink_set_position_target_global_int_t msg;
+ mavlink_msg_set_position_target_global_int_decode(&mavlinkContext.recvMsg, &msg);
+
+ if (!mavlinkIsLocalTarget(msg.target_system, msg.target_component)) {
+ return false;
+ }
+
+ uint8_t frame = msg.coordinate_frame;
+ if (!mavlinkFrameIsSupported(frame,
+ MAV_FRAME_SUPPORTED_GLOBAL |
+ MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT |
+ MAV_FRAME_SUPPORTED_GLOBAL_INT |
+ MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT_INT)) {
+ return true;
+ }
+
+ const uint16_t typeMask = msg.type_mask;
+ const bool xIgnored = (typeMask & POSITION_TARGET_TYPEMASK_X_IGNORE) != 0;
+ const bool yIgnored = (typeMask & POSITION_TARGET_TYPEMASK_Y_IGNORE) != 0;
+ const bool zIgnored = (typeMask & POSITION_TARGET_TYPEMASK_Z_IGNORE) != 0;
+
+ // Altitude-only SET_POSITION_TARGET_GLOBAL_INT mirrors MAV_CMD_DO_CHANGE_ALTITUDE semantics.
+ if (xIgnored && yIgnored && !zIgnored) {
+ if (isGCSValid()) {
+ mavlinkSetAltitudeTargetFromFrame(frame, msg.alt);
+ }
+ return true;
+ }
+
+ if (xIgnored || yIgnored) {
+ return true;
+ }
+
+ if (isGCSValid()) {
+ navWaypoint_t wp = {0};
+ wp.action = NAV_WP_ACTION_WAYPOINT;
+ wp.lat = msg.lat_int;
+ wp.lon = msg.lon_int;
+ wp.alt = zIgnored ? 0 : (int32_t)(msg.alt * 100.0f);
+ wp.p1 = 0;
+ wp.p2 = 0;
+ wp.p3 = mavlinkFrameUsesAbsoluteAltitude(frame) ? NAV_WP_ALTMODE : 0;
+ wp.flag = 0;
+
+ setWaypoint(255, &wp);
+ }
+
+ return true;
+}
+
+bool mavlinkHandleIncomingSetPositionTargetLocalNed(void)
+{
+ mavlink_set_position_target_local_ned_t msg;
+ mavlink_msg_set_position_target_local_ned_decode(&mavlinkContext.recvMsg, &msg);
+
+ if (!mavlinkIsLocalTarget(msg.target_system, msg.target_component)) {
+ return false;
+ }
+
+ if (msg.coordinate_frame != MAV_FRAME_LOCAL_OFFSET_NED) {
+ return true;
+ }
+
+ const uint16_t typeMask = msg.type_mask;
+ const bool xIgnored = (typeMask & POSITION_TARGET_TYPEMASK_X_IGNORE) != 0;
+ const bool yIgnored = (typeMask & POSITION_TARGET_TYPEMASK_Y_IGNORE) != 0;
+ const bool zIgnored = (typeMask & POSITION_TARGET_TYPEMASK_Z_IGNORE) != 0;
+
+ if (!isGCSValid() || zIgnored) {
+ return true;
+ }
+
+ if ((!xIgnored && fabsf(msg.x) > 0.01f) || (!yIgnored && fabsf(msg.y) > 0.01f)) {
+ return true;
+ }
+
+ const int32_t targetAltitudeCm = (int32_t)lrintf((float)getEstimatedActualPosition(Z) - (msg.z * 100.0f));
+ navigationSetAltitudeTargetWithDatum(NAV_WP_TAKEOFF_DATUM, targetAltitudeCm);
+
+ return true;
+}
+
+#endif
diff --git a/src/main/mavlink/mavlink_guided.h b/src/main/mavlink/mavlink_guided.h
new file mode 100644
index 00000000000..e160134d29b
--- /dev/null
+++ b/src/main/mavlink/mavlink_guided.h
@@ -0,0 +1,13 @@
+#pragma once
+
+#include
+#include
+
+#include "mavlink/mavlink_mission.h"
+
+bool mavlinkFrameIsSupported(uint8_t frame, mavFrameSupportMask_e allowedMask);
+bool mavlinkFrameUsesAbsoluteAltitude(uint8_t frame);
+MAV_RESULT mavlinkSetAltitudeTargetFromFrame(uint8_t frame, float altitudeMeters);
+
+bool mavlinkHandleIncomingSetPositionTargetGlobalInt(void);
+bool mavlinkHandleIncomingSetPositionTargetLocalNed(void);
diff --git a/src/main/mavlink/mavlink_mission.c b/src/main/mavlink/mavlink_mission.c
index 368dd39bfc9..70fcc9a06ea 100644
--- a/src/main/mavlink/mavlink_mission.c
+++ b/src/main/mavlink/mavlink_mission.c
@@ -1,5 +1,6 @@
#include "mavlink/mavlink_internal.h"
+#include "mavlink/mavlink_guided.h"
#include "mavlink/mavlink_mission.h"
#include "mavlink/mavlink_runtime.h"
@@ -29,54 +30,6 @@ void mavlinkSendPendingMissionItemReached(void)
mavSendMask = 0;
}
-bool mavlinkFrameIsSupported(uint8_t frame, mavFrameSupportMask_e allowedMask)
-{
- switch (frame) {
- case MAV_FRAME_GLOBAL:
- return allowedMask & MAV_FRAME_SUPPORTED_GLOBAL;
- case MAV_FRAME_GLOBAL_INT:
- return allowedMask & MAV_FRAME_SUPPORTED_GLOBAL_INT;
- case MAV_FRAME_GLOBAL_RELATIVE_ALT:
- return allowedMask & MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT;
- case MAV_FRAME_GLOBAL_RELATIVE_ALT_INT:
- return allowedMask & MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT_INT;
- default:
- return false;
- }
-}
-
-bool mavlinkFrameUsesAbsoluteAltitude(uint8_t frame)
-{
- return frame == MAV_FRAME_GLOBAL || frame == MAV_FRAME_GLOBAL_INT;
-}
-
-MAV_RESULT mavlinkSetAltitudeTargetFromFrame(uint8_t frame, float altitudeMeters)
-{
-#ifdef USE_BARO
- geoAltitudeDatumFlag_e datum;
-
- switch (frame) {
- case MAV_FRAME_GLOBAL:
- case MAV_FRAME_GLOBAL_INT:
- datum = NAV_WP_MSL_DATUM;
- break;
- case MAV_FRAME_GLOBAL_RELATIVE_ALT:
- case MAV_FRAME_GLOBAL_RELATIVE_ALT_INT:
- datum = NAV_WP_TAKEOFF_DATUM;
- break;
- default:
- return MAV_RESULT_UNSUPPORTED;
- }
-
- const int32_t targetAltitudeCm = (int32_t)lrintf(altitudeMeters * 100.0f);
- return navigationSetAltitudeTargetWithDatum(datum, targetAltitudeCm) ? MAV_RESULT_ACCEPTED : MAV_RESULT_DENIED;
-#else
- UNUSED(frame);
- UNUSED(altitudeMeters);
- return MAV_RESULT_UNSUPPORTED;
-#endif
-}
-
uint8_t mavlinkWaypointFrame(const navWaypoint_t *wp, bool useIntMessages)
{
switch (wp->action) {
@@ -95,16 +48,20 @@ uint8_t mavlinkWaypointFrame(const navWaypoint_t *wp, bool useIntMessages)
return useIntMessages ? MAV_FRAME_GLOBAL_RELATIVE_ALT_INT : MAV_FRAME_GLOBAL_RELATIVE_ALT;
}
-static MAV_MISSION_RESULT mavlinkMissionResultFromCommandResult(MAV_RESULT result)
+
+static void mavlinkSendMissionAck(MAV_MISSION_RESULT result)
{
- switch (result) {
- case MAV_RESULT_ACCEPTED:
- return MAV_MISSION_ACCEPTED;
- case MAV_RESULT_UNSUPPORTED:
- return MAV_MISSION_UNSUPPORTED;
- default:
- return MAV_MISSION_ERROR;
- }
+ mavlink_msg_mission_ack_pack(
+ mavSystemId,
+ mavComponentId,
+ &mavSendMsg,
+ mavlinkContext.recvMsg.sysid,
+ mavlinkContext.recvMsg.compid,
+ result,
+ MAV_MISSION_TYPE_MISSION,
+ 0
+ );
+ mavlinkSendMessage();
}
static void mavlinkResetIncomingMissionTransaction(void)
@@ -150,21 +107,21 @@ static bool mavlinkIsIncomingMissionTransactionOwner(void)
mavlinkContext.recvMsg.compid == incomingMissionSourceComponent;
}
-static bool mavlinkHandleArmedGuidedMissionItem(uint8_t current, uint8_t frame, mavFrameSupportMask_e allowedFrames, int32_t latitudeE7, int32_t longitudeE7, float altitudeMeters)
+static bool mavlinkHandleArmedGuidedMissionItem(
+ uint8_t current,
+ uint8_t frame,
+ mavFrameSupportMask_e allowedFrames,
+ int32_t latitudeE7,
+ int32_t longitudeE7,
+ float altitudeMeters)
{
if (!isGCSValid()) {
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg,
- mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid,
- MAV_MISSION_ERROR, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
+ mavlinkSendMissionAck(MAV_MISSION_ERROR);
return true;
}
if (!mavlinkFrameIsSupported(frame, allowedFrames)) {
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg,
- mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid,
- MAV_MISSION_UNSUPPORTED_FRAME, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
+ mavlinkSendMissionAck(MAV_MISSION_UNSUPPORTED_FRAME);
return true;
}
@@ -178,34 +135,39 @@ static bool mavlinkHandleArmedGuidedMissionItem(uint8_t current, uint8_t frame,
setWaypoint(255, &wp);
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg,
- mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid,
- MAV_MISSION_ACCEPTED, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
+ mavlinkSendMissionAck(MAV_MISSION_ACCEPTED);
return true;
}
if (current == 3) {
const MAV_RESULT result = mavlinkSetAltitudeTargetFromFrame(frame, altitudeMeters);
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg,
- mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid,
- mavlinkMissionResultFromCommandResult(result), MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
+ MAV_MISSION_RESULT response = MAV_MISSION_ERROR;
+ if (result == MAV_RESULT_ACCEPTED) {response = MAV_MISSION_ACCEPTED;}
+ else if (result == MAV_RESULT_UNSUPPORTED) {response = MAV_MISSION_UNSUPPORTED;}
+ mavlinkSendMissionAck(response);
return true;
}
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg,
- mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid,
- MAV_MISSION_ERROR, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
+ mavlinkSendMissionAck(MAV_MISSION_ERROR);
return true;
}
-static bool mavlinkHandleMissionItemCommon(bool useIntMessages, uint8_t frame, uint16_t command, uint8_t autocontinue, uint16_t seq, float param1, float param2, float param3, float param4, int32_t lat, int32_t lon, float altMeters)
+static bool mavlinkHandleMissionItemCommon(
+ bool useIntMessages,
+ uint8_t frame,
+ uint16_t command,
+ uint8_t autocontinue,
+ uint16_t seq,
+ float param1,
+ float param2,
+ float param3,
+ float param4,
+ int32_t lat,
+ int32_t lon,
+ float altMeters)
{
if (!mavlinkIsIncomingMissionTransactionActive() || !mavlinkIsIncomingMissionTransactionOwner()) {
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_INVALID_SEQUENCE, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
+ mavlinkSendMissionAck(MAV_MISSION_INVALID_SEQUENCE);
return true;
}
@@ -214,8 +176,7 @@ static bool mavlinkHandleMissionItemCommon(bool useIntMessages, uint8_t frame, u
const bool lastMissionItem = incomingMissionWpCount > 0 && ((int)seq + 1 >= incomingMissionWpCount);
if (autocontinue == 0 && !lastMissionItem) {
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_UNSUPPORTED, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
+ mavlinkSendMissionAck(MAV_MISSION_UNSUPPORTED);
return true;
}
@@ -230,8 +191,7 @@ static bool mavlinkHandleMissionItemCommon(bool useIntMessages, uint8_t frame, u
MAV_FRAME_SUPPORTED_GLOBAL_INT |
MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT |
MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT_INT)) {
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_UNSUPPORTED_FRAME, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
+ mavlinkSendMissionAck(MAV_MISSION_UNSUPPORTED_FRAME);
return true;
}
wp.action = NAV_WP_ACTION_WAYPOINT;
@@ -247,8 +207,7 @@ static bool mavlinkHandleMissionItemCommon(bool useIntMessages, uint8_t frame, u
MAV_FRAME_SUPPORTED_GLOBAL_INT |
MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT |
MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT_INT)) {
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_UNSUPPORTED_FRAME, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
+ mavlinkSendMissionAck(MAV_MISSION_UNSUPPORTED_FRAME);
return true;
}
wp.action = NAV_WP_ACTION_HOLD_TIME;
@@ -268,8 +227,7 @@ static bool mavlinkHandleMissionItemCommon(bool useIntMessages, uint8_t frame, u
MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT_INT);
if (!coordinateFrame && frame != MAV_FRAME_MISSION) {
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_UNSUPPORTED_FRAME, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
+ mavlinkSendMissionAck(MAV_MISSION_UNSUPPORTED_FRAME);
return true;
}
wp.action = NAV_WP_ACTION_RTH;
@@ -284,8 +242,7 @@ static bool mavlinkHandleMissionItemCommon(bool useIntMessages, uint8_t frame, u
MAV_FRAME_SUPPORTED_GLOBAL_INT |
MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT |
MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT_INT)) {
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_UNSUPPORTED_FRAME, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
+ mavlinkSendMissionAck(MAV_MISSION_UNSUPPORTED_FRAME);
return true;
}
wp.action = NAV_WP_ACTION_LAND;
@@ -297,13 +254,11 @@ static bool mavlinkHandleMissionItemCommon(bool useIntMessages, uint8_t frame, u
case MAV_CMD_DO_JUMP:
if (frame != MAV_FRAME_MISSION) {
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_UNSUPPORTED_FRAME, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
+ mavlinkSendMissionAck(MAV_MISSION_UNSUPPORTED_FRAME);
return true;
}
if (param1 < 0.0f) {
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_UNSUPPORTED, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
+ mavlinkSendMissionAck(MAV_MISSION_UNSUPPORTED);
return true;
}
wp.action = NAV_WP_ACTION_JUMP;
@@ -318,8 +273,7 @@ static bool mavlinkHandleMissionItemCommon(bool useIntMessages, uint8_t frame, u
MAV_FRAME_SUPPORTED_GLOBAL_INT |
MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT |
MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT_INT)) {
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_UNSUPPORTED, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
+ mavlinkSendMissionAck(MAV_MISSION_UNSUPPORTED);
return true;
}
wp.action = NAV_WP_ACTION_SET_POI;
@@ -331,13 +285,11 @@ static bool mavlinkHandleMissionItemCommon(bool useIntMessages, uint8_t frame, u
case MAV_CMD_CONDITION_YAW:
if (frame != MAV_FRAME_MISSION) {
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_UNSUPPORTED_FRAME, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
+ mavlinkSendMissionAck(MAV_MISSION_UNSUPPORTED_FRAME);
return true;
}
if (param4 != 0.0f) {
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_UNSUPPORTED, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
+ mavlinkSendMissionAck(MAV_MISSION_UNSUPPORTED);
return true;
}
wp.action = NAV_WP_ACTION_SET_HEAD;
@@ -345,8 +297,7 @@ static bool mavlinkHandleMissionItemCommon(bool useIntMessages, uint8_t frame, u
break;
default:
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_UNSUPPORTED, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
+ mavlinkSendMissionAck(MAV_MISSION_UNSUPPORTED);
return true;
}
@@ -357,17 +308,30 @@ static bool mavlinkHandleMissionItemCommon(bool useIntMessages, uint8_t frame, u
if (incomingMissionWpSequence >= incomingMissionWpCount) {
if (isWaypointListValid()) {
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_ACCEPTED, MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMissionAck(MAV_MISSION_ACCEPTED);
} else {
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_INVALID, MAV_MISSION_TYPE_MISSION, 0);
+ mavlinkSendMissionAck(MAV_MISSION_INVALID);
}
- mavlinkSendMessage();
mavlinkResetIncomingMissionTransaction();
} else {
if (useIntMessages) {
- mavlink_msg_mission_request_int_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, incomingMissionWpSequence, MAV_MISSION_TYPE_MISSION);
+ mavlink_msg_mission_request_int_pack(
+ mavSystemId,
+ mavComponentId,
+ &mavSendMsg,
+ mavlinkContext.recvMsg.sysid,
+ mavlinkContext.recvMsg.compid,
+ incomingMissionWpSequence,
+ MAV_MISSION_TYPE_MISSION);
} else {
- mavlink_msg_mission_request_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, incomingMissionWpSequence, MAV_MISSION_TYPE_MISSION);
+ mavlink_msg_mission_request_pack(
+ mavSystemId,
+ mavComponentId,
+ &mavSendMsg,
+ mavlinkContext.recvMsg.sysid,
+ mavlinkContext.recvMsg.compid,
+ incomingMissionWpSequence,
+ MAV_MISSION_TYPE_MISSION);
}
mavlinkSendMessage();
}
@@ -375,14 +339,27 @@ static bool mavlinkHandleMissionItemCommon(bool useIntMessages, uint8_t frame, u
if (seq + 1 == incomingMissionWpSequence) {
mavlinkTouchIncomingMissionTransaction();
if (useIntMessages) {
- mavlink_msg_mission_request_int_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, incomingMissionWpSequence, MAV_MISSION_TYPE_MISSION);
+ mavlink_msg_mission_request_int_pack(
+ mavSystemId,
+ mavComponentId,
+ &mavSendMsg,
+ mavlinkContext.recvMsg.sysid,
+ mavlinkContext.recvMsg.compid,
+ incomingMissionWpSequence,
+ MAV_MISSION_TYPE_MISSION);
} else {
- mavlink_msg_mission_request_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, incomingMissionWpSequence, MAV_MISSION_TYPE_MISSION);
+ mavlink_msg_mission_request_pack(
+ mavSystemId,
+ mavComponentId,
+ &mavSendMsg,
+ mavlinkContext.recvMsg.sysid,
+ mavlinkContext.recvMsg.compid,
+ incomingMissionWpSequence,
+ MAV_MISSION_TYPE_MISSION);
}
mavlinkSendMessage();
} else {
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_INVALID_SEQUENCE, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
+ mavlinkSendMissionAck(MAV_MISSION_INVALID_SEQUENCE);
}
}
@@ -397,8 +374,7 @@ bool mavlinkHandleIncomingMissionClearAll(void)
if (msg.target_system == mavSystemId) {
resetWaypointList();
mavlinkResetIncomingMissionTransaction();
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_ACCEPTED, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
+ mavlinkSendMissionAck(MAV_MISSION_ACCEPTED);
return true;
}
@@ -413,25 +389,29 @@ bool mavlinkHandleIncomingMissionCount(void)
if (msg.target_system == mavSystemId) {
mavlinkResetIncomingMissionTransaction();
if (ARMING_FLAG(ARMED)) {
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_ERROR, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
+ mavlinkSendMissionAck(MAV_MISSION_ERROR);
return true;
}
if (msg.count == 0) {
resetWaypointList();
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_ACCEPTED, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
+ mavlinkSendMissionAck(MAV_MISSION_ACCEPTED);
return true;
}
if (msg.count <= NAV_MAX_WAYPOINTS) {
mavlinkStartIncomingMissionTransaction(msg.count);
- mavlink_msg_mission_request_int_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, incomingMissionWpSequence, MAV_MISSION_TYPE_MISSION);
+ mavlink_msg_mission_request_int_pack(
+ mavSystemId,
+ mavComponentId,
+ &mavSendMsg,
+ mavlinkContext.recvMsg.sysid,
+ mavlinkContext.recvMsg.compid,
+ incomingMissionWpSequence,
+ MAV_MISSION_TYPE_MISSION);
mavlinkSendMessage();
return true;
}
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_NO_SPACE, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
+ mavlinkSendMissionAck(MAV_MISSION_NO_SPACE);
return true;
}
@@ -454,8 +434,7 @@ bool mavlinkHandleIncomingMissionItem(void)
(int32_t)lrintf(msg.x * 1e7f), (int32_t)lrintf(msg.y * 1e7f), msg.z);
}
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_ERROR, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
+ mavlinkSendMissionAck(MAV_MISSION_ERROR);
return true;
}
@@ -566,12 +545,10 @@ bool mavlinkHandleIncomingMissionRequest(void)
MAV_MISSION_TYPE_MISSION);
mavlinkSendMessage();
} else {
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_ERROR, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
+ mavlinkSendMissionAck(MAV_MISSION_ERROR);
}
} else {
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_INVALID_SEQUENCE, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
+ mavlinkSendMissionAck(MAV_MISSION_INVALID_SEQUENCE);
}
return true;
@@ -593,8 +570,7 @@ bool mavlinkHandleIncomingMissionItemInt(void)
msg.x, msg.y, msg.z);
}
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_ERROR, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
+ mavlinkSendMissionAck(MAV_MISSION_ERROR);
return true;
}
@@ -631,12 +607,10 @@ bool mavlinkHandleIncomingMissionRequestInt(void)
MAV_MISSION_TYPE_MISSION);
mavlinkSendMessage();
} else {
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_ERROR, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
+ mavlinkSendMissionAck(MAV_MISSION_ERROR);
}
} else {
- mavlink_msg_mission_ack_pack(mavSystemId, mavComponentId, &mavSendMsg, mavlinkContext.recvMsg.sysid, mavlinkContext.recvMsg.compid, MAV_MISSION_INVALID_SEQUENCE, MAV_MISSION_TYPE_MISSION, 0);
- mavlinkSendMessage();
+ mavlinkSendMissionAck(MAV_MISSION_INVALID_SEQUENCE);
}
return true;
diff --git a/src/main/mavlink/mavlink_mission.h b/src/main/mavlink/mavlink_mission.h
index 650bdd06338..41010e85f07 100644
--- a/src/main/mavlink/mavlink_mission.h
+++ b/src/main/mavlink/mavlink_mission.h
@@ -27,13 +27,9 @@ typedef struct mavlinkMissionItemData_s {
float alt;
} mavlinkMissionItemData_t;
-bool mavlinkFrameIsSupported(uint8_t frame, mavFrameSupportMask_e allowedMask);
-bool mavlinkFrameUsesAbsoluteAltitude(uint8_t frame);
-MAV_RESULT mavlinkSetAltitudeTargetFromFrame(uint8_t frame, float altitudeMeters);
uint8_t mavlinkWaypointFrame(const navWaypoint_t *wp, bool useIntMessages);
bool mavlinkFillMissionItemFromWaypoint(const navWaypoint_t *wp, bool useIntMessages, mavlinkMissionItemData_t *item);
void mavlinkSendPendingMissionItemReached(void);
-
bool mavlinkHandleIncomingMissionClearAll(void);
bool mavlinkHandleIncomingMissionCount(void);
bool mavlinkHandleIncomingMissionItem(void);
diff --git a/src/main/mavlink/mavlink_streams.c b/src/main/mavlink/mavlink_streams.c
index 15a6630f25c..6dfb0ef47b8 100644
--- a/src/main/mavlink/mavlink_streams.c
+++ b/src/main/mavlink/mavlink_streams.c
@@ -1089,6 +1089,68 @@ bool mavlinkSendRequestedMessage(uint16_t messageId)
}
}
+bool mavlinkHandleIncomingHeartbeat(void)
+{
+ mavlink_heartbeat_t msg;
+ mavlink_msg_heartbeat_decode(&mavlinkContext.recvMsg, &msg);
+
+ switch (msg.type) {
+#ifdef USE_ADSB
+ case MAV_TYPE_ADSB:
+ return adsbHeartbeat();
+#endif
+ default:
+ break;
+ }
+
+ return false;
+}
+
+static bool mavlinkIsLocalTarget(uint8_t targetSystem, uint8_t targetComponent)
+{
+ if (targetSystem != 0 && targetSystem != mavSystemId) {
+ return false;
+ }
+
+ if (targetComponent != 0 && targetComponent != mavComponentId) {
+ return false;
+ }
+
+ return true;
+}
+
+bool mavlinkHandleIncomingRequestDataStream(void)
+{
+ mavlink_request_data_stream_t msg;
+ mavlink_msg_request_data_stream_decode(&mavlinkContext.recvMsg, &msg);
+
+ if (!mavlinkIsLocalTarget(msg.target_system, msg.target_component)) {
+ return false;
+ }
+
+ uint8_t rate = 0;
+ if (msg.start_stop != 0) {
+ rate = (uint8_t)msg.req_message_rate;
+ if (rate > TELEMETRY_MAVLINK_MAXRATE) {
+ rate = TELEMETRY_MAVLINK_MAXRATE;
+ }
+ }
+
+ if (msg.req_stream_id == MAV_DATA_STREAM_ALL) {
+ mavlinkSetStreamRate(MAV_DATA_STREAM_EXTENDED_STATUS, rate);
+ mavlinkSetStreamRate(MAV_DATA_STREAM_RC_CHANNELS, rate);
+ mavlinkSetStreamRate(MAV_DATA_STREAM_POSITION, rate);
+ mavlinkSetStreamRate(MAV_DATA_STREAM_EXTRA1, rate);
+ mavlinkSetStreamRate(MAV_DATA_STREAM_EXTRA2, rate);
+ mavlinkSetStreamRate(MAV_DATA_STREAM_EXTRA3, rate);
+ mavlinkSetStreamRate(MAV_DATA_STREAM_EXTENDED_SYS_STATE, rate);
+ return true;
+ }
+
+ mavlinkSetStreamRate(msg.req_stream_id, rate);
+ return true;
+}
+
void processMAVLinkTelemetry(timeUs_t currentTimeUs)
{
if (mavActivePort->highLatencyEnabled && mavlinkGetProtocolVersion() != 1) {
diff --git a/src/main/mavlink/mavlink_streams.h b/src/main/mavlink/mavlink_streams.h
index 514a8e01c38..c385ef35e9a 100644
--- a/src/main/mavlink/mavlink_streams.h
+++ b/src/main/mavlink/mavlink_streams.h
@@ -21,3 +21,5 @@ void mavlinkSetStreamRate(uint8_t streamNum, uint8_t rate);
int mavlinkMessageTrigger(mavlinkPeriodicMessage_e periodicMessage, timeUs_t currentTimeUs);
void configureMAVLinkStreamRates(uint8_t portIndex);
void processMAVLinkTelemetry(timeUs_t currentTimeUs);
+bool mavlinkHandleIncomingHeartbeat(void);
+bool mavlinkHandleIncomingRequestDataStream(void);
From 403bcb5696ffb985ef25b62dda92612c0b94419c Mon Sep 17 00:00:00 2001
From: frogmane <7685285+xznhj8129@users.noreply.github.com>
Date: Sat, 4 Apr 2026 13:59:52 -0400
Subject: [PATCH 42/46] fixed docgen to include mavlink
---
docs/development/msp/get_all_inav_enums_h.py | 1 +
docs/development/msp/inav_enums.json | 24 +++++++++++++
docs/development/msp/inav_enums_ref.md | 36 ++++++++++++++++++++
3 files changed, 61 insertions(+)
diff --git a/docs/development/msp/get_all_inav_enums_h.py b/docs/development/msp/get_all_inav_enums_h.py
index 971d077d5f4..79c5c57276a 100644
--- a/docs/development/msp/get_all_inav_enums_h.py
+++ b/docs/development/msp/get_all_inav_enums_h.py
@@ -16,6 +16,7 @@
'flight',
'fc',
'drivers',
+ 'mavlink',
]
def strip_comments(text: str) -> str:
diff --git a/docs/development/msp/inav_enums.json b/docs/development/msp/inav_enums.json
index eeaa393b7ef..c23774ce6e2 100644
--- a/docs/development/msp/inav_enums.json
+++ b/docs/development/msp/inav_enums.json
@@ -2242,6 +2242,14 @@
"MAG_FAKE": "16",
"MAG_MAX": "MAG_FAKE"
},
+ "mavFrameSupportMask_e": {
+ "_source": "inav/src/main/mavlink/mavlink_mission.h",
+ "MAV_FRAME_SUPPORTED_NONE": "0",
+ "MAV_FRAME_SUPPORTED_GLOBAL": "(1 << 0)",
+ "MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT": "(1 << 1)",
+ "MAV_FRAME_SUPPORTED_GLOBAL_INT": "(1 << 2)",
+ "MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT_INT": "(1 << 3)"
+ },
"mavlinkAutopilotType_e": {
"_source": "inav/src/main/telemetry/telemetry.h",
"MAVLINK_AUTOPILOT_GENERIC": "0",
@@ -2253,6 +2261,22 @@
"MAVLINK_FC_DISPATCH_HANDLED_NO_ACTIVITY": "1",
"MAVLINK_FC_DISPATCH_HANDLED_ACTIVITY": "2"
},
+ "mavlinkPeriodicMessage_e": {
+ "_source": "inav/src/main/mavlink/mavlink_types.h",
+ "MAVLINK_PERIODIC_MESSAGE_HEARTBEAT": "0",
+ "MAVLINK_PERIODIC_MESSAGE_SYS_STATUS": "1",
+ "MAVLINK_PERIODIC_MESSAGE_EXTENDED_SYS_STATE": "2",
+ "MAVLINK_PERIODIC_MESSAGE_RC_CHANNELS": "3",
+ "MAVLINK_PERIODIC_MESSAGE_GPS_RAW_INT": "4",
+ "MAVLINK_PERIODIC_MESSAGE_GLOBAL_POSITION_INT": "5",
+ "MAVLINK_PERIODIC_MESSAGE_GPS_GLOBAL_ORIGIN": "6",
+ "MAVLINK_PERIODIC_MESSAGE_ATTITUDE": "7",
+ "MAVLINK_PERIODIC_MESSAGE_VFR_HUD": "8",
+ "MAVLINK_PERIODIC_MESSAGE_BATTERY_STATUS": "9",
+ "MAVLINK_PERIODIC_MESSAGE_SCALED_PRESSURE": "10",
+ "MAVLINK_PERIODIC_MESSAGE_SYSTEM_TIME": "11",
+ "MAVLINK_PERIODIC_MESSAGE_COUNT": "12"
+ },
"mavlinkRadio_e": {
"_source": "inav/src/main/telemetry/telemetry.h",
"MAVLINK_RADIO_GENERIC": "0",
diff --git a/docs/development/msp/inav_enums_ref.md b/docs/development/msp/inav_enums_ref.md
index e0048e8c621..1e7ba6db1de 100644
--- a/docs/development/msp/inav_enums_ref.md
+++ b/docs/development/msp/inav_enums_ref.md
@@ -173,8 +173,10 @@
- [ltm_modes_e](#enum-ltm_modes_e)
- [ltmUpdateRate_e](#enum-ltmupdaterate_e)
- [magSensor_e](#enum-magsensor_e)
+- [mavFrameSupportMask_e](#enum-mavframesupportmask_e)
- [mavlinkAutopilotType_e](#enum-mavlinkautopilottype_e)
- [mavlinkFcDispatchResult_e](#enum-mavlinkfcdispatchresult_e)
+- [mavlinkPeriodicMessage_e](#enum-mavlinkperiodicmessage_e)
- [mavlinkRadio_e](#enum-mavlinkradio_e)
- [measurementSteps_e](#enum-measurementsteps_e)
- [mixerProfileATRequest_e](#enum-mixerprofileatrequest_e)
@@ -3379,6 +3381,19 @@
| `MAG_FAKE` | 16 | |
| `MAG_MAX` | MAG_FAKE | |
+---
+## `mavFrameSupportMask_e`
+
+> Source: ../../../src/main/mavlink/mavlink_mission.h
+
+| Enumerator | Value | Condition |
+|---|---:|---|
+| `MAV_FRAME_SUPPORTED_NONE` | 0 | |
+| `MAV_FRAME_SUPPORTED_GLOBAL` | (1 << 0) | |
+| `MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT` | (1 << 1) | |
+| `MAV_FRAME_SUPPORTED_GLOBAL_INT` | (1 << 2) | |
+| `MAV_FRAME_SUPPORTED_GLOBAL_RELATIVE_ALT_INT` | (1 << 3) | |
+
---
## `mavlinkAutopilotType_e`
@@ -3400,6 +3415,27 @@
| `MAVLINK_FC_DISPATCH_HANDLED_NO_ACTIVITY` | 1 | |
| `MAVLINK_FC_DISPATCH_HANDLED_ACTIVITY` | 2 | |
+---
+## `mavlinkPeriodicMessage_e`
+
+> Source: ../../../src/main/mavlink/mavlink_types.h
+
+| Enumerator | Value | Condition |
+|---|---:|---|
+| `MAVLINK_PERIODIC_MESSAGE_HEARTBEAT` | 0 | |
+| `MAVLINK_PERIODIC_MESSAGE_SYS_STATUS` | 1 | |
+| `MAVLINK_PERIODIC_MESSAGE_EXTENDED_SYS_STATE` | 2 | |
+| `MAVLINK_PERIODIC_MESSAGE_RC_CHANNELS` | 3 | |
+| `MAVLINK_PERIODIC_MESSAGE_GPS_RAW_INT` | 4 | |
+| `MAVLINK_PERIODIC_MESSAGE_GLOBAL_POSITION_INT` | 5 | |
+| `MAVLINK_PERIODIC_MESSAGE_GPS_GLOBAL_ORIGIN` | 6 | |
+| `MAVLINK_PERIODIC_MESSAGE_ATTITUDE` | 7 | |
+| `MAVLINK_PERIODIC_MESSAGE_VFR_HUD` | 8 | |
+| `MAVLINK_PERIODIC_MESSAGE_BATTERY_STATUS` | 9 | |
+| `MAVLINK_PERIODIC_MESSAGE_SCALED_PRESSURE` | 10 | |
+| `MAVLINK_PERIODIC_MESSAGE_SYSTEM_TIME` | 11 | |
+| `MAVLINK_PERIODIC_MESSAGE_COUNT` | 12 | |
+
---
## `mavlinkRadio_e`
From 2e03649cb36b710d7a85306653b9894334d27cb4 Mon Sep 17 00:00:00 2001
From: frogmane <7685285+xznhj8129@users.noreply.github.com>
Date: Sat, 18 Apr 2026 12:10:38 -0400
Subject: [PATCH 43/46] mlrs test
---
docs/development/msp/all_enums.h | 5503 ++++++++++++++++++++++++++++++
src/main/fc/fc_mavlink.c | 11 +
src/main/fc/settings.yaml | 2 +-
src/main/mavlink/mavlink_types.h | 4 +-
src/main/navigation/navigation.h | 20 +-
src/main/telemetry/telemetry.h | 4 +-
6 files changed, 5530 insertions(+), 14 deletions(-)
create mode 100644 docs/development/msp/all_enums.h
diff --git a/docs/development/msp/all_enums.h b/docs/development/msp/all_enums.h
new file mode 100644
index 00000000000..5ffd6e5a1e4
--- /dev/null
+++ b/docs/development/msp/all_enums.h
@@ -0,0 +1,5503 @@
+// Consolidated enums — generated on 2026-04-14 13:29:50.928647
+
+// ../../../src/main/common/calibration.h
+typedef enum {
+ ZERO_CALIBRATION_NONE = 0,
+ ZERO_CALIBRATION_IN_PROGRESS,
+ ZERO_CALIBRATION_DONE,
+ ZERO_CALIBRATION_FAIL,
+} zeroCalibrationState_e;
+
+// ../../../src/main/common/color.h
+typedef enum {
+ RGB_RED = 0,
+ RGB_GREEN,
+ RGB_BLUE
+} colorComponent_e;
+
+// ../../../src/main/common/color.h
+typedef enum {
+ HSV_HUE = 0,
+ HSV_SATURATION,
+ HSV_VALUE
+} hsvColorComponent_e;
+
+// ../../../src/main/common/axis.h
+typedef enum {
+ X = 0,
+ Y,
+ Z
+} axis_e;
+
+// ../../../src/main/common/axis.h
+typedef enum {
+ FD_ROLL = 0,
+ FD_PITCH,
+ FD_YAW
+} flight_dynamics_index_t;
+
+// ../../../src/main/common/axis.h
+typedef enum {
+ AI_ROLL = 0,
+ AI_PITCH,
+} angle_index_t;
+
+// ../../../src/main/common/tristate.h
+typedef enum {
+ TRISTATE_AUTO = 0,
+ TRISTATE_ON = 1,
+ TRISTATE_OFF = 2,
+} tristate_e;
+
+// ../../../src/main/common/log.h
+typedef enum {
+ LOG_TOPIC_SYSTEM,
+ LOG_TOPIC_GYRO,
+ LOG_TOPIC_BARO,
+ LOG_TOPIC_PITOT,
+ LOG_TOPIC_PWM,
+ LOG_TOPIC_TIMER,
+ LOG_TOPIC_IMU,
+ LOG_TOPIC_TEMPERATURE,
+ LOG_TOPIC_POS_ESTIMATOR,
+ LOG_TOPIC_VTX,
+ LOG_TOPIC_OSD,
+ LOG_TOPIC_CAN,
+ LOG_TOPIC_COUNT,
+} logTopic_e;
+
+// ../../../src/main/common/fp_pid.h
+typedef enum {
+ PID_DTERM_FROM_ERROR = 1 << 0,
+ PID_ZERO_INTEGRATOR = 1 << 1,
+ PID_SHRINK_INTEGRATOR = 1 << 2,
+ PID_LIMIT_INTEGRATOR = 1 << 3,
+ PID_FREEZE_INTEGRATOR = 1 << 4,
+} pidControllerFlags_e;
+
+// ../../../src/main/common/time.h
+typedef enum {
+ TZ_AUTO_DST_OFF,
+ TZ_AUTO_DST_EU,
+ TZ_AUTO_DST_USA,
+} tz_automatic_dst_e;
+
+// ../../../src/main/common/filter.h
+typedef enum {
+ FILTER_PT1 = 0,
+ FILTER_BIQUAD,
+ FILTER_PT2,
+ FILTER_PT3,
+ FILTER_LULU
+} filterType_e;
+
+// ../../../src/main/common/filter.h
+typedef enum {
+ FILTER_LPF,
+ FILTER_NOTCH
+} biquadFilterType_e;
+
+// ../../../src/main/blackbox/blackbox_fielddefs.h
+typedef enum FlightLogFieldCondition {
+ FLIGHT_LOG_FIELD_CONDITION_ALWAYS = 0,
+ FLIGHT_LOG_FIELD_CONDITION_MOTORS,
+ FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_1,
+ FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_2,
+ FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_3,
+ FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_4,
+ FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_5,
+ FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_6,
+ FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_7,
+ FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_8,
+
+ FLIGHT_LOG_FIELD_CONDITION_SERVOS,
+ FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_1,
+ FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_2,
+ FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_3,
+ FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_4,
+ FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_5,
+ FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_6,
+ FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_7,
+ FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_8,
+ FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_9,
+ FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_10,
+ FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_11,
+ FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_12,
+ FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_13,
+ FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_14,
+ FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_15,
+ FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_16,
+ FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_17,
+ FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_18,
+ FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_19,
+ FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_20,
+ FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_21,
+ FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_22,
+ FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_23,
+ FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_24,
+ FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_25,
+ FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_26,
+
+
+ FLIGHT_LOG_FIELD_CONDITION_MAG,
+ FLIGHT_LOG_FIELD_CONDITION_BARO,
+ FLIGHT_LOG_FIELD_CONDITION_PITOT,
+ FLIGHT_LOG_FIELD_CONDITION_VBAT,
+ FLIGHT_LOG_FIELD_CONDITION_AMPERAGE,
+ FLIGHT_LOG_FIELD_CONDITION_SURFACE,
+ FLIGHT_LOG_FIELD_CONDITION_FIXED_WING_NAV,
+ FLIGHT_LOG_FIELD_CONDITION_MC_NAV,
+ FLIGHT_LOG_FIELD_CONDITION_RSSI,
+
+ FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_0,
+ FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_1,
+ FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_2,
+
+ FLIGHT_LOG_FIELD_CONDITION_NOT_LOGGING_EVERY_FRAME,
+
+ FLIGHT_LOG_FIELD_CONDITION_DEBUG,
+
+ FLIGHT_LOG_FIELD_CONDITION_NAV_ACC,
+ FLIGHT_LOG_FIELD_CONDITION_NAV_POS,
+ FLIGHT_LOG_FIELD_CONDITION_NAV_PID,
+ FLIGHT_LOG_FIELD_CONDITION_ACC,
+ FLIGHT_LOG_FIELD_CONDITION_ATTITUDE,
+ FLIGHT_LOG_FIELD_CONDITION_RC_DATA,
+ FLIGHT_LOG_FIELD_CONDITION_RC_COMMAND,
+ FLIGHT_LOG_FIELD_CONDITION_GYRO_RAW,
+
+ FLIGHT_LOG_FIELD_CONDITION_GYRO_PEAKS_ROLL,
+ FLIGHT_LOG_FIELD_CONDITION_GYRO_PEAKS_PITCH,
+ FLIGHT_LOG_FIELD_CONDITION_GYRO_PEAKS_YAW,
+
+ FLIGHT_LOG_FIELD_CONDITION_NEVER,
+
+ FLIGHT_LOG_FIELD_CONDITION_FIRST = FLIGHT_LOG_FIELD_CONDITION_ALWAYS,
+ FLIGHT_LOG_FIELD_CONDITION_LAST = FLIGHT_LOG_FIELD_CONDITION_NEVER
+} FlightLogFieldCondition;
+
+// ../../../src/main/blackbox/blackbox_fielddefs.h
+typedef enum FlightLogFieldPredictor {
+
+ FLIGHT_LOG_FIELD_PREDICTOR_0 = 0,
+
+
+ FLIGHT_LOG_FIELD_PREDICTOR_PREVIOUS = 1,
+
+
+ FLIGHT_LOG_FIELD_PREDICTOR_STRAIGHT_LINE = 2,
+
+
+ FLIGHT_LOG_FIELD_PREDICTOR_AVERAGE_2 = 3,
+
+
+ FLIGHT_LOG_FIELD_PREDICTOR_MINTHROTTLE = 4,
+
+
+ FLIGHT_LOG_FIELD_PREDICTOR_MOTOR_0 = 5,
+
+
+ FLIGHT_LOG_FIELD_PREDICTOR_INC = 6,
+
+
+ FLIGHT_LOG_FIELD_PREDICTOR_HOME_COORD = 7,
+
+
+ FLIGHT_LOG_FIELD_PREDICTOR_1500 = 8,
+
+
+ FLIGHT_LOG_FIELD_PREDICTOR_VBATREF = 9,
+
+
+ FLIGHT_LOG_FIELD_PREDICTOR_LAST_MAIN_FRAME_TIME = 10
+
+} FlightLogFieldPredictor;
+
+// ../../../src/main/blackbox/blackbox_fielddefs.h
+typedef enum FlightLogFieldEncoding {
+ FLIGHT_LOG_FIELD_ENCODING_SIGNED_VB = 0,
+ FLIGHT_LOG_FIELD_ENCODING_UNSIGNED_VB = 1,
+ FLIGHT_LOG_FIELD_ENCODING_NEG_14BIT = 3,
+ FLIGHT_LOG_FIELD_ENCODING_TAG8_8SVB = 6,
+ FLIGHT_LOG_FIELD_ENCODING_TAG2_3S32 = 7,
+ FLIGHT_LOG_FIELD_ENCODING_TAG8_4S16 = 8,
+ FLIGHT_LOG_FIELD_ENCODING_NULL = 9
+} FlightLogFieldEncoding;
+
+// ../../../src/main/blackbox/blackbox_fielddefs.h
+typedef enum FlightLogFieldSign {
+ FLIGHT_LOG_FIELD_UNSIGNED = 0,
+ FLIGHT_LOG_FIELD_SIGNED = 1
+} FlightLogFieldSign;
+
+// ../../../src/main/blackbox/blackbox_fielddefs.h
+typedef enum FlightLogEvent {
+ FLIGHT_LOG_EVENT_SYNC_BEEP = 0,
+ FLIGHT_LOG_EVENT_INFLIGHT_ADJUSTMENT = 13,
+ FLIGHT_LOG_EVENT_LOGGING_RESUME = 14,
+ FLIGHT_LOG_EVENT_FLIGHTMODE = 30,
+ FLIGHT_LOG_EVENT_IMU_FAILURE = 40,
+ FLIGHT_LOG_EVENT_LOG_END = 255
+} FlightLogEvent;
+
+// ../../../src/main/blackbox/blackbox_fielddefs.h
+enum FlightLogFieldCondition {
+ FLIGHT_LOG_FIELD_CONDITION_ALWAYS = 0,
+ FLIGHT_LOG_FIELD_CONDITION_MOTORS,
+ FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_1,
+ FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_2,
+ FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_3,
+ FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_4,
+ FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_5,
+ FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_6,
+ FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_7,
+ FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_8,
+
+ FLIGHT_LOG_FIELD_CONDITION_SERVOS,
+ FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_1,
+ FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_2,
+ FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_3,
+ FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_4,
+ FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_5,
+ FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_6,
+ FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_7,
+ FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_8,
+ FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_9,
+ FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_10,
+ FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_11,
+ FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_12,
+ FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_13,
+ FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_14,
+ FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_15,
+ FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_16,
+ FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_17,
+ FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_18,
+ FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_19,
+ FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_20,
+ FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_21,
+ FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_22,
+ FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_23,
+ FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_24,
+ FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_25,
+ FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_SERVOS_26,
+
+
+ FLIGHT_LOG_FIELD_CONDITION_MAG,
+ FLIGHT_LOG_FIELD_CONDITION_BARO,
+ FLIGHT_LOG_FIELD_CONDITION_PITOT,
+ FLIGHT_LOG_FIELD_CONDITION_VBAT,
+ FLIGHT_LOG_FIELD_CONDITION_AMPERAGE,
+ FLIGHT_LOG_FIELD_CONDITION_SURFACE,
+ FLIGHT_LOG_FIELD_CONDITION_FIXED_WING_NAV,
+ FLIGHT_LOG_FIELD_CONDITION_MC_NAV,
+ FLIGHT_LOG_FIELD_CONDITION_RSSI,
+
+ FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_0,
+ FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_1,
+ FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_2,
+
+ FLIGHT_LOG_FIELD_CONDITION_NOT_LOGGING_EVERY_FRAME,
+
+ FLIGHT_LOG_FIELD_CONDITION_DEBUG,
+
+ FLIGHT_LOG_FIELD_CONDITION_NAV_ACC,
+ FLIGHT_LOG_FIELD_CONDITION_NAV_POS,
+ FLIGHT_LOG_FIELD_CONDITION_NAV_PID,
+ FLIGHT_LOG_FIELD_CONDITION_ACC,
+ FLIGHT_LOG_FIELD_CONDITION_ATTITUDE,
+ FLIGHT_LOG_FIELD_CONDITION_RC_DATA,
+ FLIGHT_LOG_FIELD_CONDITION_RC_COMMAND,
+ FLIGHT_LOG_FIELD_CONDITION_GYRO_RAW,
+
+ FLIGHT_LOG_FIELD_CONDITION_GYRO_PEAKS_ROLL,
+ FLIGHT_LOG_FIELD_CONDITION_GYRO_PEAKS_PITCH,
+ FLIGHT_LOG_FIELD_CONDITION_GYRO_PEAKS_YAW,
+
+ FLIGHT_LOG_FIELD_CONDITION_NEVER,
+
+ FLIGHT_LOG_FIELD_CONDITION_FIRST = FLIGHT_LOG_FIELD_CONDITION_ALWAYS,
+ FLIGHT_LOG_FIELD_CONDITION_LAST = FLIGHT_LOG_FIELD_CONDITION_NEVER
+} FlightLogFieldCondition;
+typedef enum FlightLogFieldCondition FlightLogFieldCondition;
+
+// ../../../src/main/blackbox/blackbox_fielddefs.h
+enum FlightLogFieldPredictor {
+
+ FLIGHT_LOG_FIELD_PREDICTOR_0 = 0,
+
+
+ FLIGHT_LOG_FIELD_PREDICTOR_PREVIOUS = 1,
+
+
+ FLIGHT_LOG_FIELD_PREDICTOR_STRAIGHT_LINE = 2,
+
+
+ FLIGHT_LOG_FIELD_PREDICTOR_AVERAGE_2 = 3,
+
+
+ FLIGHT_LOG_FIELD_PREDICTOR_MINTHROTTLE = 4,
+
+
+ FLIGHT_LOG_FIELD_PREDICTOR_MOTOR_0 = 5,
+
+
+ FLIGHT_LOG_FIELD_PREDICTOR_INC = 6,
+
+
+ FLIGHT_LOG_FIELD_PREDICTOR_HOME_COORD = 7,
+
+
+ FLIGHT_LOG_FIELD_PREDICTOR_1500 = 8,
+
+
+ FLIGHT_LOG_FIELD_PREDICTOR_VBATREF = 9,
+
+
+ FLIGHT_LOG_FIELD_PREDICTOR_LAST_MAIN_FRAME_TIME = 10
+
+} FlightLogFieldPredictor;
+typedef enum FlightLogFieldPredictor FlightLogFieldPredictor;
+
+// ../../../src/main/blackbox/blackbox_fielddefs.h
+enum FlightLogFieldEncoding {
+ FLIGHT_LOG_FIELD_ENCODING_SIGNED_VB = 0,
+ FLIGHT_LOG_FIELD_ENCODING_UNSIGNED_VB = 1,
+ FLIGHT_LOG_FIELD_ENCODING_NEG_14BIT = 3,
+ FLIGHT_LOG_FIELD_ENCODING_TAG8_8SVB = 6,
+ FLIGHT_LOG_FIELD_ENCODING_TAG2_3S32 = 7,
+ FLIGHT_LOG_FIELD_ENCODING_TAG8_4S16 = 8,
+ FLIGHT_LOG_FIELD_ENCODING_NULL = 9
+} FlightLogFieldEncoding;
+typedef enum FlightLogFieldEncoding FlightLogFieldEncoding;
+
+// ../../../src/main/blackbox/blackbox_fielddefs.h
+enum FlightLogFieldSign {
+ FLIGHT_LOG_FIELD_UNSIGNED = 0,
+ FLIGHT_LOG_FIELD_SIGNED = 1
+} FlightLogFieldSign;
+typedef enum FlightLogFieldSign FlightLogFieldSign;
+
+// ../../../src/main/blackbox/blackbox_fielddefs.h
+enum FlightLogEvent {
+ FLIGHT_LOG_EVENT_SYNC_BEEP = 0,
+ FLIGHT_LOG_EVENT_INFLIGHT_ADJUSTMENT = 13,
+ FLIGHT_LOG_EVENT_LOGGING_RESUME = 14,
+ FLIGHT_LOG_EVENT_FLIGHTMODE = 30,
+ FLIGHT_LOG_EVENT_IMU_FAILURE = 40,
+ FLIGHT_LOG_EVENT_LOG_END = 255
+} FlightLogEvent;
+typedef enum FlightLogEvent FlightLogEvent;
+
+// ../../../src/main/blackbox/blackbox.h
+typedef enum {
+ BLACKBOX_FEATURE_NAV_ACC = 1 << 0,
+ BLACKBOX_FEATURE_NAV_POS = 1 << 1,
+ BLACKBOX_FEATURE_NAV_PID = 1 << 2,
+ BLACKBOX_FEATURE_MAG = 1 << 3,
+ BLACKBOX_FEATURE_ACC = 1 << 4,
+ BLACKBOX_FEATURE_ATTITUDE = 1 << 5,
+ BLACKBOX_FEATURE_RC_DATA = 1 << 6,
+ BLACKBOX_FEATURE_RC_COMMAND = 1 << 7,
+ BLACKBOX_FEATURE_MOTORS = 1 << 8,
+ BLACKBOX_FEATURE_GYRO_RAW = 1 << 9,
+ BLACKBOX_FEATURE_GYRO_PEAKS_ROLL = 1 << 10,
+ BLACKBOX_FEATURE_GYRO_PEAKS_PITCH = 1 << 11,
+ BLACKBOX_FEATURE_GYRO_PEAKS_YAW = 1 << 12,
+ BLACKBOX_FEATURE_SERVOS = 1 << 13,
+} blackboxFeatureMask_e;
+
+// ../../../src/main/blackbox/blackbox.h
+typedef enum BlackboxState {
+ BLACKBOX_STATE_DISABLED = 0,
+ BLACKBOX_STATE_STOPPED,
+ BLACKBOX_STATE_PREPARE_LOG_FILE,
+ BLACKBOX_STATE_SEND_HEADER,
+ BLACKBOX_STATE_SEND_MAIN_FIELD_HEADER,
+ BLACKBOX_STATE_SEND_GPS_H_HEADER,
+ BLACKBOX_STATE_SEND_GPS_G_HEADER,
+ BLACKBOX_STATE_SEND_SLOW_HEADER,
+ BLACKBOX_STATE_SEND_SYSINFO,
+ BLACKBOX_STATE_PAUSED,
+ BLACKBOX_STATE_RUNNING,
+ BLACKBOX_STATE_SHUTTING_DOWN
+} BlackboxState;
+
+// ../../../src/main/blackbox/blackbox.h
+enum BlackboxState {
+ BLACKBOX_STATE_DISABLED = 0,
+ BLACKBOX_STATE_STOPPED,
+ BLACKBOX_STATE_PREPARE_LOG_FILE,
+ BLACKBOX_STATE_SEND_HEADER,
+ BLACKBOX_STATE_SEND_MAIN_FIELD_HEADER,
+ BLACKBOX_STATE_SEND_GPS_H_HEADER,
+ BLACKBOX_STATE_SEND_GPS_G_HEADER,
+ BLACKBOX_STATE_SEND_SLOW_HEADER,
+ BLACKBOX_STATE_SEND_SYSINFO,
+ BLACKBOX_STATE_PAUSED,
+ BLACKBOX_STATE_RUNNING,
+ BLACKBOX_STATE_SHUTTING_DOWN
+} BlackboxState;
+typedef enum BlackboxState BlackboxState;
+
+// ../../../src/main/blackbox/blackbox_io.h
+typedef enum BlackboxDevice {
+ BLACKBOX_DEVICE_SERIAL = 0,
+
+#ifdef USE_FLASHFS
+ BLACKBOX_DEVICE_FLASH = 1,
+#endif
+#ifdef USE_SDCARD
+ BLACKBOX_DEVICE_SDCARD = 2,
+#endif
+#if defined(SITL_BUILD)
+ BLACKBOX_DEVICE_FILE = 3,
+#endif
+
+ BLACKBOX_DEVICE_END
+} BlackboxDevice;
+
+// ../../../src/main/blackbox/blackbox_io.h
+typedef enum {
+ BLACKBOX_RESERVE_SUCCESS,
+ BLACKBOX_RESERVE_TEMPORARY_FAILURE,
+ BLACKBOX_RESERVE_PERMANENT_FAILURE
+} blackboxBufferReserveStatus_e;
+
+// ../../../src/main/blackbox/blackbox_io.h
+enum BlackboxDevice {
+ BLACKBOX_DEVICE_SERIAL = 0,
+
+#ifdef USE_FLASHFS
+ BLACKBOX_DEVICE_FLASH = 1,
+#endif
+#ifdef USE_SDCARD
+ BLACKBOX_DEVICE_SDCARD = 2,
+#endif
+#if defined(SITL_BUILD)
+ BLACKBOX_DEVICE_FILE = 3,
+#endif
+
+ BLACKBOX_DEVICE_END
+} BlackboxDevice;
+typedef enum BlackboxDevice BlackboxDevice;
+
+// ../../../src/main/navigation/navigation_private.h
+typedef enum {
+ NAV_POS_UPDATE_NONE = 0,
+ NAV_POS_UPDATE_Z = 1 << 1,
+ NAV_POS_UPDATE_XY = 1 << 0,
+ NAV_POS_UPDATE_HEADING = 1 << 2,
+ NAV_POS_UPDATE_BEARING = 1 << 3,
+ NAV_POS_UPDATE_BEARING_TAIL_FIRST = 1 << 4,
+} navSetWaypointFlags_t;
+
+// ../../../src/main/navigation/navigation_private.h
+typedef enum {
+ ROC_TO_ALT_CURRENT,
+ ROC_TO_ALT_CONSTANT,
+ ROC_TO_ALT_TARGET
+} climbRateToAltitudeControllerMode_e;
+
+// ../../../src/main/navigation/navigation_private.h
+typedef enum {
+ EST_NONE = 0,
+ EST_USABLE = 1,
+ EST_TRUSTED = 2
+} navigationEstimateStatus_e;
+
+// ../../../src/main/navigation/navigation_private.h
+typedef enum {
+ NAV_HOME_INVALID = 0,
+ NAV_HOME_VALID_XY = 1 << 0,
+ NAV_HOME_VALID_Z = 1 << 1,
+ NAV_HOME_VALID_HEADING = 1 << 2,
+ NAV_HOME_VALID_ALL = NAV_HOME_VALID_XY | NAV_HOME_VALID_Z | NAV_HOME_VALID_HEADING,
+} navigationHomeFlags_t;
+
+// ../../../src/main/navigation/navigation_private.h
+typedef enum {
+ NAV_FSM_EVENT_NONE = 0,
+ NAV_FSM_EVENT_TIMEOUT,
+
+ NAV_FSM_EVENT_SUCCESS,
+ NAV_FSM_EVENT_ERROR,
+
+ NAV_FSM_EVENT_SWITCH_TO_IDLE,
+ NAV_FSM_EVENT_SWITCH_TO_ALTHOLD,
+ NAV_FSM_EVENT_SWITCH_TO_POSHOLD_3D,
+ NAV_FSM_EVENT_SWITCH_TO_RTH,
+ NAV_FSM_EVENT_SWITCH_TO_WAYPOINT,
+ NAV_FSM_EVENT_SWITCH_TO_EMERGENCY_LANDING,
+ NAV_FSM_EVENT_SWITCH_TO_LAUNCH,
+ NAV_FSM_EVENT_SWITCH_TO_COURSE_HOLD,
+ NAV_FSM_EVENT_SWITCH_TO_CRUISE,
+ NAV_FSM_EVENT_SWITCH_TO_COURSE_ADJ,
+ NAV_FSM_EVENT_SWITCH_TO_MIXERAT,
+ NAV_FSM_EVENT_SWITCH_TO_NAV_STATE_FW_LANDING,
+ NAV_FSM_EVENT_SWITCH_TO_SEND_TO,
+
+ NAV_FSM_EVENT_STATE_SPECIFIC_1,
+ NAV_FSM_EVENT_STATE_SPECIFIC_2,
+ NAV_FSM_EVENT_STATE_SPECIFIC_3,
+ NAV_FSM_EVENT_STATE_SPECIFIC_4,
+ NAV_FSM_EVENT_STATE_SPECIFIC_5,
+
+ NAV_FSM_EVENT_SWITCH_TO_NAV_STATE_FW_LANDING_ABORT = NAV_FSM_EVENT_STATE_SPECIFIC_1,
+ NAV_FSM_EVENT_SWITCH_TO_NAV_STATE_FW_LANDING_FINISHED = NAV_FSM_EVENT_STATE_SPECIFIC_2,
+ NAV_FSM_EVENT_SWITCH_TO_WAYPOINT_HOLD_TIME = NAV_FSM_EVENT_STATE_SPECIFIC_1,
+ NAV_FSM_EVENT_SWITCH_TO_WAYPOINT_RTH_LAND = NAV_FSM_EVENT_STATE_SPECIFIC_2,
+ NAV_FSM_EVENT_SWITCH_TO_WAYPOINT_FINISHED = NAV_FSM_EVENT_STATE_SPECIFIC_3,
+ NAV_FSM_EVENT_SWITCH_TO_NAV_STATE_RTH_INITIALIZE = NAV_FSM_EVENT_STATE_SPECIFIC_1,
+ NAV_FSM_EVENT_SWITCH_TO_NAV_STATE_RTH_TRACKBACK = NAV_FSM_EVENT_STATE_SPECIFIC_2,
+ NAV_FSM_EVENT_SWITCH_TO_RTH_HEAD_HOME = NAV_FSM_EVENT_STATE_SPECIFIC_3,
+ NAV_FSM_EVENT_SWITCH_TO_RTH_LOITER_ABOVE_HOME = NAV_FSM_EVENT_STATE_SPECIFIC_4,
+ NAV_FSM_EVENT_SWITCH_TO_RTH_LANDING = NAV_FSM_EVENT_STATE_SPECIFIC_5,
+
+ NAV_FSM_EVENT_COUNT,
+} navigationFSMEvent_t;
+
+// ../../../src/main/navigation/navigation_private.h
+typedef enum {
+ NAV_PERSISTENT_ID_UNDEFINED = 0,
+
+ NAV_PERSISTENT_ID_IDLE = 1,
+
+ NAV_PERSISTENT_ID_ALTHOLD_INITIALIZE = 2,
+ NAV_PERSISTENT_ID_ALTHOLD_IN_PROGRESS = 3,
+
+ NAV_PERSISTENT_ID_UNUSED_1 = 4,
+ NAV_PERSISTENT_ID_UNUSED_2 = 5,
+
+ NAV_PERSISTENT_ID_POSHOLD_3D_INITIALIZE = 6,
+ NAV_PERSISTENT_ID_POSHOLD_3D_IN_PROGRESS = 7,
+
+ NAV_PERSISTENT_ID_RTH_INITIALIZE = 8,
+ NAV_PERSISTENT_ID_RTH_CLIMB_TO_SAFE_ALT = 9,
+ NAV_PERSISTENT_ID_RTH_HEAD_HOME = 10,
+ NAV_PERSISTENT_ID_RTH_LOITER_PRIOR_TO_LANDING = 11,
+ NAV_PERSISTENT_ID_RTH_LANDING = 12,
+ NAV_PERSISTENT_ID_RTH_FINISHING = 13,
+ NAV_PERSISTENT_ID_RTH_FINISHED = 14,
+
+ NAV_PERSISTENT_ID_WAYPOINT_INITIALIZE = 15,
+ NAV_PERSISTENT_ID_WAYPOINT_PRE_ACTION = 16,
+ NAV_PERSISTENT_ID_WAYPOINT_IN_PROGRESS = 17,
+ NAV_PERSISTENT_ID_WAYPOINT_REACHED = 18,
+ NAV_PERSISTENT_ID_WAYPOINT_NEXT = 19,
+ NAV_PERSISTENT_ID_WAYPOINT_FINISHED = 20,
+ NAV_PERSISTENT_ID_WAYPOINT_RTH_LAND = 21,
+
+ NAV_PERSISTENT_ID_EMERGENCY_LANDING_INITIALIZE = 22,
+ NAV_PERSISTENT_ID_EMERGENCY_LANDING_IN_PROGRESS = 23,
+ NAV_PERSISTENT_ID_EMERGENCY_LANDING_FINISHED = 24,
+
+ NAV_PERSISTENT_ID_LAUNCH_INITIALIZE = 25,
+ NAV_PERSISTENT_ID_LAUNCH_WAIT = 26,
+ NAV_PERSISTENT_ID_UNUSED_3 = 27,
+ NAV_PERSISTENT_ID_LAUNCH_IN_PROGRESS = 28,
+
+ NAV_PERSISTENT_ID_COURSE_HOLD_INITIALIZE = 29,
+ NAV_PERSISTENT_ID_COURSE_HOLD_IN_PROGRESS = 30,
+ NAV_PERSISTENT_ID_COURSE_HOLD_ADJUSTING = 31,
+
+ NAV_PERSISTENT_ID_CRUISE_INITIALIZE = 32,
+ NAV_PERSISTENT_ID_CRUISE_IN_PROGRESS = 33,
+ NAV_PERSISTENT_ID_CRUISE_ADJUSTING = 34,
+
+ NAV_PERSISTENT_ID_WAYPOINT_HOLD_TIME = 35,
+ NAV_PERSISTENT_ID_RTH_LOITER_ABOVE_HOME = 36,
+ NAV_PERSISTENT_ID_UNUSED_4 = 37,
+ NAV_PERSISTENT_ID_RTH_TRACKBACK = 38,
+
+ NAV_PERSISTENT_ID_MIXERAT_INITIALIZE = 39,
+ NAV_PERSISTENT_ID_MIXERAT_IN_PROGRESS = 40,
+ NAV_PERSISTENT_ID_MIXERAT_ABORT = 41,
+ NAV_PERSISTENT_ID_FW_LANDING_CLIMB_TO_LOITER = 42,
+ NAV_PERSISTENT_ID_FW_LANDING_LOITER = 43,
+ NAV_PERSISTENT_ID_FW_LANDING_APPROACH = 44,
+ NAV_PERSISTENT_ID_FW_LANDING_GLIDE = 45,
+ NAV_PERSISTENT_ID_FW_LANDING_FLARE = 46,
+ NAV_PERSISTENT_ID_FW_LANDING_ABORT = 47,
+ NAV_PERSISTENT_ID_FW_LANDING_FINISHED = 48,
+
+ NAV_PERSISTENT_ID_SEND_TO_INITALIZE = 49,
+ NAV_PERSISTENT_ID_SEND_TO_IN_PROGRES = 50,
+ NAV_PERSISTENT_ID_SEND_TO_FINISHED = 51
+} navigationPersistentId_e;
+
+// ../../../src/main/navigation/navigation_private.h
+typedef enum {
+ NAV_STATE_UNDEFINED = 0,
+
+ NAV_STATE_IDLE,
+
+ NAV_STATE_ALTHOLD_INITIALIZE,
+ NAV_STATE_ALTHOLD_IN_PROGRESS,
+
+ NAV_STATE_POSHOLD_3D_INITIALIZE,
+ NAV_STATE_POSHOLD_3D_IN_PROGRESS,
+
+ NAV_STATE_RTH_INITIALIZE,
+ NAV_STATE_RTH_CLIMB_TO_SAFE_ALT,
+ NAV_STATE_RTH_TRACKBACK,
+ NAV_STATE_RTH_HEAD_HOME,
+ NAV_STATE_RTH_LOITER_PRIOR_TO_LANDING,
+ NAV_STATE_RTH_LOITER_ABOVE_HOME,
+ NAV_STATE_RTH_LANDING,
+ NAV_STATE_RTH_FINISHING,
+ NAV_STATE_RTH_FINISHED,
+
+ NAV_STATE_WAYPOINT_INITIALIZE,
+ NAV_STATE_WAYPOINT_PRE_ACTION,
+ NAV_STATE_WAYPOINT_IN_PROGRESS,
+ NAV_STATE_WAYPOINT_REACHED,
+ NAV_STATE_WAYPOINT_HOLD_TIME,
+ NAV_STATE_WAYPOINT_NEXT,
+ NAV_STATE_WAYPOINT_FINISHED,
+ NAV_STATE_WAYPOINT_RTH_LAND,
+
+ NAV_STATE_EMERGENCY_LANDING_INITIALIZE,
+ NAV_STATE_EMERGENCY_LANDING_IN_PROGRESS,
+ NAV_STATE_EMERGENCY_LANDING_FINISHED,
+
+ NAV_STATE_LAUNCH_INITIALIZE,
+ NAV_STATE_LAUNCH_WAIT,
+ NAV_STATE_LAUNCH_IN_PROGRESS,
+
+ NAV_STATE_COURSE_HOLD_INITIALIZE,
+ NAV_STATE_COURSE_HOLD_IN_PROGRESS,
+ NAV_STATE_COURSE_HOLD_ADJUSTING,
+ NAV_STATE_CRUISE_INITIALIZE,
+ NAV_STATE_CRUISE_IN_PROGRESS,
+ NAV_STATE_CRUISE_ADJUSTING,
+
+ NAV_STATE_FW_LANDING_CLIMB_TO_LOITER,
+ NAV_STATE_FW_LANDING_LOITER,
+ NAV_STATE_FW_LANDING_APPROACH,
+ NAV_STATE_FW_LANDING_GLIDE,
+ NAV_STATE_FW_LANDING_FLARE,
+ NAV_STATE_FW_LANDING_FINISHED,
+ NAV_STATE_FW_LANDING_ABORT,
+
+ NAV_STATE_MIXERAT_INITIALIZE,
+ NAV_STATE_MIXERAT_IN_PROGRESS,
+ NAV_STATE_MIXERAT_ABORT,
+
+ NAV_STATE_SEND_TO_INITALIZE,
+ NAV_STATE_SEND_TO_IN_PROGESS,
+ NAV_STATE_SEND_TO_FINISHED,
+
+ NAV_STATE_COUNT,
+} navigationFSMState_t;
+
+// ../../../src/main/navigation/navigation_private.h
+typedef enum {
+
+ NAV_CTL_ALT = (1 << 0),
+ NAV_CTL_POS = (1 << 1),
+ NAV_CTL_YAW = (1 << 2),
+ NAV_CTL_EMERG = (1 << 3),
+ NAV_CTL_LAUNCH = (1 << 4),
+
+
+ NAV_REQUIRE_ANGLE = (1 << 5),
+ NAV_REQUIRE_ANGLE_FW = (1 << 6),
+ NAV_REQUIRE_MAGHOLD = (1 << 7),
+ NAV_REQUIRE_THRTILT = (1 << 8),
+
+
+ NAV_AUTO_RTH = (1 << 9),
+ NAV_AUTO_WP = (1 << 10),
+
+
+ NAV_RC_ALT = (1 << 11),
+ NAV_RC_POS = (1 << 12),
+ NAV_RC_YAW = (1 << 13),
+
+
+ NAV_CTL_LAND = (1 << 14),
+ NAV_AUTO_WP_DONE = (1 << 15),
+
+ NAV_MIXERAT = (1 << 16),
+ NAV_CTL_HOLD = (1 << 17),
+} navigationFSMStateFlags_t;
+
+// ../../../src/main/navigation/navigation_private.h
+typedef enum {
+ FW_AUTOLAND_WP_TURN,
+ FW_AUTOLAND_WP_FINAL_APPROACH,
+ FW_AUTOLAND_WP_LAND,
+ FW_AUTOLAND_WP_COUNT,
+} fwAutolandWaypoint_t;
+
+// ../../../src/main/navigation/navigation_private.h
+typedef enum {
+ RTH_HOME_ENROUTE_INITIAL,
+ RTH_HOME_ENROUTE_PROPORTIONAL,
+ RTH_HOME_ENROUTE_FINAL,
+ RTH_HOME_FINAL_LOITER,
+ RTH_HOME_FINAL_LAND,
+} rthTargetMode_e;
+
+// ../../../src/main/navigation/navigation_pos_estimator_private.h
+typedef enum {
+ SURFACE_QUAL_LOW,
+ SURFACE_QUAL_MID,
+ SURFACE_QUAL_HIGH
+} navAGLEstimateQuality_e;
+
+// ../../../src/main/navigation/navigation_pos_estimator_private.h
+typedef enum {
+ EST_GPS_XY_VALID = (1 << 0),
+ EST_GPS_Z_VALID = (1 << 1),
+ EST_BARO_VALID = (1 << 2),
+ EST_SURFACE_VALID = (1 << 3),
+ EST_FLOW_VALID = (1 << 4),
+ EST_XY_VALID = (1 << 5),
+ EST_Z_VALID = (1 << 6),
+} navPositionEstimationFlags_e;
+
+// ../../../src/main/navigation/navigation_pos_estimator_private.h
+typedef enum {
+ ALTITUDE_SOURCE_GPS,
+ ALTITUDE_SOURCE_BARO,
+ ALTITUDE_SOURCE_GPS_ONLY,
+ ALTITUDE_SOURCE_BARO_ONLY,
+} navDefaultAltitudeSensor_e;
+
+// ../../../src/main/navigation/navigation_fw_launch.c
+typedef enum {
+ FW_LAUNCH_MESSAGE_TYPE_NONE = 0,
+ FW_LAUNCH_MESSAGE_TYPE_WAIT_THROTTLE,
+ FW_LAUNCH_MESSAGE_TYPE_WAIT_IDLE,
+ FW_LAUNCH_MESSAGE_TYPE_WAIT_DETECTION,
+ FW_LAUNCH_MESSAGE_TYPE_IN_PROGRESS,
+ FW_LAUNCH_MESSAGE_TYPE_FINISHING
+} fixedWingLaunchMessage_t;
+
+// ../../../src/main/navigation/navigation_fw_launch.c
+typedef enum {
+ FW_LAUNCH_EVENT_NONE = 0,
+ FW_LAUNCH_EVENT_SUCCESS,
+ FW_LAUNCH_EVENT_GOTO_DETECTION,
+ FW_LAUNCH_EVENT_ABORT,
+ FW_LAUNCH_EVENT_THROTTLE_LOW,
+ FW_LAUNCH_EVENT_COUNT
+} fixedWingLaunchEvent_t;
+
+// ../../../src/main/navigation/navigation_fw_launch.c
+typedef enum {
+ FW_LAUNCH_STATE_WAIT_THROTTLE = 0,
+ FW_LAUNCH_STATE_IDLE_WIGGLE_WAIT,
+ FW_LAUNCH_STATE_IDLE_MOTOR_DELAY,
+ FW_LAUNCH_STATE_MOTOR_IDLE,
+ FW_LAUNCH_STATE_WAIT_DETECTION,
+ FW_LAUNCH_STATE_DETECTED,
+ FW_LAUNCH_STATE_MOTOR_DELAY,
+ FW_LAUNCH_STATE_MOTOR_SPINUP,
+ FW_LAUNCH_STATE_IN_PROGRESS,
+ FW_LAUNCH_STATE_FINISH,
+ FW_LAUNCH_STATE_ABORTED,
+ FW_LAUNCH_STATE_FLYING,
+ FW_LAUNCH_STATE_COUNT
+} fixedWingLaunchState_t;
+
+// ../../../src/main/navigation/navigation.h
+typedef enum {
+ SAFEHOME_USAGE_OFF = 0,
+ SAFEHOME_USAGE_RTH = 1,
+ SAFEHOME_USAGE_RTH_FS = 2,
+} safehomeUsageMode_e;
+
+// ../../../src/main/navigation/navigation.h
+typedef enum {
+ FW_AUTOLAND_APPROACH_DIRECTION_LEFT,
+ FW_AUTOLAND_APPROACH_DIRECTION_RIGHT
+} fwAutolandApproachDirection_e;
+
+// ../../../src/main/navigation/navigation.h
+typedef enum {
+ FW_AUTOLAND_STATE_IDLE,
+ FW_AUTOLAND_STATE_LOITER,
+ FW_AUTOLAND_STATE_DOWNWIND,
+ FW_AUTOLAND_STATE_BASE_LEG,
+ FW_AUTOLAND_STATE_FINAL_APPROACH,
+ FW_AUTOLAND_STATE_GLIDE,
+ FW_AUTOLAND_STATE_FLARE
+} fwAutolandState_t;
+
+// ../../../src/main/navigation/navigation.h
+typedef enum {
+ GEOZONE_MESSAGE_STATE_NONE,
+ GEOZONE_MESSAGE_STATE_NFZ,
+ GEOZONE_MESSAGE_STATE_LEAVING_FZ,
+ GEOZONE_MESSAGE_STATE_OUTSIDE_FZ,
+ GEOZONE_MESSAGE_STATE_ENTERING_NFZ,
+ GEOZONE_MESSAGE_STATE_AVOIDING_FB,
+ GEOZONE_MESSAGE_STATE_RETURN_TO_ZONE,
+ GEOZONE_MESSAGE_STATE_FLYOUT_NFZ,
+ GEOZONE_MESSAGE_STATE_AVOIDING_ALTITUDE_BREACH,
+ GEOZONE_MESSAGE_STATE_POS_HOLD
+} geozoneMessageState_e;
+
+// ../../../src/main/navigation/navigation.h
+typedef enum {
+ NAV_RESET_NEVER = 0,
+ NAV_RESET_ON_FIRST_ARM,
+ NAV_RESET_ON_EACH_ARM,
+} nav_reset_type_e;
+
+// ../../../src/main/navigation/navigation.h
+typedef enum {
+ NAV_RTH_ALLOW_LANDING_NEVER = 0,
+ NAV_RTH_ALLOW_LANDING_ALWAYS = 1,
+ NAV_RTH_ALLOW_LANDING_FS_ONLY = 2,
+} navRTHAllowLanding_e;
+
+// ../../../src/main/navigation/navigation.h
+typedef enum {
+ NAV_EXTRA_ARMING_SAFETY_ON = 0,
+ NAV_EXTRA_ARMING_SAFETY_ALLOW_BYPASS = 1,
+} navExtraArmingSafety_e;
+
+// ../../../src/main/navigation/navigation.h
+typedef enum {
+ NAV_ARMING_BLOCKER_NONE = 0,
+ NAV_ARMING_BLOCKER_MISSING_GPS_FIX = 1,
+ NAV_ARMING_BLOCKER_NAV_IS_ALREADY_ACTIVE = 2,
+ NAV_ARMING_BLOCKER_FIRST_WAYPOINT_TOO_FAR = 3,
+ NAV_ARMING_BLOCKER_JUMP_WAYPOINT_ERROR = 4,
+} navArmingBlocker_e;
+
+// ../../../src/main/navigation/navigation.h
+typedef enum {
+ NOMS_OFF_ALWAYS,
+ NOMS_OFF,
+ NOMS_AUTO_ONLY,
+ NOMS_ALL_NAV
+} navOverridesMotorStop_e;
+
+// ../../../src/main/navigation/navigation.h
+typedef enum {
+ RTH_CLIMB_OFF,
+ RTH_CLIMB_ON,
+ RTH_CLIMB_ON_FW_SPIRAL,
+} navRTHClimbFirst_e;
+
+// ../../../src/main/navigation/navigation.h
+typedef enum {
+ FW_LAUNCH_DETECTED = 5,
+ FW_LAUNCH_ABORTED = 10,
+ FW_LAUNCH_FLYING = 11,
+} navFwLaunchStatus_e;
+
+// ../../../src/main/navigation/navigation.h
+typedef enum {
+ WP_PLAN_WAIT,
+ WP_PLAN_SAVE,
+ WP_PLAN_OK,
+ WP_PLAN_FULL,
+} wpMissionPlannerStatus_e;
+
+// ../../../src/main/navigation/navigation.h
+typedef enum {
+ WP_MISSION_START,
+ WP_MISSION_RESUME,
+ WP_MISSION_SWITCH,
+} navMissionRestart_e;
+
+// ../../../src/main/navigation/navigation.h
+typedef enum {
+ RTH_TRACKBACK_OFF,
+ RTH_TRACKBACK_ON,
+ RTH_TRACKBACK_FS,
+} rthTrackbackMode_e;
+
+// ../../../src/main/navigation/navigation.h
+typedef enum {
+ WP_TURN_SMOOTHING_OFF,
+ WP_TURN_SMOOTHING_ON,
+ WP_TURN_SMOOTHING_CUT,
+} wpFwTurnSmoothing_e;
+
+// ../../../src/main/navigation/navigation.h
+typedef enum {
+ MC_ALT_HOLD_STICK,
+ MC_ALT_HOLD_MID,
+ MC_ALT_HOLD_HOVER,
+} navMcAltHoldThrottle_e;
+
+// ../../../src/main/navigation/navigation.h
+typedef enum {
+ NAV_WP_ACTION_WAYPOINT = 0x01,
+ NAV_WP_ACTION_HOLD_TIME = 0x03,
+ NAV_WP_ACTION_RTH = 0x04,
+ NAV_WP_ACTION_SET_POI = 0x05,
+ NAV_WP_ACTION_JUMP = 0x06,
+ NAV_WP_ACTION_SET_HEAD = 0x07,
+ NAV_WP_ACTION_LAND = 0x08
+} navWaypointActions_e;
+
+// ../../../src/main/navigation/navigation.h
+typedef enum {
+ NAV_WP_HEAD_MODE_NONE = 0,
+ NAV_WP_HEAD_MODE_POI = 1,
+ NAV_WP_HEAD_MODE_FIXED = 2
+} navWaypointHeadings_e;
+
+// ../../../src/main/navigation/navigation.h
+typedef enum {
+ NAV_WP_FLAG_HOME = 0x48,
+ NAV_WP_FLAG_LAST = 0xA5
+} navWaypointFlags_e;
+
+// ../../../src/main/navigation/navigation.h
+typedef enum {
+ NAV_WP_ALTMODE = (1<<0),
+ NAV_WP_USER1 = (1<<1),
+ NAV_WP_USER2 = (1<<2),
+ NAV_WP_USER3 = (1<<3),
+ NAV_WP_USER4 = (1<<4)
+} navWaypointP3Flags_e;
+
+// ../../../src/main/navigation/navigation.h
+typedef enum {
+ MW_GPS_MODE_NONE = 0,
+ MW_GPS_MODE_HOLD,
+ MW_GPS_MODE_RTH,
+ MW_GPS_MODE_NAV,
+ MW_GPS_MODE_EMERG = 15
+} navSystemStatus_Mode_e;
+
+// ../../../src/main/navigation/navigation.h
+typedef enum {
+ MW_NAV_STATE_NONE = 0,
+ MW_NAV_STATE_RTH_START,
+ MW_NAV_STATE_RTH_ENROUTE,
+ MW_NAV_STATE_HOLD_INFINIT,
+ MW_NAV_STATE_HOLD_TIMED,
+ MW_NAV_STATE_WP_ENROUTE,
+ MW_NAV_STATE_PROCESS_NEXT,
+ MW_NAV_STATE_DO_JUMP,
+ MW_NAV_STATE_LAND_START,
+ MW_NAV_STATE_LAND_IN_PROGRESS,
+ MW_NAV_STATE_LANDED,
+ MW_NAV_STATE_LAND_SETTLE,
+ MW_NAV_STATE_LAND_START_DESCENT,
+ MW_NAV_STATE_HOVER_ABOVE_HOME,
+ MW_NAV_STATE_EMERGENCY_LANDING,
+ MW_NAV_STATE_RTH_CLIMB,
+} navSystemStatus_State_e;
+
+// ../../../src/main/navigation/navigation.h
+typedef enum {
+ MW_NAV_ERROR_NONE = 0,
+ MW_NAV_ERROR_TOOFAR,
+ MW_NAV_ERROR_SPOILED_GPS,
+ MW_NAV_ERROR_WP_CRC,
+ MW_NAV_ERROR_FINISH,
+ MW_NAV_ERROR_TIMEWAIT,
+ MW_NAV_ERROR_INVALID_JUMP,
+ MW_NAV_ERROR_INVALID_DATA,
+ MW_NAV_ERROR_WAIT_FOR_RTH_ALT,
+ MW_NAV_ERROR_GPS_FIX_LOST,
+ MW_NAV_ERROR_DISARMED,
+ MW_NAV_ERROR_LANDING
+} navSystemStatus_Error_e;
+
+// ../../../src/main/navigation/navigation.h
+typedef enum {
+ MW_NAV_FLAG_ADJUSTING_POSITION = 1 << 0,
+ MW_NAV_FLAG_ADJUSTING_ALTITUDE = 1 << 1,
+} navSystemStatus_Flags_e;
+
+// ../../../src/main/navigation/navigation.h
+typedef enum {
+ GEO_ALT_ABSOLUTE,
+ GEO_ALT_RELATIVE
+} geoAltitudeConversionMode_e;
+
+// ../../../src/main/navigation/navigation.h
+typedef enum {
+ GEO_ORIGIN_SET,
+ GEO_ORIGIN_RESET_ALTITUDE
+} geoOriginResetMode_e;
+
+// ../../../src/main/navigation/navigation.h
+typedef enum {
+ NAV_WP_TAKEOFF_DATUM,
+ NAV_WP_MSL_DATUM,
+ NAV_WP_TERRAIN_DATUM
+} geoAltitudeDatumFlag_e;
+
+// ../../../src/main/navigation/navigation.h
+enum fenceAction_e {
+ GEOFENCE_ACTION_NONE,
+ GEOFENCE_ACTION_AVOID,
+ GEOFENCE_ACTION_POS_HOLD,
+ GEOFENCE_ACTION_RTH,
+};
+typedef enum fenceAction_e fenceAction_e;
+
+// ../../../src/main/navigation/navigation.h
+enum noWayHomeAction {
+ NO_WAY_HOME_ACTION_RTH,
+ NO_WAY_HOME_ACTION_EMRG_LAND,
+};
+typedef enum noWayHomeAction noWayHomeAction;
+
+// ../../../src/main/navigation/navigation_geozone.c
+typedef enum {
+ GEOZONE_ACTION_STATE_NONE,
+ GEOZONE_ACTION_STATE_AVOIDING,
+ GEOZONE_ACTION_STATE_AVOIDING_UPWARD,
+ GEOZONE_ACTION_STATE_AVOIDING_ALTITUDE,
+ GEOZONE_ACTION_STATE_RETURN_TO_FZ,
+ GEOZONE_ACTION_STATE_FLYOUT_NFZ,
+ GEOZONE_ACTION_STATE_POSHOLD,
+ GEOZONE_ACTION_STATE_RTH
+} geozoneActionState_e;
+
+// ../../../src/main/sensors/battery_config_structs.h
+typedef enum {
+ CURRENT_SENSOR_NONE = 0,
+ CURRENT_SENSOR_ADC,
+ CURRENT_SENSOR_VIRTUAL,
+ CURRENT_SENSOR_FAKE,
+ CURRENT_SENSOR_ESC,
+ CURRENT_SENSOR_SMARTPORT,
+ CURRENT_SENSOR_CAN,
+ CURRENT_SENSOR_MAX = CURRENT_SENSOR_CAN
+} currentSensor_e;
+
+// ../../../src/main/sensors/battery_config_structs.h
+typedef enum {
+ VOLTAGE_SENSOR_NONE = 0,
+ VOLTAGE_SENSOR_ADC,
+ VOLTAGE_SENSOR_ESC,
+ VOLTAGE_SENSOR_FAKE,
+ VOLTAGE_SENSOR_SMARTPORT,
+ VOLTAGE_SENSOR_CAN,
+ VOLTAGE_SENSOR_MAX = VOLTAGE_SENSOR_CAN
+} voltageSensor_e;
+
+// ../../../src/main/sensors/battery_config_structs.h
+typedef enum {
+ BAT_CAPACITY_UNIT_MAH,
+ BAT_CAPACITY_UNIT_MWH,
+} batCapacityUnit_e;
+
+// ../../../src/main/sensors/battery_config_structs.h
+typedef enum {
+ BAT_VOLTAGE_RAW,
+ BAT_VOLTAGE_SAG_COMP
+} batVoltageSource_e;
+
+// ../../../src/main/sensors/rangefinder.h
+typedef enum {
+ RANGEFINDER_NONE = 0,
+ RANGEFINDER_SRF10 = 1,
+ RANGEFINDER_VL53L0X = 2,
+ RANGEFINDER_MSP = 3,
+ RANGEFINDER_BENEWAKE = 4,
+ RANGEFINDER_VL53L1X = 5,
+ RANGEFINDER_US42 = 6,
+ RANGEFINDER_TOF10102I2C = 7,
+ RANGEFINDER_FAKE = 8,
+ RANGEFINDER_TERARANGER_EVO = 9,
+ RANGEFINDER_USD1_V0 = 10,
+ RANGEFINDER_NANORADAR = 11,
+} rangefinderType_e;
+
+// ../../../src/main/sensors/gyro.h
+typedef enum {
+ GYRO_NONE = 0,
+ GYRO_AUTODETECT,
+ GYRO_MPU6000,
+ GYRO_MPU6500,
+ GYRO_MPU9250,
+ GYRO_BMI160,
+ GYRO_ICM20689,
+ GYRO_BMI088,
+ GYRO_ICM42605,
+ GYRO_BMI270,
+ GYRO_LSM6DXX,
+ GYRO_ICM45686,
+ GYRO_FAKE
+} gyroSensor_e;
+
+// ../../../src/main/sensors/gyro.h
+typedef enum {
+ DYNAMIC_NOTCH_MODE_2D = 0,
+ DYNAMIC_NOTCH_MODE_3D
+} dynamicGyroNotchMode_e;
+
+// ../../../src/main/sensors/gyro.h
+typedef enum {
+ GYRO_FILTER_MODE_OFF = 0,
+ GYRO_FILTER_MODE_STATIC = 1,
+ GYRO_FILTER_MODE_DYNAMIC = 2,
+ GYRO_FILTER_MODE_ADAPTIVE = 3
+} gyroFilterMode_e;
+
+// ../../../src/main/sensors/opflow.h
+typedef enum {
+ OPFLOW_NONE = 0,
+ OPFLOW_CXOF = 1,
+ OPFLOW_MSP = 2,
+ OPFLOW_FAKE = 3,
+} opticalFlowSensor_e;
+
+// ../../../src/main/sensors/opflow.h
+typedef enum {
+ OPFLOW_QUALITY_INVALID,
+ OPFLOW_QUALITY_VALID
+} opflowQuality_e;
+
+// ../../../src/main/sensors/battery.h
+typedef enum {
+ BATTERY_OK = 0,
+ BATTERY_WARNING,
+ BATTERY_CRITICAL,
+ BATTERY_NOT_PRESENT
+} batteryState_e;
+
+// ../../../src/main/sensors/temperature.h
+typedef enum {
+ TEMP_SENSOR_NONE = 0,
+ TEMP_SENSOR_LM75,
+ TEMP_SENSOR_DS18B20
+} tempSensorType_e;
+
+// ../../../src/main/sensors/pitotmeter.h
+typedef enum {
+ PITOT_NONE = 0,
+ PITOT_AUTODETECT = 1,
+ PITOT_MS4525 = 2,
+ PITOT_ADC = 3,
+ PITOT_VIRTUAL = 4,
+ PITOT_FAKE = 5,
+ PITOT_MSP = 6,
+ PITOT_DLVR = 7,
+} pitotSensor_e;
+
+// ../../../src/main/sensors/esc_sensor.c
+typedef enum {
+ ESC_SENSOR_WAIT_STARTUP = 0,
+ ESC_SENSOR_READY = 1,
+ ESC_SENSOR_WAITING = 2
+} escSensorState_t;
+
+// ../../../src/main/sensors/esc_sensor.c
+typedef enum {
+ ESC_SENSOR_FRAME_PENDING,
+ ESC_SENSOR_FRAME_COMPLETE,
+ ESC_SENSOR_FRAME_FAILED
+} escSensorFrameStatus_t;
+
+// ../../../src/main/sensors/sensors.h
+typedef enum {
+ SENSOR_INDEX_GYRO = 0,
+ SENSOR_INDEX_ACC,
+ SENSOR_INDEX_BARO,
+ SENSOR_INDEX_MAG,
+ SENSOR_INDEX_RANGEFINDER,
+ SENSOR_INDEX_PITOT,
+ SENSOR_INDEX_OPFLOW,
+ SENSOR_INDEX_COUNT
+} sensorIndex_e;
+
+// ../../../src/main/sensors/sensors.h
+typedef enum {
+ SENSOR_GYRO = 1 << 0,
+ SENSOR_ACC = 1 << 1,
+ SENSOR_BARO = 1 << 2,
+ SENSOR_MAG = 1 << 3,
+ SENSOR_RANGEFINDER = 1 << 4,
+ SENSOR_PITOT = 1 << 5,
+ SENSOR_OPFLOW = 1 << 6,
+ SENSOR_GPS = 1 << 7,
+ SENSOR_GPSMAG = 1 << 8,
+ SENSOR_TEMP = 1 << 9
+} sensors_e;
+
+// ../../../src/main/sensors/sensors.h
+typedef enum {
+ SENSOR_TEMP_CAL_INITIALISE,
+ SENSOR_TEMP_CAL_IN_PROGRESS,
+ SENSOR_TEMP_CAL_COMPLETE,
+} sensorTempCalState_e;
+
+// ../../../src/main/sensors/barometer.c
+typedef enum {
+ BAROMETER_NEEDS_SAMPLES = 0,
+ BAROMETER_NEEDS_CALCULATION
+} barometerState_e;
+
+// ../../../src/main/sensors/acceleration.h
+typedef enum {
+ ACC_NONE = 0,
+ ACC_AUTODETECT,
+ ACC_MPU6000,
+ ACC_MPU6500,
+ ACC_MPU9250,
+ ACC_BMI160,
+ ACC_ICM20689,
+ ACC_BMI088,
+ ACC_ICM42605,
+ ACC_BMI270,
+ ACC_LSM6DXX,
+ ACC_ICM45686,
+ ACC_FAKE,
+ ACC_MAX = ACC_FAKE
+} accelerationSensor_e;
+
+// ../../../src/main/sensors/barometer.h
+typedef enum {
+ BARO_NONE = 0,
+ BARO_AUTODETECT = 1,
+ BARO_BMP085 = 2,
+ BARO_MS5611 = 3,
+ BARO_BMP280 = 4,
+ BARO_MS5607 = 5,
+ BARO_LPS25H = 6,
+ BARO_SPL06 = 7,
+ BARO_BMP388 = 8,
+ BARO_DPS310 = 9,
+ BARO_B2SMPB = 10,
+ BARO_MSP = 11,
+ BARO_FAKE = 12,
+ BARO_MAX = BARO_FAKE
+} baroSensor_e;
+
+// ../../../src/main/sensors/diagnostics.h
+typedef enum {
+ HW_SENSOR_NONE = 0,
+ HW_SENSOR_OK = 1,
+ HW_SENSOR_UNAVAILABLE = 2,
+ HW_SENSOR_UNHEALTHY = 3,
+} hardwareSensorStatus_e;
+
+// ../../../src/main/sensors/compass.h
+typedef enum {
+ MAG_NONE = 0,
+ MAG_AUTODETECT,
+ MAG_HMC5883,
+ MAG_AK8975,
+ MAG_MAG3110,
+ MAG_AK8963,
+ MAG_IST8310,
+ MAG_QMC5883,
+ MAG_QMC5883P,
+ MAG_MPU9250,
+ MAG_IST8308,
+ MAG_LIS3MDL,
+ MAG_MSP,
+ MAG_RM3100,
+ MAG_VCM5883,
+ MAG_MLX90393,
+ MAG_FAKE,
+ MAG_MAX = MAG_FAKE
+} magSensor_e;
+
+// ../../../src/main/programming/logic_condition.h
+typedef enum {
+ LOGIC_CONDITION_TRUE = 0,
+ LOGIC_CONDITION_EQUAL = 1,
+ LOGIC_CONDITION_GREATER_THAN = 2,
+ LOGIC_CONDITION_LOWER_THAN = 3,
+ LOGIC_CONDITION_LOW = 4,
+ LOGIC_CONDITION_MID = 5,
+ LOGIC_CONDITION_HIGH = 6,
+ LOGIC_CONDITION_AND = 7,
+ LOGIC_CONDITION_OR = 8,
+ LOGIC_CONDITION_XOR = 9,
+ LOGIC_CONDITION_NAND = 10,
+ LOGIC_CONDITION_NOR = 11,
+ LOGIC_CONDITION_NOT = 12,
+ LOGIC_CONDITION_STICKY = 13,
+ LOGIC_CONDITION_ADD = 14,
+ LOGIC_CONDITION_SUB = 15,
+ LOGIC_CONDITION_MUL = 16,
+ LOGIC_CONDITION_DIV = 17,
+ LOGIC_CONDITION_GVAR_SET = 18,
+ LOGIC_CONDITION_GVAR_INC = 19,
+ LOGIC_CONDITION_GVAR_DEC = 20,
+ LOGIC_CONDITION_PORT_SET = 21,
+ LOGIC_CONDITION_OVERRIDE_ARMING_SAFETY = 22,
+ LOGIC_CONDITION_OVERRIDE_THROTTLE_SCALE = 23,
+ LOGIC_CONDITION_SWAP_ROLL_YAW = 24,
+ LOGIC_CONDITION_SET_VTX_POWER_LEVEL = 25,
+ LOGIC_CONDITION_INVERT_ROLL = 26,
+ LOGIC_CONDITION_INVERT_PITCH = 27,
+ LOGIC_CONDITION_INVERT_YAW = 28,
+ LOGIC_CONDITION_OVERRIDE_THROTTLE = 29,
+ LOGIC_CONDITION_SET_VTX_BAND = 30,
+ LOGIC_CONDITION_SET_VTX_CHANNEL = 31,
+ LOGIC_CONDITION_SET_OSD_LAYOUT = 32,
+ LOGIC_CONDITION_SIN = 33,
+ LOGIC_CONDITION_COS = 34,
+ LOGIC_CONDITION_TAN = 35,
+ LOGIC_CONDITION_MAP_INPUT = 36,
+ LOGIC_CONDITION_MAP_OUTPUT = 37,
+ LOGIC_CONDITION_RC_CHANNEL_OVERRIDE = 38,
+ LOGIC_CONDITION_SET_HEADING_TARGET = 39,
+ LOGIC_CONDITION_MODULUS = 40,
+ LOGIC_CONDITION_LOITER_OVERRIDE = 41,
+ LOGIC_CONDITION_SET_PROFILE = 42,
+ LOGIC_CONDITION_MIN = 43,
+ LOGIC_CONDITION_MAX = 44,
+ LOGIC_CONDITION_FLIGHT_AXIS_ANGLE_OVERRIDE = 45,
+ LOGIC_CONDITION_FLIGHT_AXIS_RATE_OVERRIDE = 46,
+ LOGIC_CONDITION_EDGE = 47,
+ LOGIC_CONDITION_DELAY = 48,
+ LOGIC_CONDITION_TIMER = 49,
+ LOGIC_CONDITION_DELTA = 50,
+ LOGIC_CONDITION_APPROX_EQUAL = 51,
+ LOGIC_CONDITION_LED_PIN_PWM = 52,
+ LOGIC_CONDITION_DISABLE_GPS_FIX = 53,
+ LOGIC_CONDITION_RESET_MAG_CALIBRATION = 54,
+ LOGIC_CONDITION_SET_GIMBAL_SENSITIVITY = 55,
+ LOGIC_CONDITION_OVERRIDE_MIN_GROUND_SPEED = 56,
+ LOGIC_CONDITION_SET_ALTITUDE_TARGET = 57,
+ LOGIC_CONDITION_ACOS = 58,
+ LOGIC_CONDITION_ASIN = 59,
+ LOGIC_CONDITION_ATAN2 = 60,
+ LOGIC_CONDITION_LAST
+} logicOperation_e;
+
+// ../../../src/main/programming/logic_condition.h
+typedef enum logicOperandType_s {
+ LOGIC_CONDITION_OPERAND_TYPE_VALUE = 0,
+ LOGIC_CONDITION_OPERAND_TYPE_RC_CHANNEL,
+ LOGIC_CONDITION_OPERAND_TYPE_FLIGHT,
+ LOGIC_CONDITION_OPERAND_TYPE_FLIGHT_MODE,
+ LOGIC_CONDITION_OPERAND_TYPE_LC,
+ LOGIC_CONDITION_OPERAND_TYPE_GVAR,
+ LOGIC_CONDITION_OPERAND_TYPE_PID,
+ LOGIC_CONDITION_OPERAND_TYPE_WAYPOINTS,
+ LOGIC_CONDITION_OPERAND_TYPE_LAST
+} logicOperandType_e;
+
+// ../../../src/main/programming/logic_condition.h
+typedef enum {
+ LOGIC_CONDITION_OPERAND_FLIGHT_ARM_TIMER = 0,
+ LOGIC_CONDITION_OPERAND_FLIGHT_HOME_DISTANCE,
+ LOGIC_CONDITION_OPERAND_FLIGHT_TRIP_DISTANCE,
+ LOGIC_CONDITION_OPERAND_FLIGHT_RSSI,
+ LOGIC_CONDITION_OPERAND_FLIGHT_VBAT,
+ LOGIC_CONDITION_OPERAND_FLIGHT_CELL_VOLTAGE,
+ LOGIC_CONDITION_OPERAND_FLIGHT_CURRENT,
+ LOGIC_CONDITION_OPERAND_FLIGHT_MAH_DRAWN,
+ LOGIC_CONDITION_OPERAND_FLIGHT_GPS_SATS,
+ LOGIC_CONDITION_OPERAND_FLIGHT_GROUD_SPEED,
+ LOGIC_CONDITION_OPERAND_FLIGHT_3D_SPEED,
+ LOGIC_CONDITION_OPERAND_FLIGHT_AIR_SPEED,
+ LOGIC_CONDITION_OPERAND_FLIGHT_ALTITUDE,
+ LOGIC_CONDITION_OPERAND_FLIGHT_VERTICAL_SPEED,
+ LOGIC_CONDITION_OPERAND_FLIGHT_TROTTLE_POS,
+ LOGIC_CONDITION_OPERAND_FLIGHT_ATTITUDE_ROLL,
+ LOGIC_CONDITION_OPERAND_FLIGHT_ATTITUDE_PITCH,
+ LOGIC_CONDITION_OPERAND_FLIGHT_IS_ARMED,
+ LOGIC_CONDITION_OPERAND_FLIGHT_IS_AUTOLAUNCH,
+ LOGIC_CONDITION_OPERAND_FLIGHT_IS_ALTITUDE_CONTROL,
+ LOGIC_CONDITION_OPERAND_FLIGHT_IS_POSITION_CONTROL,
+ LOGIC_CONDITION_OPERAND_FLIGHT_IS_EMERGENCY_LANDING,
+ LOGIC_CONDITION_OPERAND_FLIGHT_IS_RTH,
+ LOGIC_CONDITION_OPERAND_FLIGHT_IS_LANDING,
+ LOGIC_CONDITION_OPERAND_FLIGHT_IS_FAILSAFE,
+ LOGIC_CONDITION_OPERAND_FLIGHT_STABILIZED_ROLL,
+ LOGIC_CONDITION_OPERAND_FLIGHT_STABILIZED_PITCH,
+ LOGIC_CONDITION_OPERAND_FLIGHT_STABILIZED_YAW,
+ LOGIC_CONDITION_OPERAND_FLIGHT_3D_HOME_DISTANCE,
+ LOGIC_CONDITION_OPERAND_FLIGHT_LQ_UPLINK,
+ LOGIC_CONDITION_OPERAND_FLIGHT_SNR,
+ LOGIC_CONDITION_OPERAND_FLIGHT_GPS_VALID,
+ LOGIC_CONDITION_OPERAND_FLIGHT_LOITER_RADIUS,
+ LOGIC_CONDITION_OPERAND_FLIGHT_ACTIVE_PROFILE,
+ LOGIC_CONDITION_OPERAND_FLIGHT_BATT_CELLS,
+ LOGIC_CONDITION_OPERAND_FLIGHT_AGL_STATUS,
+ LOGIC_CONDITION_OPERAND_FLIGHT_AGL,
+ LOGIC_CONDITION_OPERAND_FLIGHT_RANGEFINDER_RAW,
+ LOGIC_CONDITION_OPERAND_FLIGHT_ACTIVE_MIXER_PROFILE,
+ LOGIC_CONDITION_OPERAND_FLIGHT_MIXER_TRANSITION_ACTIVE,
+ LOGIC_CONDITION_OPERAND_FLIGHT_ATTITUDE_YAW,
+ LOGIC_CONDITION_OPERAND_FLIGHT_FW_LAND_STATE,
+ LOGIC_CONDITION_OPERAND_FLIGHT_BATT_PROFILE,
+ LOGIC_CONDITION_OPERAND_FLIGHT_FLOWN_LOITER_RADIUS,
+ LOGIC_CONDITION_OPERAND_FLIGHT_LQ_DOWNLINK,
+ LOGIC_CONDITION_OPERAND_FLIGHT_UPLINK_RSSI_DBM,
+ LOGIC_CONDITION_OPERAND_FLIGHT_MIN_GROUND_SPEED,
+ LOGIC_CONDITION_OPERAND_FLIGHT_HORIZONTAL_WIND_SPEED,
+ LOGIC_CONDITION_OPERAND_FLIGHT_WIND_DIRECTION,
+ LOGIC_CONDITION_OPERAND_FLIGHT_RELATIVE_WIND_OFFSET,
+} logicFlightOperands_e;
+
+// ../../../src/main/programming/logic_condition.h
+typedef enum {
+ LOGIC_CONDITION_OPERAND_FLIGHT_MODE_FAILSAFE,
+ LOGIC_CONDITION_OPERAND_FLIGHT_MODE_MANUAL,
+ LOGIC_CONDITION_OPERAND_FLIGHT_MODE_RTH,
+ LOGIC_CONDITION_OPERAND_FLIGHT_MODE_POSHOLD,
+ LOGIC_CONDITION_OPERAND_FLIGHT_MODE_CRUISE,
+ LOGIC_CONDITION_OPERAND_FLIGHT_MODE_ALTHOLD,
+ LOGIC_CONDITION_OPERAND_FLIGHT_MODE_ANGLE,
+ LOGIC_CONDITION_OPERAND_FLIGHT_MODE_HORIZON,
+ LOGIC_CONDITION_OPERAND_FLIGHT_MODE_AIR,
+ LOGIC_CONDITION_OPERAND_FLIGHT_MODE_USER1,
+ LOGIC_CONDITION_OPERAND_FLIGHT_MODE_USER2,
+ LOGIC_CONDITION_OPERAND_FLIGHT_MODE_COURSE_HOLD,
+ LOGIC_CONDITION_OPERAND_FLIGHT_MODE_USER3,
+ LOGIC_CONDITION_OPERAND_FLIGHT_MODE_USER4,
+ LOGIC_CONDITION_OPERAND_FLIGHT_MODE_ACRO,
+ LOGIC_CONDITION_OPERAND_FLIGHT_MODE_WAYPOINT_MISSION,
+ LOGIC_CONDITION_OPERAND_FLIGHT_MODE_ANGLEHOLD,
+} logicFlightModeOperands_e;
+
+// ../../../src/main/programming/logic_condition.h
+typedef enum {
+ LOGIC_CONDITION_OPERAND_WAYPOINTS_IS_WP,
+ LOGIC_CONDITION_OPERAND_WAYPOINTS_WAYPOINT_INDEX,
+ LOGIC_CONDITION_OPERAND_WAYPOINTS_WAYPOINT_ACTION,
+ LOGIC_CONDITION_OPERAND_WAYPOINTS_NEXT_WAYPOINT_ACTION,
+ LOGIC_CONDITION_OPERAND_WAYPOINTS_WAYPOINT_DISTANCE,
+ LOGIC_CONDTIION_OPERAND_WAYPOINTS_DISTANCE_FROM_WAYPOINT,
+ LOGIC_CONDITION_OPERAND_WAYPOINTS_USER1_ACTION,
+ LOGIC_CONDITION_OPERAND_WAYPOINTS_USER2_ACTION,
+ LOGIC_CONDITION_OPERAND_WAYPOINTS_USER3_ACTION,
+ LOGIC_CONDITION_OPERAND_WAYPOINTS_USER4_ACTION,
+ LOGIC_CONDITION_OPERAND_WAYPOINTS_USER1_ACTION_NEXT_WP,
+ LOGIC_CONDITION_OPERAND_WAYPOINTS_USER2_ACTION_NEXT_WP,
+ LOGIC_CONDITION_OPERAND_WAYPOINTS_USER3_ACTION_NEXT_WP,
+ LOGIC_CONDITION_OPERAND_WAYPOINTS_USER4_ACTION_NEXT_WP,
+} logicWaypointOperands_e;
+
+// ../../../src/main/programming/logic_condition.h
+typedef enum {
+ LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_ARMING_SAFETY = (1 << 0),
+ LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_THROTTLE_SCALE = (1 << 1),
+ LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_SWAP_ROLL_YAW = (1 << 2),
+ LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_INVERT_ROLL = (1 << 3),
+ LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_INVERT_PITCH = (1 << 4),
+ LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_INVERT_YAW = (1 << 5),
+ LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_THROTTLE = (1 << 6),
+ LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_OSD_LAYOUT = (1 << 7),
+ LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_RC_CHANNEL = (1 << 8),
+ LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_LOITER_RADIUS = (1 << 9),
+ LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_FLIGHT_AXIS = (1 << 10),
+#ifdef USE_GPS_FIX_ESTIMATION
+ LOGIC_CONDITION_GLOBAL_FLAG_DISABLE_GPS_FIX = (1 << 11),
+#endif
+ LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_MIN_GROUND_SPEED = (1 << 12),
+} logicConditionsGlobalFlags_t;
+
+// ../../../src/main/programming/logic_condition.h
+typedef enum {
+ LOGIC_CONDITION_FLAG_LATCH = 1 << 0,
+ LOGIC_CONDITION_FLAG_TIMEOUT_SATISFIED = 1 << 1,
+} logicConditionFlags_e;
+
+// ../../../src/main/programming/logic_condition.h
+enum logicOperandType_s {
+ LOGIC_CONDITION_OPERAND_TYPE_VALUE = 0,
+ LOGIC_CONDITION_OPERAND_TYPE_RC_CHANNEL,
+ LOGIC_CONDITION_OPERAND_TYPE_FLIGHT,
+ LOGIC_CONDITION_OPERAND_TYPE_FLIGHT_MODE,
+ LOGIC_CONDITION_OPERAND_TYPE_LC,
+ LOGIC_CONDITION_OPERAND_TYPE_GVAR,
+ LOGIC_CONDITION_OPERAND_TYPE_PID,
+ LOGIC_CONDITION_OPERAND_TYPE_WAYPOINTS,
+ LOGIC_CONDITION_OPERAND_TYPE_LAST
+} logicOperandType_e;
+typedef enum logicOperandType_s logicOperandType_s;
+
+// ../../../src/main/rx/rx.h
+typedef enum {
+ RX_FRAME_PENDING = 0,
+ RX_FRAME_COMPLETE = (1 << 0),
+ RX_FRAME_FAILSAFE = (1 << 1),
+ RX_FRAME_PROCESSING_REQUIRED = (1 << 2),
+ RX_FRAME_DROPPED = (1 << 3),
+} rxFrameState_e;
+
+// ../../../src/main/rx/rx.h
+typedef enum {
+ RX_TYPE_NONE = 0,
+ RX_TYPE_SERIAL,
+ RX_TYPE_MSP,
+ RX_TYPE_SIM
+} rxReceiverType_e;
+
+// ../../../src/main/rx/rx.h
+typedef enum {
+ SERIALRX_SPEKTRUM1024 = 0,
+ SERIALRX_SPEKTRUM2048,
+ SERIALRX_SBUS,
+ SERIALRX_SUMD,
+ SERIALRX_IBUS,
+ SERIALRX_JETIEXBUS,
+ SERIALRX_CRSF,
+ SERIALRX_FPORT,
+ SERIALRX_SBUS_FAST,
+ SERIALRX_FPORT2,
+ SERIALRX_SRXL2,
+ SERIALRX_GHST,
+ SERIALRX_MAVLINK,
+ SERIALRX_FBUS,
+ SERIALRX_SBUS2,
+} rxSerialReceiverType_e;
+
+// ../../../src/main/rx/rx.h
+typedef enum {
+ RSSI_SOURCE_NONE = 0,
+ RSSI_SOURCE_AUTO,
+ RSSI_SOURCE_ADC,
+ RSSI_SOURCE_RX_CHANNEL,
+ RSSI_SOURCE_RX_PROTOCOL,
+ RSSI_SOURCE_MSP,
+} rssiSource_e;
+
+// ../../../src/main/rx/crsf.h
+typedef enum {
+ CRSF_ADDRESS_BROADCAST = 0x00,
+ CRSF_ADDRESS_USB = 0x10,
+ CRSF_ADDRESS_TBS_CORE_PNP_PRO = 0x80,
+ CRSF_ADDRESS_RESERVED1 = 0x8A,
+ CRSF_ADDRESS_CURRENT_SENSOR = 0xC0,
+ CRSF_ADDRESS_GPS = 0xC2,
+ CRSF_ADDRESS_TBS_BLACKBOX = 0xC4,
+ CRSF_ADDRESS_FLIGHT_CONTROLLER = 0xC8,
+ CRSF_ADDRESS_RESERVED2 = 0xCA,
+ CRSF_ADDRESS_RACE_TAG = 0xCC,
+ CRSF_ADDRESS_RADIO_TRANSMITTER = 0xEA,
+ CRSF_ADDRESS_CRSF_RECEIVER = 0xEC,
+ CRSF_ADDRESS_CRSF_TRANSMITTER = 0xEE
+} crsfAddress_e;
+
+// ../../../src/main/rx/crsf.h
+typedef enum {
+ CRSF_FRAMETYPE_GPS = 0x02,
+ CRSF_FRAMETYPE_VARIO_SENSOR = 0x07,
+ CRSF_FRAMETYPE_BATTERY_SENSOR = 0x08,
+ CRSF_FRAMETYPE_BAROMETER_ALTITUDE = 0x09,
+ CRSF_FRAMETYPE_LINK_STATISTICS = 0x14,
+ CRSF_FRAMETYPE_RC_CHANNELS_PACKED = 0x16,
+ CRSF_FRAMETYPE_ATTITUDE = 0x1E,
+ CRSF_FRAMETYPE_FLIGHT_MODE = 0x21,
+
+ CRSF_FRAMETYPE_DEVICE_PING = 0x28,
+ CRSF_FRAMETYPE_DEVICE_INFO = 0x29,
+ CRSF_FRAMETYPE_PARAMETER_SETTINGS_ENTRY = 0x2B,
+ CRSF_FRAMETYPE_PARAMETER_READ = 0x2C,
+ CRSF_FRAMETYPE_PARAMETER_WRITE = 0x2D,
+ CRSF_FRAMETYPE_COMMAND = 0x32,
+
+ CRSF_FRAMETYPE_MSP_REQ = 0x7A,
+ CRSF_FRAMETYPE_MSP_RESP = 0x7B,
+ CRSF_FRAMETYPE_MSP_WRITE = 0x7C,
+ CRSF_FRAMETYPE_DISPLAYPORT_CMD = 0x7D,
+} crsfFrameType_e;
+
+// ../../../src/main/rx/sbus.c
+typedef enum {
+ STATE_SBUS_SYNC = 0,
+ STATE_SBUS_PAYLOAD,
+ STATE_SBUS26_PAYLOAD,
+ STATE_SBUS_WAIT_SYNC
+} sbusDecoderState_e;
+
+// ../../../src/main/rx/ghst_protocol.h
+typedef enum {
+ GHST_ADDR_RADIO = 0x80,
+ GHST_ADDR_TX_MODULE_SYM = 0x81,
+ GHST_ADDR_TX_MODULE_ASYM = 0x88,
+ GHST_ADDR_FC = 0x82,
+ GHST_ADDR_GOGGLES = 0x83,
+ GHST_ADDR_QUANTUM_TEE1 = 0x84,
+ GHST_ADDR_QUANTUM_TEE2 = 0x85,
+ GHST_ADDR_QUANTUM_GW1 = 0x86,
+ GHST_ADDR_5G_CLK = 0x87,
+ GHST_ADDR_RX = 0x89
+} ghstAddr_e;
+
+// ../../../src/main/rx/ghst_protocol.h
+typedef enum {
+
+
+
+ GHST_UL_RC_CHANS_HS4_FIRST = 0x10,
+ GHST_UL_RC_CHANS_HS4_5TO8 = 0x10,
+ GHST_UL_RC_CHANS_HS4_9TO12 = 0x11,
+ GHST_UL_RC_CHANS_HS4_13TO16 = 0x12,
+ GHST_UL_RC_CHANS_HS4_RSSI = 0x13,
+ GHST_UL_RC_CHANS_HS4_LAST = 0x1f
+} ghstUl_e;
+
+// ../../../src/main/rx/ghst_protocol.h
+typedef enum {
+ GHST_DL_OPENTX_SYNC = 0x20,
+ GHST_DL_LINK_STAT = 0x21,
+ GHST_DL_VTX_STAT = 0x22,
+ GHST_DL_PACK_STAT = 0x23,
+ GHST_DL_GPS_PRIMARY = 0x25,
+ GHST_DL_GPS_SECONDARY = 0x26
+} ghstDl_e;
+
+// ../../../src/main/rx/fport2.c
+typedef enum {
+ CFT_RC = 0xFF,
+ CFT_OTA_START = 0xF0,
+ CFT_OTA_DATA = 0xF1,
+ CFT_OTA_STOP = 0xF2
+} fport2_control_frame_type_e;
+
+// ../../../src/main/rx/fport2.c
+typedef enum {
+ FT_CONTROL,
+ FT_DOWNLINK
+} frame_type_e;
+
+// ../../../src/main/rx/fport2.c
+typedef enum {
+ FS_CONTROL_FRAME_START,
+ FS_CONTROL_FRAME_TYPE,
+ FS_CONTROL_FRAME_DATA,
+ FS_DOWNLINK_FRAME_START,
+ FS_DOWNLINK_FRAME_DATA
+} frame_state_e;
+
+// ../../../src/main/rx/jetiexbus.h
+enum exBusHeader_e {
+ EXBUS_HEADER_SYNC = 0,
+ EXBUS_HEADER_REQ,
+ EXBUS_HEADER_MSG_LEN,
+ EXBUS_HEADER_PACKET_ID,
+ EXBUS_HEADER_DATA_ID,
+ EXBUS_HEADER_SUBLEN,
+ EXBUS_HEADER_DATA
+};
+typedef enum exBusHeader_e exBusHeader_e;
+
+// ../../../src/main/rx/srxl2_types.h
+typedef enum {
+ Disabled,
+ ListenForActivity,
+ SendHandshake,
+ ListenForHandshake,
+ Running
+} Srxl2State;
+
+// ../../../src/main/rx/srxl2_types.h
+typedef enum {
+ Handshake = 0x21,
+ BindInfo = 0x41,
+ ParameterConfiguration = 0x50,
+ SignalQuality = 0x55,
+ TelemetrySensorData = 0x80,
+ ControlData = 0xCD,
+} Srxl2PacketType;
+
+// ../../../src/main/rx/srxl2_types.h
+typedef enum {
+ ChannelData = 0x00,
+ FailsafeChannelData = 0x01,
+ VTXData = 0x02,
+} Srxl2ControlDataCommand;
+
+// ../../../src/main/rx/srxl2_types.h
+typedef enum {
+ NoDevice = 0,
+ RemoteReceiver = 1,
+ Receiver = 2,
+ FlightController = 3,
+ ESC = 4,
+ Reserved = 5,
+ SRXLServo = 6,
+ SRXLServo_2 = 7,
+ VTX = 8,
+} Srxl2DeviceType;
+
+// ../../../src/main/rx/srxl2_types.h
+typedef enum {
+ FlightControllerDefault = 0x30,
+ FlightControllerMax = 0x3F,
+ Broadcast = 0xFF,
+} Srxl2DeviceId;
+
+// ../../../src/main/rx/srxl2_types.h
+typedef enum {
+ EnterBindMode = 0xEB,
+ RequestBindStatus = 0xB5,
+ BoundDataReport = 0xDB,
+ SetBindInfo = 0x5B,
+} Srxl2BindRequest;
+
+// ../../../src/main/rx/srxl2_types.h
+typedef enum {
+ NotBound = 0x0,
+ DSM2_1024_22ms = 0x01,
+ DSM2_1024_MC24 = 0x02,
+ DMS2_2048_11ms = 0x12,
+ DMSX_22ms = 0xA2,
+ DMSX_11ms = 0xB2,
+ Surface_DSM2_16_5ms = 0x63,
+ DSMR_11ms_22ms = 0xE2,
+ DSMR_5_5ms = 0xE4,
+} Srxl2BindType;
+
+// ../../../src/main/telemetry/crsf.c
+typedef enum {
+ CRSF_ACTIVE_ANTENNA1 = 0,
+ CRSF_ACTIVE_ANTENNA2 = 1
+} crsfActiveAntenna_e;
+
+// ../../../src/main/telemetry/crsf.c
+typedef enum {
+ CRSF_RF_MODE_4_HZ = 0,
+ CRSF_RF_MODE_50_HZ = 1,
+ CRSF_RF_MODE_150_HZ = 2
+} crsrRfMode_e;
+
+// ../../../src/main/telemetry/crsf.c
+typedef enum {
+ CRSF_RF_POWER_0_mW = 0,
+ CRSF_RF_POWER_10_mW = 1,
+ CRSF_RF_POWER_25_mW = 2,
+ CRSF_RF_POWER_100_mW = 3,
+ CRSF_RF_POWER_500_mW = 4,
+ CRSF_RF_POWER_1000_mW = 5,
+ CRSF_RF_POWER_2000_mW = 6,
+ CRSF_RF_POWER_250_mW = 7
+} crsrRfPower_e;
+
+// ../../../src/main/telemetry/crsf.c
+typedef enum {
+ CRSF_FRAME_START_INDEX = 0,
+ CRSF_FRAME_ATTITUDE_INDEX = CRSF_FRAME_START_INDEX,
+ CRSF_FRAME_BATTERY_SENSOR_INDEX,
+ CRSF_FRAME_FLIGHT_MODE_INDEX,
+ CRSF_FRAME_GPS_INDEX,
+ CRSF_FRAME_VARIO_SENSOR_INDEX,
+ CRSF_FRAME_BAROMETER_ALTITUDE_INDEX,
+ CRSF_SCHEDULE_COUNT_MAX
+} crsfFrameTypeIndex_e;
+
+// ../../../src/main/telemetry/telemetry.h
+typedef enum {
+ LTM_RATE_NORMAL,
+ LTM_RATE_MEDIUM,
+ LTM_RATE_SLOW
+} ltmUpdateRate_e;
+
+// ../../../src/main/telemetry/telemetry.h
+typedef enum {
+ MAVLINK_AUTOPILOT_GENERIC,
+ MAVLINK_AUTOPILOT_ARDUPILOT
+} mavlinkAutopilotType_e;
+
+// ../../../src/main/telemetry/telemetry.h
+typedef enum {
+ MAVLINK_RADIO_GENERIC,
+ MAVLINK_RADIO_ELRS,
+ MAVLINK_RADIO_SIK,
+} mavlinkRadio_e;
+
+// ../../../src/main/telemetry/telemetry.h
+typedef enum {
+ SMARTPORT_FUEL_UNIT_PERCENT,
+ SMARTPORT_FUEL_UNIT_MAH,
+ SMARTPORT_FUEL_UNIT_MWH
+} smartportFuelUnit_e;
+
+// ../../../src/main/telemetry/hott.c
+typedef enum {
+ HOTT_WAITING_FOR_REQUEST,
+ HOTT_RECEIVING_REQUEST,
+ HOTT_WAITING_FOR_TX_WINDOW,
+ HOTT_TRANSMITTING,
+ HOTT_ENDING_TRANSMISSION
+} hottState_e;
+
+// ../../../src/main/telemetry/hott.c
+typedef enum {
+ GPS_FIX_CHAR_NONE = '-',
+ GPS_FIX_CHAR_2D = '2',
+ GPS_FIX_CHAR_3D = '3',
+ GPS_FIX_CHAR_DGPS = 'D',
+} gpsFixChar_e;
+
+// ../../../src/main/telemetry/hott.h
+typedef enum {
+ HOTT_EAM_ALARM1_FLAG_NONE = 0,
+ HOTT_EAM_ALARM1_FLAG_MAH = (1 << 0),
+ HOTT_EAM_ALARM1_FLAG_BATTERY_1 = (1 << 1),
+ HOTT_EAM_ALARM1_FLAG_BATTERY_2 = (1 << 2),
+ HOTT_EAM_ALARM1_FLAG_TEMPERATURE_1 = (1 << 3),
+ HOTT_EAM_ALARM1_FLAG_TEMPERATURE_2 = (1 << 4),
+ HOTT_EAM_ALARM1_FLAG_ALTITUDE = (1 << 5),
+ HOTT_EAM_ALARM1_FLAG_CURRENT = (1 << 6),
+ HOTT_EAM_ALARM1_FLAG_MAIN_VOLTAGE = (1 << 7),
+} hottEamAlarm1Flag_e;
+
+// ../../../src/main/telemetry/hott.h
+typedef enum {
+ HOTT_EAM_ALARM2_FLAG_NONE = 0,
+ HOTT_EAM_ALARM2_FLAG_MS = (1 << 0),
+ HOTT_EAM_ALARM2_FLAG_M3S = (1 << 1),
+ HOTT_EAM_ALARM2_FLAG_ALTITUDE_DUPLICATE = (1 << 2),
+ HOTT_EAM_ALARM2_FLAG_MS_DUPLICATE = (1 << 3),
+ HOTT_EAM_ALARM2_FLAG_M3S_DUPLICATE = (1 << 4),
+ HOTT_EAM_ALARM2_FLAG_UNKNOWN_1 = (1 << 5),
+ HOTT_EAM_ALARM2_FLAG_UNKNOWN_2 = (1 << 6),
+ HOTT_EAM_ALARM2_FLAG_ON_SIGN_OR_TEXT_ACTIVE = (1 << 7),
+} hottEamAlarm2Flag_e;
+
+// ../../../src/main/telemetry/ltm.h
+typedef enum {
+ LTM_FRAME_START = 0,
+ LTM_AFRAME = LTM_FRAME_START,
+ LTM_SFRAME,
+#if defined(USE_GPS)
+ LTM_GFRAME,
+ LTM_OFRAME,
+ LTM_XFRAME,
+#endif
+ LTM_NFRAME,
+ LTM_FRAME_COUNT
+} ltm_frame_e;
+
+// ../../../src/main/telemetry/ltm.h
+typedef enum {
+ LTM_MODE_MANUAL = 0,
+ LTM_MODE_RATE,
+ LTM_MODE_ANGLE,
+ LTM_MODE_HORIZON,
+ LTM_MODE_ACRO,
+ LTM_MODE_STABALIZED1,
+ LTM_MODE_STABALIZED2,
+ LTM_MODE_STABILIZED3,
+ LTM_MODE_ALTHOLD,
+ LTM_MODE_GPSHOLD,
+ LTM_MODE_WAYPOINTS,
+ LTM_MODE_HEADHOLD,
+ LTM_MODE_CIRCLE,
+ LTM_MODE_RTH,
+ LTM_MODE_FOLLOWWME,
+ LTM_MODE_LAND,
+ LTM_MODE_FLYBYWIRE1,
+ LTM_MODE_FLYBYWIRE2,
+ LTM_MODE_CRUISE,
+ LTM_MODE_UNKNOWN,
+
+ LTM_MODE_LAUNCH,
+ LTM_MODE_AUTOTUNE
+} ltm_modes_e;
+
+// ../../../src/main/telemetry/ibus_shared.h
+typedef enum {
+ IBUS_MEAS_TYPE_INTERNAL_VOLTAGE = 0x00,
+ IBUS_MEAS_TYPE_TEMPERATURE = 0x01,
+ IBUS_MEAS_TYPE_RPM = 0x02,
+ IBUS_MEAS_TYPE_EXTERNAL_VOLTAGE = 0x03,
+ IBUS_MEAS_TYPE_HEADING = 0x04,
+ IBUS_MEAS_TYPE_CURRENT = 0x05,
+ IBUS_MEAS_TYPE_CLIMB = 0x06,
+ IBUS_MEAS_TYPE_ACC_Z = 0x07,
+ IBUS_MEAS_TYPE_ACC_Y = 0x08,
+ IBUS_MEAS_TYPE_ACC_X = 0x09,
+ IBUS_MEAS_TYPE_VSPEED = 0x0a,
+ IBUS_MEAS_TYPE_SPEED = 0x0b,
+ IBUS_MEAS_TYPE_DIST = 0x0c,
+ IBUS_MEAS_TYPE_ARMED = 0x0d,
+ IBUS_MEAS_TYPE_MODE = 0x0e,
+
+ IBUS_MEAS_TYPE_PRES = 0x41,
+
+
+ IBUS_MEAS_TYPE_SPE = 0x7e,
+ IBUS_MEAS_TYPE_COG = 0x80,
+ IBUS_MEAS_TYPE_GPS_STATUS = 0x81,
+ IBUS_MEAS_TYPE_GPS_LON = 0x82,
+ IBUS_MEAS_TYPE_GPS_LAT = 0x83,
+ IBUS_MEAS_TYPE_ALT = 0x84,
+ IBUS_MEAS_TYPE_S85 = 0x85,
+ IBUS_MEAS_TYPE_S86 = 0x86,
+ IBUS_MEAS_TYPE_S87 = 0x87,
+ IBUS_MEAS_TYPE_S88 = 0x88,
+ IBUS_MEAS_TYPE_S89 = 0x89,
+ IBUS_MEAS_TYPE_S8A = 0x8A,
+ IBUS_MEAS_TYPE_GALT = 0xf9,
+
+
+
+ IBUS_MEAS_TYPE_GPS = 0xfd
+
+} ibusSensorType_e;
+
+// ../../../src/main/telemetry/ibus_shared.h
+typedef enum {
+ IBUS_MEAS_TYPE1_INTV = 0x00,
+ IBUS_MEAS_TYPE1_TEM = 0x01,
+ IBUS_MEAS_TYPE1_MOT = 0x02,
+ IBUS_MEAS_TYPE1_EXTV = 0x03,
+ IBUS_MEAS_TYPE1_CELL = 0x04,
+ IBUS_MEAS_TYPE1_BAT_CURR = 0x05,
+ IBUS_MEAS_TYPE1_FUEL = 0x06,
+ IBUS_MEAS_TYPE1_RPM = 0x07,
+ IBUS_MEAS_TYPE1_CMP_HEAD = 0x08,
+ IBUS_MEAS_TYPE1_CLIMB_RATE = 0x09,
+ IBUS_MEAS_TYPE1_COG = 0x0a,
+ IBUS_MEAS_TYPE1_GPS_STATUS = 0x0b,
+ IBUS_MEAS_TYPE1_ACC_X = 0x0c,
+ IBUS_MEAS_TYPE1_ACC_Y = 0x0d,
+ IBUS_MEAS_TYPE1_ACC_Z = 0x0e,
+ IBUS_MEAS_TYPE1_ROLL = 0x0f,
+ IBUS_MEAS_TYPE1_PITCH = 0x10,
+ IBUS_MEAS_TYPE1_YAW = 0x11,
+ IBUS_MEAS_TYPE1_VERTICAL_SPEED = 0x12,
+ IBUS_MEAS_TYPE1_GROUND_SPEED = 0x13,
+ IBUS_MEAS_TYPE1_GPS_DIST = 0x14,
+ IBUS_MEAS_TYPE1_ARMED = 0x15,
+ IBUS_MEAS_TYPE1_FLIGHT_MODE = 0x16,
+ IBUS_MEAS_TYPE1_PRES = 0x41,
+
+
+ IBUS_MEAS_TYPE1_SPE = 0x7e,
+
+ IBUS_MEAS_TYPE1_GPS_LAT = 0x80,
+ IBUS_MEAS_TYPE1_GPS_LON = 0x81,
+ IBUS_MEAS_TYPE1_GPS_ALT = 0x82,
+ IBUS_MEAS_TYPE1_ALT = 0x83,
+ IBUS_MEAS_TYPE1_S84 = 0x84,
+ IBUS_MEAS_TYPE1_S85 = 0x85,
+ IBUS_MEAS_TYPE1_S86 = 0x86,
+ IBUS_MEAS_TYPE1_S87 = 0x87,
+ IBUS_MEAS_TYPE1_S88 = 0x88,
+ IBUS_MEAS_TYPE1_S89 = 0x89,
+ IBUS_MEAS_TYPE1_S8a = 0x8a
+
+
+
+
+} ibusSensorType1_e;
+
+// ../../../src/main/telemetry/ibus_shared.h
+typedef enum {
+ IBUS_MEAS_VALUE_NONE = 0x00,
+ IBUS_MEAS_VALUE_TEMPERATURE = 0x01,
+ IBUS_MEAS_VALUE_MOT = 0x02,
+ IBUS_MEAS_VALUE_EXTERNAL_VOLTAGE = 0x03,
+ IBUS_MEAS_VALUE_CELL = 0x04,
+ IBUS_MEAS_VALUE_CURRENT = 0x05,
+ IBUS_MEAS_VALUE_FUEL = 0x06,
+ IBUS_MEAS_VALUE_RPM = 0x07,
+ IBUS_MEAS_VALUE_HEADING = 0x08,
+ IBUS_MEAS_VALUE_CLIMB = 0x09,
+ IBUS_MEAS_VALUE_COG = 0x0a,
+ IBUS_MEAS_VALUE_GPS_STATUS = 0x0b,
+ IBUS_MEAS_VALUE_ACC_X = 0x0c,
+ IBUS_MEAS_VALUE_ACC_Y = 0x0d,
+ IBUS_MEAS_VALUE_ACC_Z = 0x0e,
+ IBUS_MEAS_VALUE_ROLL = 0x0f,
+ IBUS_MEAS_VALUE_PITCH = 0x10,
+ IBUS_MEAS_VALUE_YAW = 0x11,
+ IBUS_MEAS_VALUE_VSPEED = 0x12,
+ IBUS_MEAS_VALUE_SPEED = 0x13,
+ IBUS_MEAS_VALUE_DIST = 0x14,
+ IBUS_MEAS_VALUE_ARMED = 0x15,
+ IBUS_MEAS_VALUE_MODE = 0x16,
+ IBUS_MEAS_VALUE_PRES = 0x41,
+ IBUS_MEAS_VALUE_SPE = 0x7e,
+ IBUS_MEAS_VALUE_GPS_LAT = 0x80,
+ IBUS_MEAS_VALUE_GPS_LON = 0x81,
+ IBUS_MEAS_VALUE_GALT4 = 0x82,
+ IBUS_MEAS_VALUE_ALT4 = 0x83,
+ IBUS_MEAS_VALUE_GALT = 0x84,
+ IBUS_MEAS_VALUE_ALT = 0x85,
+ IBUS_MEAS_VALUE_STATUS = 0x87,
+ IBUS_MEAS_VALUE_GPS_LAT1 = 0x88,
+ IBUS_MEAS_VALUE_GPS_LON1 = 0x89,
+ IBUS_MEAS_VALUE_GPS_LAT2 = 0x90,
+ IBUS_MEAS_VALUE_GPS_LON2 = 0x91,
+ IBUS_MEAS_VALUE_GPS = 0xfd
+} ibusSensorValue_e;
+
+// ../../../src/main/telemetry/ibus_shared.c
+typedef enum {
+ IBUS_COMMAND_DISCOVER_SENSOR = 0x80,
+ IBUS_COMMAND_SENSOR_TYPE = 0x90,
+ IBUS_COMMAND_MEASUREMENT = 0xA0
+} ibusCommand_e;
+
+// ../../../src/main/telemetry/sim.c
+typedef enum {
+ SIM_MODULE_NOT_DETECTED = 0,
+ SIM_MODULE_NOT_REGISTERED,
+ SIM_MODULE_REGISTERED,
+} simModuleState_e;
+
+// ../../../src/main/telemetry/sim.c
+typedef enum {
+ SIM_STATE_INIT = 0,
+ SIM_STATE_INIT2,
+ SIM_STATE_INIT_ENTER_PIN,
+ SIM_STATE_SET_MODES,
+ SIM_STATE_SEND_SMS,
+ SIM_STATE_SEND_SMS_ENTER_MESSAGE
+} simTelemetryState_e;
+
+// ../../../src/main/telemetry/sim.c
+typedef enum {
+ SIM_AT_OK = 0,
+ SIM_AT_ERROR,
+ SIM_AT_WAITING_FOR_RESPONSE
+} simATCommandState_e;
+
+// ../../../src/main/telemetry/sim.c
+typedef enum {
+ SIM_READSTATE_RESPONSE = 0,
+ SIM_READSTATE_SMS,
+ SIM_READSTATE_SKIP
+} simReadState_e;
+
+// ../../../src/main/telemetry/sim.c
+typedef enum {
+ SIM_TX_NO = 0,
+ SIM_TX_FS,
+ SIM_TX
+} simTransmissionState_e;
+
+// ../../../src/main/telemetry/sim.c
+typedef enum {
+ ACC_EVENT_NONE = 0,
+ ACC_EVENT_HIGH,
+ ACC_EVENT_LOW,
+ ACC_EVENT_NEG_X
+} accEvent_t;
+
+// ../../../src/main/telemetry/mavlink.c
+typedef enum APM_PLANE_MODE
+{
+ PLANE_MODE_MANUAL=0,
+ PLANE_MODE_CIRCLE=1,
+ PLANE_MODE_STABILIZE=2,
+ PLANE_MODE_TRAINING=3,
+ PLANE_MODE_ACRO=4,
+ PLANE_MODE_FLY_BY_WIRE_A=5,
+ PLANE_MODE_FLY_BY_WIRE_B=6,
+ PLANE_MODE_CRUISE=7,
+ PLANE_MODE_AUTOTUNE=8,
+ PLANE_MODE_AUTO=10,
+ PLANE_MODE_RTL=11,
+ PLANE_MODE_LOITER=12,
+ PLANE_MODE_TAKEOFF=13,
+ PLANE_MODE_AVOID_ADSB=14,
+ PLANE_MODE_GUIDED=15,
+ PLANE_MODE_INITIALIZING=16,
+ PLANE_MODE_QSTABILIZE=17,
+ PLANE_MODE_QHOVER=18,
+ PLANE_MODE_QLOITER=19,
+ PLANE_MODE_QLAND=20,
+ PLANE_MODE_QRTL=21,
+ PLANE_MODE_QAUTOTUNE=22,
+ PLANE_MODE_ENUM_END=23,
+} APM_PLANE_MODE;
+
+// ../../../src/main/telemetry/mavlink.c
+typedef enum APM_COPTER_MODE
+{
+ COPTER_MODE_STABILIZE=0,
+ COPTER_MODE_ACRO=1,
+ COPTER_MODE_ALT_HOLD=2,
+ COPTER_MODE_AUTO=3,
+ COPTER_MODE_GUIDED=4,
+ COPTER_MODE_LOITER=5,
+ COPTER_MODE_RTL=6,
+ COPTER_MODE_CIRCLE=7,
+ COPTER_MODE_LAND=9,
+ COPTER_MODE_DRIFT=11,
+ COPTER_MODE_SPORT=13,
+ COPTER_MODE_FLIP=14,
+ COPTER_MODE_AUTOTUNE=15,
+ COPTER_MODE_POSHOLD=16,
+ COPTER_MODE_BRAKE=17,
+ COPTER_MODE_THROW=18,
+ COPTER_MODE_AVOID_ADSB=19,
+ COPTER_MODE_GUIDED_NOGPS=20,
+ COPTER_MODE_SMART_RTL=21,
+ COPTER_MODE_ENUM_END=22,
+} APM_COPTER_MODE;
+
+// ../../../src/main/telemetry/mavlink.c
+enum APM_PLANE_MODE
+{
+ PLANE_MODE_MANUAL=0,
+ PLANE_MODE_CIRCLE=1,
+ PLANE_MODE_STABILIZE=2,
+ PLANE_MODE_TRAINING=3,
+ PLANE_MODE_ACRO=4,
+ PLANE_MODE_FLY_BY_WIRE_A=5,
+ PLANE_MODE_FLY_BY_WIRE_B=6,
+ PLANE_MODE_CRUISE=7,
+ PLANE_MODE_AUTOTUNE=8,
+ PLANE_MODE_AUTO=10,
+ PLANE_MODE_RTL=11,
+ PLANE_MODE_LOITER=12,
+ PLANE_MODE_TAKEOFF=13,
+ PLANE_MODE_AVOID_ADSB=14,
+ PLANE_MODE_GUIDED=15,
+ PLANE_MODE_INITIALIZING=16,
+ PLANE_MODE_QSTABILIZE=17,
+ PLANE_MODE_QHOVER=18,
+ PLANE_MODE_QLOITER=19,
+ PLANE_MODE_QLAND=20,
+ PLANE_MODE_QRTL=21,
+ PLANE_MODE_QAUTOTUNE=22,
+ PLANE_MODE_ENUM_END=23,
+} APM_PLANE_MODE;
+typedef enum APM_PLANE_MODE APM_PLANE_MODE;
+
+// ../../../src/main/telemetry/mavlink.c
+enum APM_COPTER_MODE
+{
+ COPTER_MODE_STABILIZE=0,
+ COPTER_MODE_ACRO=1,
+ COPTER_MODE_ALT_HOLD=2,
+ COPTER_MODE_AUTO=3,
+ COPTER_MODE_GUIDED=4,
+ COPTER_MODE_LOITER=5,
+ COPTER_MODE_RTL=6,
+ COPTER_MODE_CIRCLE=7,
+ COPTER_MODE_LAND=9,
+ COPTER_MODE_DRIFT=11,
+ COPTER_MODE_SPORT=13,
+ COPTER_MODE_FLIP=14,
+ COPTER_MODE_AUTOTUNE=15,
+ COPTER_MODE_POSHOLD=16,
+ COPTER_MODE_BRAKE=17,
+ COPTER_MODE_THROW=18,
+ COPTER_MODE_AVOID_ADSB=19,
+ COPTER_MODE_GUIDED_NOGPS=20,
+ COPTER_MODE_SMART_RTL=21,
+ COPTER_MODE_ENUM_END=22,
+} APM_COPTER_MODE;
+typedef enum APM_COPTER_MODE APM_COPTER_MODE;
+
+// ../../../src/main/telemetry/sim.h
+typedef enum {
+ SIM_TX_FLAG = (1 << 0),
+ SIM_TX_FLAG_FAILSAFE = (1 << 1),
+ SIM_TX_FLAG_GPS = (1 << 2),
+ SIM_TX_FLAG_ACC = (1 << 3),
+ SIM_TX_FLAG_LOW_ALT = (1 << 4),
+ SIM_TX_FLAG_RESPONSE = (1 << 5)
+} simTxFlags_e;
+
+// ../../../src/main/telemetry/jetiexbus.c
+enum exTelHeader_e {
+ EXTEL_HEADER_SYNC = 0,
+ EXTEL_HEADER_TYPE_LEN,
+ EXTEL_HEADER_USN_LB,
+ EXTEL_HEADER_USN_HB,
+ EXTEL_HEADER_LSN_LB,
+ EXTEL_HEADER_LSN_HB,
+ EXTEL_HEADER_RES,
+ EXTEL_HEADER_ID,
+ EXTEL_HEADER_DATA
+};
+typedef enum exTelHeader_e exTelHeader_e;
+
+// ../../../src/main/telemetry/jetiexbus.c
+enum exDataType_e {
+ EX_TYPE_6b = 0,
+ EX_TYPE_14b = 1,
+ EX_TYPE_22b = 4,
+ EX_TYPE_DT = 5,
+ EX_TYPE_30b = 8,
+ EX_TYPE_GPS = 9,
+ EX_TYPE_DES = 255
+};
+typedef enum exDataType_e exDataType_e;
+
+// ../../../src/main/telemetry/jetiexbus.c
+enum exSensors_e {
+ EX_VOLTAGE = 1,
+ EX_CURRENT,
+ EX_ALTITUDE,
+ EX_CAPACITY,
+ EX_POWER,
+ EX_ROLL_ANGLE,
+ EX_PITCH_ANGLE,
+ EX_HEADING,
+ EX_VARIO,
+ EX_GPS_SATS,
+ EX_GPS_LONG,
+ EX_GPS_LAT,
+ EX_GPS_SPEED,
+ EX_GPS_DISTANCE_TO_HOME,
+ EX_GPS_DIRECTION_TO_HOME,
+ EX_GPS_HEADING = 17,
+ EX_GPS_ALTITUDE,
+ EX_GFORCE_X,
+ EX_GFORCE_Y,
+ EX_GFORCE_Z,
+ EX_RPM,
+ EX_TRIP_DISTANCE,
+ EX_DEBUG0,
+ EX_DEBUG1,
+ EX_DEBUG2,
+ EX_DEBUG3,
+ EX_DEBUG4,
+ EX_DEBUG5,
+ EX_DEBUG6,
+ EX_DEBUG7
+};
+typedef enum exSensors_e exSensors_e;
+
+// ../../../src/main/telemetry/ghst.c
+typedef enum {
+ GHST_FRAME_START_INDEX = 0,
+ GHST_FRAME_PACK_INDEX = GHST_FRAME_START_INDEX,
+ GHST_FRAME_GPS_PRIMARY_INDEX,
+ GHST_FRAME_GPS_SECONDARY_INDEX,
+ GHST_SCHEDULE_COUNT_MAX
+} ghstFrameTypeIndex_e;
+
+// ../../../src/main/io/gps.h
+typedef enum {
+ GPS_UBLOX = 0,
+ GPS_MSP,
+ GPS_FAKE,
+ GPS_DRONECAN,
+ GPS_PROVIDER_COUNT
+} gpsProvider_e;
+
+// ../../../src/main/io/gps.h
+typedef enum {
+ SBAS_AUTO = 0,
+ SBAS_EGNOS,
+ SBAS_WAAS,
+ SBAS_MSAS,
+ SBAS_GAGAN,
+ SBAS_SPAN,
+ SBAS_NONE
+} sbasMode_e;
+
+// ../../../src/main/io/gps.h
+typedef enum {
+ GPS_BAUDRATE_115200 = 0,
+ GPS_BAUDRATE_57600,
+ GPS_BAUDRATE_38400,
+ GPS_BAUDRATE_19200,
+ GPS_BAUDRATE_9600,
+ GPS_BAUDRATE_230400,
+ GPS_BAUDRATE_460800,
+ GPS_BAUDRATE_921600,
+ GPS_BAUDRATE_COUNT
+} gpsBaudRate_e;
+
+// ../../../src/main/io/gps.h
+typedef enum {
+ GPS_AUTOCONFIG_OFF = 0,
+ GPS_AUTOCONFIG_ON,
+} gpsAutoConfig_e;
+
+// ../../../src/main/io/gps.h
+typedef enum {
+ GPS_AUTOBAUD_OFF = 0,
+ GPS_AUTOBAUD_ON
+} gpsAutoBaud_e;
+
+// ../../../src/main/io/gps.h
+typedef enum {
+ GPS_DYNMODEL_PEDESTRIAN = 0,
+ GPS_DYNMODEL_AUTOMOTIVE,
+ GPS_DYNMODEL_AIR_1G,
+ GPS_DYNMODEL_AIR_2G,
+ GPS_DYNMODEL_AIR_4G,
+ GPS_DYNMODEL_SEA,
+ GPS_DYNMODEL_MOWER,
+} gpsDynModel_e;
+
+// ../../../src/main/io/gps.h
+typedef enum {
+ GPS_NO_FIX = 0,
+ GPS_FIX_2D,
+ GPS_FIX_3D
+} gpsFixType_e;
+
+// ../../../src/main/io/displayport_msp.h
+typedef enum {
+ MSP_DP_HEARTBEAT = 0,
+ MSP_DP_RELEASE = 1,
+ MSP_DP_CLEAR_SCREEN = 2,
+ MSP_DP_WRITE_STRING = 3,
+ MSP_DP_DRAW_SCREEN = 4,
+ MSP_DP_OPTIONS = 5,
+ MSP_DP_SYS = 6,
+ MSP_DP_COUNT,
+} displayportMspCommand_e;
+
+// ../../../src/main/io/gimbal_serial.h
+typedef enum {
+ WAITING_HDR1,
+ WAITING_HDR2,
+ WAITING_PAYLOAD,
+ WAITING_CRCH,
+ WAITING_CRCL,
+} gimbalHeadtrackerState_e;
+
+// ../../../src/main/io/osd_dji_hd.c
+typedef enum {
+ DJI_OSD_CN_MESSAGES,
+ DJI_OSD_CN_THROTTLE,
+ DJI_OSD_CN_THROTTLE_AUTO_THR,
+ DJI_OSD_CN_AIR_SPEED,
+ DJI_OSD_CN_EFFICIENCY,
+ DJI_OSD_CN_DISTANCE,
+ DJI_OSD_CN_ADJUSTEMNTS,
+ DJI_OSD_CN_MAX_ELEMENTS
+} DjiCraftNameElements_t;
+
+// ../../../src/main/io/vtx.h
+typedef enum {
+ VTX_LOW_POWER_DISARM_OFF = 0,
+ VTX_LOW_POWER_DISARM_ALWAYS = 1,
+ VTX_LOW_POWER_DISARM_UNTIL_FIRST_ARM = 2,
+} vtxLowerPowerDisarm_e;
+
+// ../../../src/main/io/vtx_tramp.c
+typedef enum {
+ VTX_STATE_RESET = 0,
+ VTX_STATE_OFFILE = 1,
+ VTX_STATE_DETECTING = 2,
+ VTX_STATE_IDLE = 3,
+ VTX_STATE_QUERY_DELAY = 4,
+ VTX_STATE_QUERY_STATUS = 5,
+ VTX_STATE_WAIT_STATUS = 6,
+} vtxProtoState_e;
+
+// ../../../src/main/io/vtx_tramp.c
+typedef enum {
+ VTX_RESPONSE_TYPE_NONE,
+ VTX_RESPONSE_TYPE_CAPABILITIES,
+ VTX_RESPONSE_TYPE_STATUS,
+} vtxProtoResponseType_e;
+
+// ../../../src/main/io/serial.h
+typedef enum {
+ PORTSHARING_UNUSED = 0,
+ PORTSHARING_NOT_SHARED,
+ PORTSHARING_SHARED
+} portSharing_e;
+
+// ../../../src/main/io/serial.h
+typedef enum {
+ FUNCTION_NONE = 0,
+ FUNCTION_MSP = (1 << 0),
+ FUNCTION_GPS = (1 << 1),
+ FUNCTION_UNUSED_3 = (1 << 2),
+ FUNCTION_TELEMETRY_HOTT = (1 << 3),
+ FUNCTION_TELEMETRY_LTM = (1 << 4),
+ FUNCTION_TELEMETRY_SMARTPORT = (1 << 5),
+ FUNCTION_RX_SERIAL = (1 << 6),
+ FUNCTION_BLACKBOX = (1 << 7),
+ FUNCTION_TELEMETRY_MAVLINK = (1 << 8),
+ FUNCTION_TELEMETRY_IBUS = (1 << 9),
+ FUNCTION_RCDEVICE = (1 << 10),
+ FUNCTION_VTX_SMARTAUDIO = (1 << 11),
+ FUNCTION_VTX_TRAMP = (1 << 12),
+ FUNCTION_UNUSED_1 = (1 << 13),
+ FUNCTION_OPTICAL_FLOW = (1 << 14),
+ FUNCTION_LOG = (1 << 15),
+ FUNCTION_RANGEFINDER = (1 << 16),
+ FUNCTION_VTX_FFPV = (1 << 17),
+ FUNCTION_ESCSERIAL = (1 << 18),
+ FUNCTION_TELEMETRY_SIM = (1 << 19),
+ FUNCTION_FRSKY_OSD = (1 << 20),
+ FUNCTION_DJI_HD_OSD = (1 << 21),
+ FUNCTION_SERVO_SERIAL = (1 << 22),
+ FUNCTION_TELEMETRY_SMARTPORT_MASTER = (1 << 23),
+ FUNCTION_UNUSED_2 = (1 << 24),
+ FUNCTION_MSP_OSD = (1 << 25),
+ FUNCTION_GIMBAL = (1 << 26),
+ FUNCTION_GIMBAL_HEADTRACKER = (1 << 27),
+} serialPortFunction_e;
+
+// ../../../src/main/io/serial.h
+typedef enum {
+ BAUD_AUTO = 0,
+ BAUD_1200,
+ BAUD_2400,
+ BAUD_4800,
+ BAUD_9600,
+ BAUD_19200,
+ BAUD_38400,
+ BAUD_57600,
+ BAUD_115200,
+ BAUD_230400,
+ BAUD_250000,
+ BAUD_460800,
+ BAUD_921600,
+ BAUD_1000000,
+ BAUD_1500000,
+ BAUD_2000000,
+ BAUD_2470000,
+
+ BAUD_MIN = BAUD_AUTO,
+ BAUD_MAX = BAUD_2470000,
+} baudRate_e;
+
+// ../../../src/main/io/serial.h
+typedef enum {
+ SERIAL_PORT_NONE = -1,
+ SERIAL_PORT_USART1 = 0,
+ SERIAL_PORT_USART2,
+ SERIAL_PORT_USART3,
+ SERIAL_PORT_USART4,
+ SERIAL_PORT_USART5,
+ SERIAL_PORT_USART6,
+ SERIAL_PORT_USART7,
+ SERIAL_PORT_USART8,
+ SERIAL_PORT_USB_VCP = 20,
+ SERIAL_PORT_SOFTSERIAL1 = 30,
+ SERIAL_PORT_SOFTSERIAL2,
+ SERIAL_PORT_IDENTIFIER_MAX = SERIAL_PORT_SOFTSERIAL2
+} serialPortIdentifier_e;
+
+// ../../../src/main/io/rcdevice.h
+typedef enum {
+ RCDEVICE_PROTOCOL_FEATURE_SIMULATE_POWER_BUTTON = (1 << 0),
+ RCDEVICE_PROTOCOL_FEATURE_SIMULATE_WIFI_BUTTON = (1 << 1),
+ RCDEVICE_PROTOCOL_FEATURE_CHANGE_MODE = (1 << 2),
+ RCDEVICE_PROTOCOL_FEATURE_SIMULATE_5_KEY_OSD_CABLE = (1 << 3),
+ RCDEVICE_PROTOCOL_FEATURE_START_RECORDING = (1 << 6),
+ RCDEVICE_PROTOCOL_FEATURE_STOP_RECORDING = (1 << 7),
+ RCDEVICE_PROTOCOL_FEATURE_CMS_MENU = (1 << 8),
+} rcdevice_features_e;
+
+// ../../../src/main/io/rcdevice.h
+typedef enum {
+ RCDEVICE_PROTOCOL_CAM_CTRL_SIMULATE_WIFI_BTN = 0x00,
+ RCDEVICE_PROTOCOL_CAM_CTRL_SIMULATE_POWER_BTN = 0x01,
+ RCDEVICE_PROTOCOL_CAM_CTRL_CHANGE_MODE = 0x02,
+ RCDEVICE_PROTOCOL_CAM_CTRL_START_RECORDING = 0x03,
+ RCDEVICE_PROTOCOL_CAM_CTRL_STOP_RECORDING = 0x04,
+ RCDEVICE_PROTOCOL_CAM_CTRL_UNKNOWN_CAMERA_OPERATION = 0xFF
+} rcdevice_camera_control_opeation_e;
+
+// ../../../src/main/io/rcdevice.h
+typedef enum {
+ RCDEVICE_PROTOCOL_5KEY_SIMULATION_NONE = 0x00,
+ RCDEVICE_PROTOCOL_5KEY_SIMULATION_SET = 0x01,
+ RCDEVICE_PROTOCOL_5KEY_SIMULATION_LEFT = 0x02,
+ RCDEVICE_PROTOCOL_5KEY_SIMULATION_RIGHT = 0x03,
+ RCDEVICE_PROTOCOL_5KEY_SIMULATION_UP = 0x04,
+ RCDEVICE_PROTOCOL_5KEY_SIMULATION_DOWN = 0x05
+} rcdevice_5key_simulation_operation_e;
+
+// ../../../src/main/io/rcdevice.h
+typedef enum {
+ RCDEVICE_PROTOCOL_5KEY_CONNECTION_OPEN = 0x01,
+ RCDEVICE_PROTOCOL_5KEY_CONNECTION_CLOSE = 0x02
+} RCDEVICE_5key_connection_event_e;
+
+// ../../../src/main/io/rcdevice.h
+typedef enum {
+ RCDEVICE_CAM_KEY_NONE,
+ RCDEVICE_CAM_KEY_ENTER,
+ RCDEVICE_CAM_KEY_LEFT,
+ RCDEVICE_CAM_KEY_UP,
+ RCDEVICE_CAM_KEY_RIGHT,
+ RCDEVICE_CAM_KEY_DOWN,
+ RCDEVICE_CAM_KEY_CONNECTION_CLOSE,
+ RCDEVICE_CAM_KEY_CONNECTION_OPEN,
+ RCDEVICE_CAM_KEY_RELEASE,
+} rcdeviceCamSimulationKeyEvent_e;
+
+// ../../../src/main/io/rcdevice.h
+typedef enum {
+ RCDEVICE_PROTOCOL_RCSPLIT_VERSION = 0x00,
+
+
+ RCDEVICE_PROTOCOL_VERSION_1_0 = 0x01,
+ RCDEVICE_PROTOCOL_UNKNOWN
+} rcdevice_protocol_version_e;
+
+// ../../../src/main/io/rcdevice.h
+typedef enum {
+ RCDEVICE_RESP_SUCCESS = 0,
+ RCDEVICE_RESP_INCORRECT_CRC = 1,
+ RCDEVICE_RESP_TIMEOUT = 2
+} rcdeviceResponseStatus_e;
+
+// ../../../src/main/io/vtx.c
+typedef enum {
+ VTX_PARAM_POWER = 0,
+ VTX_PARAM_BANDCHAN,
+ VTX_PARAM_PITMODE,
+ VTX_PARAM_COUNT
+} vtxScheduleParams_e;
+
+// ../../../src/main/io/beeper.h
+typedef enum {
+
+ BEEPER_SILENCE = 0,
+
+ BEEPER_RUNTIME_CALIBRATION_DONE,
+ BEEPER_HARDWARE_FAILURE,
+ BEEPER_RX_LOST,
+ BEEPER_RX_LOST_LANDING,
+ BEEPER_DISARMING,
+ BEEPER_ARMING,
+ BEEPER_ARMING_GPS_FIX,
+ BEEPER_BAT_CRIT_LOW,
+ BEEPER_BAT_LOW,
+ BEEPER_GPS_STATUS,
+ BEEPER_RX_SET,
+ BEEPER_ACTION_SUCCESS,
+ BEEPER_ACTION_FAIL,
+ BEEPER_READY_BEEP,
+ BEEPER_MULTI_BEEPS,
+ BEEPER_DISARM_REPEAT,
+ BEEPER_ARMED,
+ BEEPER_SYSTEM_INIT,
+ BEEPER_USB,
+ BEEPER_LAUNCH_MODE_ENABLED,
+ BEEPER_LAUNCH_MODE_LOW_THROTTLE,
+ BEEPER_LAUNCH_MODE_IDLE_START,
+ BEEPER_CAM_CONNECTION_OPEN,
+ BEEPER_CAM_CONNECTION_CLOSE,
+
+ BEEPER_ALL,
+ BEEPER_PREFERENCE,
+
+} beeperMode_e;
+
+// ../../../src/main/io/frsky_osd.c
+typedef enum
+{
+ OSD_CMD_RESPONSE_ERROR = 0,
+
+ OSD_CMD_INFO = 1,
+ OSD_CMD_READ_FONT = 2,
+ OSD_CMD_WRITE_FONT = 3,
+ OSD_CMD_GET_CAMERA = 4,
+ OSD_CMD_SET_CAMERA = 5,
+ OSD_CMD_GET_ACTIVE_CAMERA = 6,
+ OSD_CMD_GET_OSD_ENABLED = 7,
+ OSD_CMD_SET_OSD_ENABLED = 8,
+
+ OSD_CMD_TRANSACTION_BEGIN = 16,
+ OSD_CMD_TRANSACTION_COMMIT = 17,
+ OSD_CMD_TRANSACTION_BEGIN_PROFILED = 18,
+ OSD_CMD_TRANSACTION_BEGIN_RESET_DRAWING = 19,
+
+ OSD_CMD_DRAWING_SET_STROKE_COLOR = 22,
+ OSD_CMD_DRAWING_SET_FILL_COLOR = 23,
+ OSD_CMD_DRAWING_SET_STROKE_AND_FILL_COLOR = 24,
+ OSD_CMD_DRAWING_SET_COLOR_INVERSION = 25,
+ OSD_CMD_DRAWING_SET_PIXEL = 26,
+ OSD_CMD_DRAWING_SET_PIXEL_TO_STROKE_COLOR = 27,
+ OSD_CMD_DRAWING_SET_PIXEL_TO_FILL_COLOR = 28,
+ OSD_CMD_DRAWING_SET_STROKE_WIDTH = 29,
+ OSD_CMD_DRAWING_SET_LINE_OUTLINE_TYPE = 30,
+ OSD_CMD_DRAWING_SET_LINE_OUTLINE_COLOR = 31,
+
+ OSD_CMD_DRAWING_CLIP_TO_RECT = 40,
+ OSD_CMD_DRAWING_CLEAR_SCREEN = 41,
+ OSD_CMD_DRAWING_CLEAR_RECT = 42,
+ OSD_CMD_DRAWING_RESET = 43,
+ OSD_CMD_DRAWING_DRAW_BITMAP = 44,
+ OSD_CMD_DRAWING_DRAW_BITMAP_MASK = 45,
+ OSD_CMD_DRAWING_DRAW_CHAR = 46,
+ OSD_CMD_DRAWING_DRAW_CHAR_MASK = 47,
+ OSD_CMD_DRAWING_DRAW_STRING = 48,
+ OSD_CMD_DRAWING_DRAW_STRING_MASK = 49,
+ OSD_CMD_DRAWING_MOVE_TO_POINT = 50,
+ OSD_CMD_DRAWING_STROKE_LINE_TO_POINT = 51,
+ OSD_CMD_DRAWING_STROKE_TRIANGLE = 52,
+ OSD_CMD_DRAWING_FILL_TRIANGLE = 53,
+ OSD_CMD_DRAWING_FILL_STROKE_TRIANGLE = 54,
+ OSD_CMD_DRAWING_STROKE_RECT = 55,
+ OSD_CMD_DRAWING_FILL_RECT = 56,
+ OSD_CMD_DRAWING_FILL_STROKE_RECT = 57,
+ OSD_CMD_DRAWING_STROKE_ELLIPSE_IN_RECT = 58,
+ OSD_CMD_DRAWING_FILL_ELLIPSE_IN_RECT = 59,
+ OSD_CMD_DRAWING_FILL_STROKE_ELLIPSE_IN_RECT = 60,
+
+ OSD_CMD_CTM_RESET = 80,
+ OSD_CMD_CTM_SET = 81,
+ OSD_CMD_CTM_TRANSLATE = 82,
+ OSD_CMD_CTM_SCALE = 83,
+ OSD_CMD_CTM_ROTATE = 84,
+ OSD_CMD_CTM_ROTATE_ABOUT = 85,
+ OSD_CMD_CTM_SHEAR = 86,
+ OSD_CMD_CTM_SHEAR_ABOUT = 87,
+ OSD_CMD_CTM_MULTIPLY = 88,
+
+ OSD_CMD_CONTEXT_PUSH = 100,
+ OSD_CMD_CONTEXT_POP = 101,
+
+
+ OSD_CMD_DRAW_GRID_CHR = 110,
+ OSD_CMD_DRAW_GRID_STR = 111,
+ OSD_CMD_DRAW_GRID_CHR_2 = 112,
+ OSD_CMD_DRAW_GRID_STR_2 = 113,
+
+ OSD_CMD_WIDGET_SET_CONFIG = 115,
+ OSD_CMD_WIDGET_DRAW = 116,
+ OSD_CMD_WIDGET_ERASE = 117,
+
+ OSD_CMD_SET_DATA_RATE = 122,
+} osdCommand_e;
+
+// ../../../src/main/io/frsky_osd.c
+typedef enum {
+ RECV_STATE_NONE,
+ RECV_STATE_SYNC,
+ RECV_STATE_LENGTH,
+ RECV_STATE_DATA,
+ RECV_STATE_CHECKSUM,
+ RECV_STATE_DONE,
+} frskyOSDRecvState_e;
+
+// ../../../src/main/io/gps_ublox.h
+typedef enum {
+ UBLOX_SIG_HEALTH_UNKNOWN = 0,
+ UBLOX_SIG_HEALTH_HEALTHY = 1,
+ UBLOX_SIG_HEALTH_UNHEALTHY = 2
+} ublox_nav_sig_health_e;
+
+// ../../../src/main/io/gps_ublox.h
+typedef enum {
+ UBLOX_SIG_QUALITY_NOSIGNAL = 0,
+ UBLOX_SIG_QUALITY_SEARCHING = 1,
+ UBLOX_SIG_QUALITY_ACQUIRED = 2,
+ UBLOX_SIG_QUALITY_UNUSABLE = 3,
+ UBLOX_SIG_QUALITY_CODE_LOCK_TIME_SYNC = 4,
+ UBLOX_SIG_QUALITY_CODE_CARRIER_LOCK_TIME_SYNC = 5,
+ UBLOX_SIG_QUALITY_CODE_CARRIER_LOCK_TIME_SYNC2 = 6,
+ UBLOX_SIG_QUALITY_CODE_CARRIER_LOCK_TIME_SYNC3 = 7,
+} ublox_nav_sig_quality;
+
+// ../../../src/main/io/gps_ublox.h
+typedef enum {
+ UBX_ACK_WAITING = 0,
+ UBX_ACK_GOT_ACK = 1,
+ UBX_ACK_GOT_NAK = 2
+} ubx_ack_state_t;
+
+// ../../../src/main/io/gps_ublox.h
+typedef enum {
+ PREAMBLE1 = 0xB5,
+ PREAMBLE2 = 0x62,
+ CLASS_NAV = 0x01,
+ CLASS_ACK = 0x05,
+ CLASS_CFG = 0x06,
+ CLASS_MON = 0x0A,
+ MSG_CLASS_UBX = 0x01,
+ MSG_CLASS_NMEA = 0xF0,
+ MSG_VER = 0x04,
+ MSG_ACK_NACK = 0x00,
+ MSG_ACK_ACK = 0x01,
+ MSG_NMEA_GGA = 0x0,
+ MSG_NMEA_GLL = 0x1,
+ MSG_NMEA_GSA = 0x2,
+ MSG_NMEA_GSV = 0x3,
+ MSG_NMEA_RMC = 0x4,
+ MSG_NMEA_VGS = 0x5,
+ MSG_POSLLH = 0x2,
+ MSG_STATUS = 0x3,
+ MSG_SOL = 0x6,
+ MSG_PVT = 0x7,
+ MSG_VELNED = 0x12,
+ MSG_TIMEUTC = 0x21,
+ MSG_SVINFO = 0x30,
+ MSG_NAV_SAT = 0x35,
+ MSG_CFG_PRT = 0x00,
+ MSG_CFG_RATE = 0x08,
+ MSG_CFG_SET_RATE = 0x01,
+ MSG_CFG_NAV_SETTINGS = 0x24,
+ MSG_CFG_SBAS = 0x16,
+ MSG_CFG_GNSS = 0x3e,
+ MSG_MON_GNSS = 0x28,
+ MSG_NAV_SIG = 0x43
+} ubx_protocol_bytes_t;
+
+// ../../../src/main/io/gps_ublox.h
+typedef enum {
+ FIX_NONE = 0,
+ FIX_DEAD_RECKONING = 1,
+ FIX_2D = 2,
+ FIX_3D = 3,
+ FIX_GPS_DEAD_RECKONING = 4,
+ FIX_TIME = 5
+} ubs_nav_fix_type_t;
+
+// ../../../src/main/io/gps_ublox.h
+typedef enum {
+ NAV_STATUS_FIX_VALID = 1
+} ubx_nav_status_bits_t;
+
+// ../../../src/main/io/dashboard.h
+typedef enum {
+ PAGE_WELCOME,
+ PAGE_ARMED,
+ PAGE_STATUS
+} pageId_e;
+
+// ../../../src/main/io/osd_common.h
+typedef enum {
+ OSD_SPEED_SOURCE_GROUND = 0,
+ OSD_SPEED_SOURCE_3D = 1,
+ OSD_SPEED_SOURCE_AIR = 2
+} osdSpeedSource_e;
+
+// ../../../src/main/io/osd_common.h
+typedef enum {
+ OSD_DRAW_POINT_TYPE_GRID,
+ OSD_DRAW_POINT_TYPE_PIXEL,
+} osdDrawPointType_e;
+
+// ../../../src/main/io/osd_dji_hd.h
+enum djiOsdTempSource_e {
+ DJI_OSD_TEMP_ESC = 0,
+ DJI_OSD_TEMP_CORE = 1,
+ DJI_OSD_TEMP_BARO = 2
+};
+typedef enum djiOsdTempSource_e djiOsdTempSource_e;
+
+// ../../../src/main/io/osd_dji_hd.h
+enum djiRssiSource_e {
+ DJI_RSSI = 0,
+ DJI_CRSF_LQ = 1
+};
+typedef enum djiRssiSource_e djiRssiSource_e;
+
+// ../../../src/main/io/osd_dji_hd.h
+enum djiOsdProtoWorkarounds_e {
+ DJI_OSD_USE_NON_STANDARD_MSP_ESC_SENSOR_DATA = 1 << 0,
+};
+typedef enum djiOsdProtoWorkarounds_e djiOsdProtoWorkarounds_e;
+
+// ../../../src/main/io/ledstrip.h
+typedef enum {
+ COLOR_BLACK = 0,
+ COLOR_WHITE,
+ COLOR_RED,
+ COLOR_ORANGE,
+ COLOR_YELLOW,
+ COLOR_LIME_GREEN,
+ COLOR_GREEN,
+ COLOR_MINT_GREEN,
+ COLOR_CYAN,
+ COLOR_LIGHT_BLUE,
+ COLOR_BLUE,
+ COLOR_DARK_VIOLET,
+ COLOR_MAGENTA,
+ COLOR_DEEP_PINK,
+} colorId_e;
+
+// ../../../src/main/io/ledstrip.h
+typedef enum {
+ LED_MODE_ORIENTATION = 0,
+ LED_MODE_HEADFREE,
+ LED_MODE_HORIZON,
+ LED_MODE_ANGLE,
+ LED_MODE_MAG,
+ LED_MODE_BARO,
+ LED_MODE_LOITER,
+ LED_SPECIAL
+} ledModeIndex_e;
+
+// ../../../src/main/io/ledstrip.h
+typedef enum {
+ LED_SCOLOR_DISARMED = 0,
+ LED_SCOLOR_ARMED,
+ LED_SCOLOR_ANIMATION,
+ LED_SCOLOR_BACKGROUND,
+ LED_SCOLOR_BLINKBACKGROUND,
+ LED_SCOLOR_GPSNOSATS,
+ LED_SCOLOR_GPSNOLOCK,
+ LED_SCOLOR_GPSLOCKED,
+ LED_SCOLOR_STROBE
+} ledSpecialColorIds_e;
+
+// ../../../src/main/io/ledstrip.h
+typedef enum {
+ LED_DIRECTION_NORTH = 0,
+ LED_DIRECTION_EAST,
+ LED_DIRECTION_SOUTH,
+ LED_DIRECTION_WEST,
+ LED_DIRECTION_UP,
+ LED_DIRECTION_DOWN
+} ledDirectionId_e;
+
+// ../../../src/main/io/ledstrip.h
+typedef enum {
+ LED_FUNCTION_COLOR,
+ LED_FUNCTION_FLIGHT_MODE,
+ LED_FUNCTION_ARM_STATE,
+ LED_FUNCTION_BATTERY,
+ LED_FUNCTION_RSSI,
+ LED_FUNCTION_GPS,
+ LED_FUNCTION_THRUST_RING,
+ LED_FUNCTION_CHANNEL,
+} ledBaseFunctionId_e;
+
+// ../../../src/main/io/ledstrip.h
+typedef enum {
+ LED_OVERLAY_THROTTLE,
+ LED_OVERLAY_LARSON_SCANNER,
+ LED_OVERLAY_BLINK,
+ LED_OVERLAY_LANDING_FLASH,
+ LED_OVERLAY_INDICATOR,
+ LED_OVERLAY_WARNING,
+ LED_OVERLAY_STROBE
+} ledOverlayId_e;
+
+// ../../../src/main/io/smartport_master.c
+typedef enum {
+ PT_ACTIVE_ID,
+ PT_INACTIVE_ID
+} pollType_e;
+
+// ../../../src/main/io/vtx_smartaudio.c
+enum saFramerState_e {
+ S_WAITPRE1,
+ S_WAITPRE2,
+ S_WAITRESP,
+ S_WAITLEN,
+ S_DATA,
+ S_WAITCRC,
+ } state = S_WAITPRE1;
+typedef enum saFramerState_e saFramerState_e;
+
+// ../../../src/main/io/statusindicator.c
+typedef enum {
+ WARNING_LED_OFF = 0,
+ WARNING_LED_ON,
+ WARNING_LED_FLASH
+} warningLedState_e;
+
+// ../../../src/main/io/frsky_osd.h
+typedef enum {
+ FRSKY_OSD_TRANSACTION_OPT_PROFILED = 1 << 0,
+ FRSKY_OSD_TRANSACTION_OPT_RESET_DRAWING = 1 << 1,
+} frskyOSDTransactionOptions_e;
+
+// ../../../src/main/io/frsky_osd.h
+typedef enum {
+ FRSKY_OSD_COLOR_BLACK = 0,
+ FRSKY_OSD_COLOR_TRANSPARENT = 1,
+ FRSKY_OSD_COLOR_WHITE = 2,
+ FRSKY_OSD_COLOR_GRAY = 3,
+} frskyOSDColor_e;
+
+// ../../../src/main/io/frsky_osd.h
+typedef enum {
+ FRSKY_OSD_OUTLINE_TYPE_NONE = 0,
+ FRSKY_OSD_OUTLINE_TYPE_TOP = 1 << 0,
+ FRSKY_OSD_OUTLINE_TYPE_RIGHT = 1 << 1,
+ FRSKY_OSD_OUTLINE_TYPE_BOTTOM = 1 << 2,
+ FRSKY_OSD_OUTLINE_TYPE_LEFT = 1 << 3,
+} frskyOSDLineOutlineType_e;
+
+// ../../../src/main/io/frsky_osd.h
+typedef enum
+{
+ FRSKY_OSD_WIDGET_ID_AHI = 0,
+
+ FRSKY_OSD_WIDGET_ID_SIDEBAR_0 = 1,
+ FRSKY_OSD_WIDGET_ID_SIDEBAR_1 = 2,
+
+ FRSKY_OSD_WIDGET_ID_GRAPH_0 = 3,
+ FRSKY_OSD_WIDGET_ID_GRAPH_1 = 4,
+ FRSKY_OSD_WIDGET_ID_GRAPH_2 = 5,
+ FRSKY_OSD_WIDGET_ID_GRAPH_3 = 6,
+
+ FRSKY_OSD_WIDGET_ID_CHARGAUGE_0 = 7,
+ FRSKY_OSD_WIDGET_ID_CHARGAUGE_1 = 8,
+ FRSKY_OSD_WIDGET_ID_CHARGAUGE_2 = 9,
+ FRSKY_OSD_WIDGET_ID_CHARGAUGE_3 = 10,
+
+ FRSKY_OSD_WIDGET_ID_SIDEBAR_FIRST = FRSKY_OSD_WIDGET_ID_SIDEBAR_0,
+ FRSKY_OSD_WIDGET_ID_SIDEBAR_LAST = FRSKY_OSD_WIDGET_ID_SIDEBAR_1,
+
+ FRSKY_OSD_WIDGET_ID_GRAPH_FIRST = FRSKY_OSD_WIDGET_ID_GRAPH_0,
+ FRSKY_OSD_WIDGET_ID_GRAPH_LAST = FRSKY_OSD_WIDGET_ID_GRAPH_3,
+
+ FRSKY_OSD_WIDGET_ID_CHARGAUGE_FIRST = FRSKY_OSD_WIDGET_ID_CHARGAUGE_0,
+ FRSKY_OSD_WIDGET_ID_CHARGAUGE_LAST = FRSKY_OSD_WIDGET_ID_CHARGAUGE_3,
+} frskyOSDWidgetID_e;
+
+// ../../../src/main/io/osd.h
+typedef enum {
+ OSD_RSSI_VALUE,
+ OSD_MAIN_BATT_VOLTAGE,
+ OSD_CROSSHAIRS,
+ OSD_ARTIFICIAL_HORIZON,
+ OSD_HORIZON_SIDEBARS,
+ OSD_ONTIME,
+ OSD_FLYTIME,
+ OSD_FLYMODE,
+ OSD_CRAFT_NAME,
+ OSD_THROTTLE_POS,
+ OSD_VTX_CHANNEL,
+ OSD_CURRENT_DRAW,
+ OSD_MAH_DRAWN,
+ OSD_GPS_SPEED,
+ OSD_GPS_SATS,
+ OSD_ALTITUDE,
+ OSD_ROLL_PIDS,
+ OSD_PITCH_PIDS,
+ OSD_YAW_PIDS,
+ OSD_POWER,
+ OSD_GPS_LON,
+ OSD_GPS_LAT,
+ OSD_HOME_DIR,
+ OSD_HOME_DIST,
+ OSD_HEADING,
+ OSD_VARIO,
+ OSD_VERTICAL_SPEED_INDICATOR,
+ OSD_AIR_SPEED,
+ OSD_ONTIME_FLYTIME,
+ OSD_RTC_TIME,
+ OSD_MESSAGES,
+ OSD_GPS_HDOP,
+ OSD_MAIN_BATT_CELL_VOLTAGE,
+ OSD_SCALED_THROTTLE_POS,
+ OSD_HEADING_GRAPH,
+ OSD_EFFICIENCY_MAH_PER_KM,
+ OSD_WH_DRAWN,
+ OSD_BATTERY_REMAINING_CAPACITY,
+ OSD_BATTERY_REMAINING_PERCENT,
+ OSD_EFFICIENCY_WH_PER_KM,
+ OSD_TRIP_DIST,
+ OSD_ATTITUDE_PITCH,
+ OSD_ATTITUDE_ROLL,
+ OSD_MAP_NORTH,
+ OSD_MAP_TAKEOFF,
+ OSD_RADAR,
+ OSD_WIND_SPEED_HORIZONTAL,
+ OSD_WIND_SPEED_VERTICAL,
+ OSD_REMAINING_FLIGHT_TIME_BEFORE_RTH,
+ OSD_REMAINING_DISTANCE_BEFORE_RTH,
+ OSD_HOME_HEADING_ERROR,
+ OSD_COURSE_HOLD_ERROR,
+ OSD_COURSE_HOLD_ADJUSTMENT,
+ OSD_SAG_COMPENSATED_MAIN_BATT_VOLTAGE,
+ OSD_MAIN_BATT_SAG_COMPENSATED_CELL_VOLTAGE,
+ OSD_POWER_SUPPLY_IMPEDANCE,
+ OSD_LEVEL_PIDS,
+ OSD_POS_XY_PIDS,
+ OSD_POS_Z_PIDS,
+ OSD_VEL_XY_PIDS,
+ OSD_VEL_Z_PIDS,
+ OSD_HEADING_P,
+ OSD_BOARD_ALIGN_ROLL,
+ OSD_BOARD_ALIGN_PITCH,
+ OSD_RC_EXPO,
+ OSD_RC_YAW_EXPO,
+ OSD_THROTTLE_EXPO,
+ OSD_PITCH_RATE,
+ OSD_ROLL_RATE,
+ OSD_YAW_RATE,
+ OSD_MANUAL_RC_EXPO,
+ OSD_MANUAL_RC_YAW_EXPO,
+ OSD_MANUAL_PITCH_RATE,
+ OSD_MANUAL_ROLL_RATE,
+ OSD_MANUAL_YAW_RATE,
+ OSD_NAV_FW_CRUISE_THR,
+ OSD_NAV_FW_PITCH2THR,
+ OSD_FW_MIN_THROTTLE_DOWN_PITCH_ANGLE,
+ OSD_DEBUG,
+ OSD_FW_ALT_PID_OUTPUTS,
+ OSD_FW_POS_PID_OUTPUTS,
+ OSD_MC_VEL_X_PID_OUTPUTS,
+ OSD_MC_VEL_Y_PID_OUTPUTS,
+ OSD_MC_VEL_Z_PID_OUTPUTS,
+ OSD_MC_POS_XYZ_P_OUTPUTS,
+ OSD_3D_SPEED,
+ OSD_IMU_TEMPERATURE,
+ OSD_BARO_TEMPERATURE,
+ OSD_TEMP_SENSOR_0_TEMPERATURE,
+ OSD_TEMP_SENSOR_1_TEMPERATURE,
+ OSD_TEMP_SENSOR_2_TEMPERATURE,
+ OSD_TEMP_SENSOR_3_TEMPERATURE,
+ OSD_TEMP_SENSOR_4_TEMPERATURE,
+ OSD_TEMP_SENSOR_5_TEMPERATURE,
+ OSD_TEMP_SENSOR_6_TEMPERATURE,
+ OSD_TEMP_SENSOR_7_TEMPERATURE,
+ OSD_ALTITUDE_MSL,
+ OSD_PLUS_CODE,
+ OSD_MAP_SCALE,
+ OSD_MAP_REFERENCE,
+ OSD_GFORCE,
+ OSD_GFORCE_X,
+ OSD_GFORCE_Y,
+ OSD_GFORCE_Z,
+ OSD_RC_SOURCE,
+ OSD_VTX_POWER,
+ OSD_ESC_RPM,
+ OSD_ESC_TEMPERATURE,
+ OSD_AZIMUTH,
+ OSD_RSSI_DBM,
+ OSD_LQ_UPLINK,
+ OSD_SNR_DB,
+ OSD_TX_POWER_UPLINK,
+ OSD_GVAR_0,
+ OSD_GVAR_1,
+ OSD_GVAR_2,
+ OSD_GVAR_3,
+ OSD_TPA,
+ OSD_NAV_FW_CONTROL_SMOOTHNESS,
+ OSD_VERSION,
+ OSD_RANGEFINDER,
+ OSD_PLIMIT_REMAINING_BURST_TIME,
+ OSD_PLIMIT_ACTIVE_CURRENT_LIMIT,
+ OSD_PLIMIT_ACTIVE_POWER_LIMIT,
+ OSD_GLIDESLOPE,
+ OSD_GPS_MAX_SPEED,
+ OSD_3D_MAX_SPEED,
+ OSD_AIR_MAX_SPEED,
+ OSD_ACTIVE_PROFILE,
+ OSD_MISSION,
+ OSD_SWITCH_INDICATOR_0,
+ OSD_SWITCH_INDICATOR_1,
+ OSD_SWITCH_INDICATOR_2,
+ OSD_SWITCH_INDICATOR_3,
+ OSD_TPA_TIME_CONSTANT,
+ OSD_FW_LEVEL_TRIM,
+ OSD_GLIDE_TIME_REMAINING,
+ OSD_GLIDE_RANGE,
+ OSD_CLIMB_EFFICIENCY,
+ OSD_NAV_WP_MULTI_MISSION_INDEX,
+ OSD_GROUND_COURSE,
+ OSD_CROSS_TRACK_ERROR,
+ OSD_PILOT_NAME,
+ OSD_PAN_SERVO_CENTRED,
+ OSD_MULTI_FUNCTION,
+ OSD_ODOMETER,
+ OSD_PILOT_LOGO,
+ OSD_CUSTOM_ELEMENT_1,
+ OSD_CUSTOM_ELEMENT_2,
+ OSD_CUSTOM_ELEMENT_3,
+ OSD_ADSB_WARNING,
+ OSD_ADSB_INFO,
+ OSD_BLACKBOX,
+ OSD_FORMATION_FLIGHT,
+ OSD_CUSTOM_ELEMENT_4,
+ OSD_CUSTOM_ELEMENT_5,
+ OSD_CUSTOM_ELEMENT_6,
+ OSD_CUSTOM_ELEMENT_7,
+ OSD_CUSTOM_ELEMENT_8,
+ OSD_LQ_DOWNLINK,
+ OSD_RX_POWER_DOWNLINK,
+ OSD_RX_BAND,
+ OSD_RX_MODE,
+ OSD_COURSE_TO_FENCE,
+ OSD_H_DIST_TO_FENCE,
+ OSD_V_DIST_TO_FENCE,
+ OSD_NAV_FW_ALT_CONTROL_RESPONSE,
+ OSD_NAV_MIN_GROUND_SPEED,
+ OSD_THROTTLE_GAUGE,
+ OSD_ITEM_COUNT
+} osd_items_e;
+
+// ../../../src/main/io/osd.h
+typedef enum {
+ OSD_UNIT_IMPERIAL,
+ OSD_UNIT_METRIC,
+ OSD_UNIT_METRIC_MPH,
+ OSD_UNIT_UK,
+ OSD_UNIT_GA,
+
+ OSD_UNIT_MAX = OSD_UNIT_GA,
+} osd_unit_e;
+
+// ../../../src/main/io/osd.h
+typedef enum {
+ OSD_STATS_ENERGY_UNIT_MAH,
+ OSD_STATS_ENERGY_UNIT_WH,
+} osd_stats_energy_unit_e;
+
+// ../../../src/main/io/osd.h
+typedef enum {
+ OSD_CROSSHAIRS_STYLE_DEFAULT,
+ OSD_CROSSHAIRS_STYLE_AIRCRAFT,
+ OSD_CROSSHAIRS_STYLE_TYPE3,
+ OSD_CROSSHAIRS_STYLE_TYPE4,
+ OSD_CROSSHAIRS_STYLE_TYPE5,
+ OSD_CROSSHAIRS_STYLE_TYPE6,
+ OSD_CROSSHAIRS_STYLE_TYPE7,
+} osd_crosshairs_style_e;
+
+// ../../../src/main/io/osd.h
+typedef enum {
+ OSD_SIDEBAR_SCROLL_NONE,
+ OSD_SIDEBAR_SCROLL_ALTITUDE,
+ OSD_SIDEBAR_SCROLL_SPEED,
+ OSD_SIDEBAR_SCROLL_HOME_DISTANCE,
+
+ OSD_SIDEBAR_SCROLL_MAX = OSD_SIDEBAR_SCROLL_HOME_DISTANCE,
+} osd_sidebar_scroll_e;
+
+// ../../../src/main/io/osd.h
+typedef enum {
+ OSD_ALIGN_LEFT,
+ OSD_ALIGN_RIGHT
+} osd_alignment_e;
+
+// ../../../src/main/io/osd.h
+typedef enum {
+ OSD_ADSB_WARNING_STYLE_COMPACT,
+ OSD_ADSB_WARNING_STYLE_EXTENDED,
+} osd_adsb_warning_style_e;
+
+// ../../../src/main/io/osd.h
+typedef enum {
+ OSD_AHI_STYLE_DEFAULT,
+ OSD_AHI_STYLE_LINE,
+} osd_ahi_style_e;
+
+// ../../../src/main/io/osd.h
+typedef enum {
+ OSD_CRSF_LQ_TYPE1,
+ OSD_CRSF_LQ_TYPE2,
+ OSD_CRSF_LQ_TYPE3
+} osd_crsf_lq_format_e;
+
+// ../../../src/main/io/osd.h
+typedef enum {
+ OSD_SPEED_TYPE_GROUND,
+ OSD_SPEED_TYPE_AIR,
+ OSD_SPEED_TYPE_3D,
+ OSD_SPEED_TYPE_MIN_GROUND,
+} osd_SpeedTypes_e;
+
+// ../../../src/main/io/ledstrip.c
+typedef enum {
+
+ QUADRANT_NORTH = 1 << 0,
+ QUADRANT_SOUTH = 1 << 1,
+ QUADRANT_EAST = 1 << 2,
+ QUADRANT_WEST = 1 << 3,
+ QUADRANT_NORTH_EAST = 1 << 4,
+ QUADRANT_SOUTH_EAST = 1 << 5,
+ QUADRANT_NORTH_WEST = 1 << 6,
+ QUADRANT_SOUTH_WEST = 1 << 7,
+ QUADRANT_NONE = 1 << 8,
+ QUADRANT_NOTDIAG = 1 << 9,
+
+ QUADRANT_ANY = QUADRANT_NORTH | QUADRANT_SOUTH | QUADRANT_EAST | QUADRANT_WEST | QUADRANT_NONE,
+} quadrant_e;
+
+// ../../../src/main/io/ledstrip.c
+typedef enum {
+ WARNING_ARMING_DISABLED,
+ WARNING_LOW_BATTERY,
+ WARNING_FAILSAFE,
+ WARNING_HW_ERROR,
+} warningFlags_e;
+
+// ../../../src/main/io/ledstrip.c
+typedef enum {
+ timBlink = 0,
+ timLarson,
+ timBattery,
+ timRssi,
+#ifdef USE_GPS
+ timGps,
+#endif
+ timWarning,
+ timIndicator,
+#ifdef USE_LED_ANIMATION
+ timAnimation,
+#endif
+ timRing,
+ timTimerCount
+} timId_e;
+
+// ../../../src/main/io/ledstrip.c
+enum parseState_e {
+ X_COORDINATE,
+ Y_COORDINATE,
+ DIRECTIONS,
+ FUNCTIONS,
+ RING_COLORS,
+ PARSE_STATE_COUNT
+ };
+typedef enum parseState_e parseState_e;
+
+// ../../../src/main/io/vtx_smartaudio.h
+typedef enum {
+ SA_UNKNOWN,
+ SA_1_0,
+ SA_2_0,
+ SA_2_1
+} smartAudioVersion_e;
+
+// ../../../src/main/io/gps_private.h
+typedef enum {
+ GPS_UNKNOWN,
+ GPS_INITIALIZING,
+ GPS_RUNNING,
+ GPS_LOST_COMMUNICATION,
+} gpsState_e;
+
+// ../../../src/main/io/smartport_master.h
+typedef enum {
+ VS600_BAND_A,
+ VS600_BAND_B,
+ VS600_BAND_C,
+ VS600_BAND_D,
+ VS600_BAND_E,
+ VS600_BAND_F,
+} vs600Band_e;
+
+// ../../../src/main/io/smartport_master.h
+typedef enum {
+ VS600_POWER_PIT,
+ VS600_POWER_25MW,
+ VS600_POWER_200MW,
+ VS600_POWER_600MW,
+} vs600Power_e;
+
+// ../../../src/main/io/displayport_msp_osd.c
+typedef enum {
+ SD_3016,
+ HD_5018,
+ HD_6022,
+ HD_5320
+} resolutionType_e;
+
+// ../../../src/main/io/osd_grid.c
+typedef enum {
+ OSD_SIDEBAR_ARROW_NONE,
+ OSD_SIDEBAR_ARROW_UP,
+ OSD_SIDEBAR_ARROW_DOWN,
+} osd_sidebar_arrow_e;
+
+// ../../../src/main/io/osd/custom_elements.h
+typedef enum {
+ CUSTOM_ELEMENT_TYPE_NONE = 0,
+ CUSTOM_ELEMENT_TYPE_TEXT = 1,
+ CUSTOM_ELEMENT_TYPE_ICON_STATIC = 2,
+ CUSTOM_ELEMENT_TYPE_ICON_GV = 3,
+ CUSTOM_ELEMENT_TYPE_ICON_LC = 4,
+ CUSTOM_ELEMENT_TYPE_GV_1 = 5,
+ CUSTOM_ELEMENT_TYPE_GV_2 = 6,
+ CUSTOM_ELEMENT_TYPE_GV_3 = 7,
+ CUSTOM_ELEMENT_TYPE_GV_4 = 8,
+ CUSTOM_ELEMENT_TYPE_GV_5 = 9,
+ CUSTOM_ELEMENT_TYPE_GV_FLOAT_1_1 = 10,
+ CUSTOM_ELEMENT_TYPE_GV_FLOAT_1_2 = 11,
+ CUSTOM_ELEMENT_TYPE_GV_FLOAT_2_1 = 12,
+ CUSTOM_ELEMENT_TYPE_GV_FLOAT_2_2 = 13,
+ CUSTOM_ELEMENT_TYPE_GV_FLOAT_3_1 = 14,
+ CUSTOM_ELEMENT_TYPE_GV_FLOAT_3_2 = 15,
+ CUSTOM_ELEMENT_TYPE_GV_FLOAT_4_1 = 16,
+ CUSTOM_ELEMENT_TYPE_LC_1 = 17,
+ CUSTOM_ELEMENT_TYPE_LC_2 = 18,
+ CUSTOM_ELEMENT_TYPE_LC_3 = 19,
+ CUSTOM_ELEMENT_TYPE_LC_4 = 20,
+ CUSTOM_ELEMENT_TYPE_LC_5 = 21,
+ CUSTOM_ELEMENT_TYPE_LC_FLOAT_1_1 = 22,
+ CUSTOM_ELEMENT_TYPE_LC_FLOAT_1_2 = 23,
+ CUSTOM_ELEMENT_TYPE_LC_FLOAT_2_1 = 24,
+ CUSTOM_ELEMENT_TYPE_LC_FLOAT_2_2 = 25,
+ CUSTOM_ELEMENT_TYPE_LC_FLOAT_3_1 = 26,
+ CUSTOM_ELEMENT_TYPE_LC_FLOAT_3_2 = 27,
+ CUSTOM_ELEMENT_TYPE_LC_FLOAT_4_1 = 28,
+ CUSTOM_ELEMENT_TYPE_END
+} osdCustomElementType_e;
+
+// ../../../src/main/io/osd/custom_elements.h
+typedef enum {
+ CUSTOM_ELEMENT_VISIBILITY_ALWAYS = 0,
+ CUSTOM_ELEMENT_VISIBILITY_GV = 1,
+ CUSTOM_ELEMENT_VISIBILITY_LOGIC_CON = 2,
+} osdCustomElementTypeVisibility_e;
+
+// ../../../src/main/io/asyncfatfs/asyncfatfs.h
+typedef enum {
+ AFATFS_FILESYSTEM_STATE_UNKNOWN,
+ AFATFS_FILESYSTEM_STATE_FATAL,
+ AFATFS_FILESYSTEM_STATE_INITIALIZATION,
+ AFATFS_FILESYSTEM_STATE_READY,
+} afatfsFilesystemState_e;
+
+// ../../../src/main/io/asyncfatfs/asyncfatfs.h
+typedef enum {
+ AFATFS_OPERATION_IN_PROGRESS,
+ AFATFS_OPERATION_SUCCESS,
+ AFATFS_OPERATION_FAILURE,
+} afatfsOperationStatus_e;
+
+// ../../../src/main/io/asyncfatfs/asyncfatfs.h
+typedef enum {
+ AFATFS_ERROR_NONE = 0,
+ AFATFS_ERROR_GENERIC = 1,
+ AFATFS_ERROR_BAD_MBR = 2,
+ AFATFS_ERROR_BAD_FILESYSTEM_HEADER = 3
+} afatfsError_e;
+
+// ../../../src/main/io/asyncfatfs/asyncfatfs.h
+typedef enum {
+ AFATFS_SEEK_SET,
+ AFATFS_SEEK_CUR,
+ AFATFS_SEEK_END,
+} afatfsSeek_e;
+
+// ../../../src/main/io/asyncfatfs/fat_standard.h
+typedef enum {
+ FAT_FILESYSTEM_TYPE_INVALID,
+ FAT_FILESYSTEM_TYPE_FAT12,
+ FAT_FILESYSTEM_TYPE_FAT16,
+ FAT_FILESYSTEM_TYPE_FAT32,
+} fatFilesystemType_e;
+
+// ../../../src/main/io/asyncfatfs/asyncfatfs.c
+typedef enum {
+ AFATFS_SAVE_DIRECTORY_NORMAL,
+ AFATFS_SAVE_DIRECTORY_FOR_CLOSE,
+ AFATFS_SAVE_DIRECTORY_DELETED,
+} afatfsSaveDirectoryEntryMode_e;
+
+// ../../../src/main/io/asyncfatfs/asyncfatfs.c
+typedef enum {
+ AFATFS_CACHE_STATE_EMPTY,
+ AFATFS_CACHE_STATE_IN_SYNC,
+ AFATFS_CACHE_STATE_READING,
+ AFATFS_CACHE_STATE_WRITING,
+ AFATFS_CACHE_STATE_DIRTY
+} afatfsCacheBlockState_e;
+
+// ../../../src/main/io/asyncfatfs/asyncfatfs.c
+typedef enum {
+ AFATFS_FILE_TYPE_NONE,
+ AFATFS_FILE_TYPE_NORMAL,
+ AFATFS_FILE_TYPE_FAT16_ROOT_DIRECTORY,
+ AFATFS_FILE_TYPE_DIRECTORY
+} afatfsFileType_e;
+
+// ../../../src/main/io/asyncfatfs/asyncfatfs.c
+typedef enum {
+ CLUSTER_SEARCH_FREE_AT_BEGINNING_OF_FAT_SECTOR,
+ CLUSTER_SEARCH_FREE,
+ CLUSTER_SEARCH_OCCUPIED,
+} afatfsClusterSearchCondition_e;
+
+// ../../../src/main/io/asyncfatfs/asyncfatfs.c
+typedef enum {
+ AFATFS_FIND_CLUSTER_IN_PROGRESS,
+ AFATFS_FIND_CLUSTER_FOUND,
+ AFATFS_FIND_CLUSTER_FATAL,
+ AFATFS_FIND_CLUSTER_NOT_FOUND,
+} afatfsFindClusterStatus_e;
+
+// ../../../src/main/io/asyncfatfs/asyncfatfs.c
+typedef enum {
+ AFATFS_FAT_PATTERN_UNTERMINATED_CHAIN,
+ AFATFS_FAT_PATTERN_TERMINATED_CHAIN,
+ AFATFS_FAT_PATTERN_FREE
+} afatfsFATPattern_e;
+
+// ../../../src/main/io/asyncfatfs/asyncfatfs.c
+typedef enum {
+ AFATFS_FREE_SPACE_SEARCH_PHASE_FIND_HOLE,
+ AFATFS_FREE_SPACE_SEARCH_PHASE_GROW_HOLE
+} afatfsFreeSpaceSearchPhase_e;
+
+// ../../../src/main/io/asyncfatfs/asyncfatfs.c
+typedef enum {
+ AFATFS_APPEND_SUPERCLUSTER_PHASE_INIT = 0,
+ AFATFS_APPEND_SUPERCLUSTER_PHASE_UPDATE_FREEFILE_DIRECTORY,
+ AFATFS_APPEND_SUPERCLUSTER_PHASE_UPDATE_FAT,
+ AFATFS_APPEND_SUPERCLUSTER_PHASE_UPDATE_FILE_DIRECTORY,
+} afatfsAppendSuperclusterPhase_e;
+
+// ../../../src/main/io/asyncfatfs/asyncfatfs.c
+typedef enum {
+ AFATFS_APPEND_FREE_CLUSTER_PHASE_INITIAL = 0,
+ AFATFS_APPEND_FREE_CLUSTER_PHASE_FIND_FREESPACE = 0,
+ AFATFS_APPEND_FREE_CLUSTER_PHASE_UPDATE_FAT1,
+ AFATFS_APPEND_FREE_CLUSTER_PHASE_UPDATE_FAT2,
+ AFATFS_APPEND_FREE_CLUSTER_PHASE_UPDATE_FILE_DIRECTORY,
+ AFATFS_APPEND_FREE_CLUSTER_PHASE_COMPLETE,
+ AFATFS_APPEND_FREE_CLUSTER_PHASE_FAILURE,
+} afatfsAppendFreeClusterPhase_e;
+
+// ../../../src/main/io/asyncfatfs/asyncfatfs.c
+typedef enum {
+ AFATFS_EXTEND_SUBDIRECTORY_PHASE_INITIAL = 0,
+ AFATFS_EXTEND_SUBDIRECTORY_PHASE_ADD_FREE_CLUSTER = 0,
+ AFATFS_EXTEND_SUBDIRECTORY_PHASE_WRITE_SECTORS,
+ AFATFS_EXTEND_SUBDIRECTORY_PHASE_SUCCESS,
+ AFATFS_EXTEND_SUBDIRECTORY_PHASE_FAILURE
+} afatfsExtendSubdirectoryPhase_e;
+
+// ../../../src/main/io/asyncfatfs/asyncfatfs.c
+typedef enum {
+ AFATFS_TRUNCATE_FILE_INITIAL = 0,
+ AFATFS_TRUNCATE_FILE_UPDATE_DIRECTORY = 0,
+ AFATFS_TRUNCATE_FILE_ERASE_FAT_CHAIN_NORMAL,
+#ifdef AFATFS_USE_FREEFILE
+ AFATFS_TRUNCATE_FILE_ERASE_FAT_CHAIN_CONTIGUOUS,
+ AFATFS_TRUNCATE_FILE_PREPEND_TO_FREEFILE,
+#endif
+ AFATFS_TRUNCATE_FILE_SUCCESS,
+} afatfsTruncateFilePhase_e;
+
+// ../../../src/main/io/asyncfatfs/asyncfatfs.c
+typedef enum {
+ AFATFS_DELETE_FILE_DELETE_DIRECTORY_ENTRY,
+ AFATFS_DELETE_FILE_DEALLOCATE_CLUSTERS,
+} afatfsDeleteFilePhase_e;
+
+// ../../../src/main/io/asyncfatfs/asyncfatfs.c
+typedef enum {
+ AFATFS_FILE_OPERATION_NONE,
+ AFATFS_FILE_OPERATION_CREATE_FILE,
+ AFATFS_FILE_OPERATION_SEEK,
+ AFATFS_FILE_OPERATION_CLOSE,
+ AFATFS_FILE_OPERATION_TRUNCATE,
+ AFATFS_FILE_OPERATION_UNLINK,
+#ifdef AFATFS_USE_FREEFILE
+ AFATFS_FILE_OPERATION_APPEND_SUPERCLUSTER,
+ AFATFS_FILE_OPERATION_LOCKED,
+#endif
+ AFATFS_FILE_OPERATION_APPEND_FREE_CLUSTER,
+ AFATFS_FILE_OPERATION_EXTEND_SUBDIRECTORY,
+} afatfsFileOperation_e;
+
+// ../../../src/main/io/asyncfatfs/asyncfatfs.c
+typedef enum {
+ AFATFS_INITIALIZATION_READ_MBR,
+ AFATFS_INITIALIZATION_READ_VOLUME_ID,
+
+#ifdef AFATFS_USE_FREEFILE
+ AFATFS_INITIALIZATION_FREEFILE_CREATE,
+ AFATFS_INITIALIZATION_FREEFILE_CREATING,
+ AFATFS_INITIALIZATION_FREEFILE_FAT_SEARCH,
+ AFATFS_INITIALIZATION_FREEFILE_UPDATE_FAT,
+ AFATFS_INITIALIZATION_FREEFILE_SAVE_DIR_ENTRY,
+ AFATFS_INITIALIZATION_FREEFILE_LAST = AFATFS_INITIALIZATION_FREEFILE_SAVE_DIR_ENTRY,
+#endif
+
+ AFATFS_INITIALIZATION_DONE
+} afatfsInitializationPhase_e;
+
+// ../../../src/main/flight/servos.h
+typedef enum {
+ INPUT_STABILIZED_ROLL = 0,
+ INPUT_STABILIZED_PITCH = 1,
+ INPUT_STABILIZED_YAW = 2,
+ INPUT_STABILIZED_THROTTLE = 3,
+ INPUT_RC_ROLL = 4,
+ INPUT_RC_PITCH = 5,
+ INPUT_RC_YAW = 6,
+ INPUT_RC_THROTTLE = 7,
+ INPUT_RC_CH5 = 8,
+ INPUT_RC_CH6 = 9,
+ INPUT_RC_CH7 = 10,
+ INPUT_RC_CH8 = 11,
+ INPUT_GIMBAL_PITCH = 12,
+ INPUT_GIMBAL_ROLL = 13,
+ INPUT_FEATURE_FLAPS = 14,
+ INPUT_RC_CH9 = 15,
+ INPUT_RC_CH10 = 16,
+ INPUT_RC_CH11 = 17,
+ INPUT_RC_CH12 = 18,
+ INPUT_RC_CH13 = 19,
+ INPUT_RC_CH14 = 20,
+ INPUT_RC_CH15 = 21,
+ INPUT_RC_CH16 = 22,
+ INPUT_STABILIZED_ROLL_PLUS = 23,
+ INPUT_STABILIZED_ROLL_MINUS = 24,
+ INPUT_STABILIZED_PITCH_PLUS = 25,
+ INPUT_STABILIZED_PITCH_MINUS = 26,
+ INPUT_STABILIZED_YAW_PLUS = 27,
+ INPUT_STABILIZED_YAW_MINUS = 28,
+ INPUT_MAX = 29,
+ INPUT_GVAR_0 = 30,
+ INPUT_GVAR_1 = 31,
+ INPUT_GVAR_2 = 32,
+ INPUT_GVAR_3 = 33,
+ INPUT_GVAR_4 = 34,
+ INPUT_GVAR_5 = 35,
+ INPUT_GVAR_6 = 36,
+ INPUT_GVAR_7 = 37,
+ INPUT_MIXER_TRANSITION = 38,
+ INPUT_HEADTRACKER_PAN = 39,
+ INPUT_HEADTRACKER_TILT = 40,
+ INPUT_HEADTRACKER_ROLL = 41,
+ INPUT_RC_CH17 = 42,
+ INPUT_RC_CH18 = 43,
+ INPUT_RC_CH19 = 44,
+ INPUT_RC_CH20 = 45,
+ INPUT_RC_CH21 = 46,
+ INPUT_RC_CH22 = 47,
+ INPUT_RC_CH23 = 48,
+ INPUT_RC_CH24 = 49,
+ INPUT_RC_CH25 = 50,
+ INPUT_RC_CH26 = 51,
+ INPUT_RC_CH27 = 52,
+ INPUT_RC_CH28 = 53,
+ INPUT_RC_CH29 = 54,
+ INPUT_RC_CH30 = 55,
+ INPUT_RC_CH31 = 56,
+ INPUT_RC_CH32 = 57,
+ INPUT_RC_CH33 = 58,
+ INPUT_RC_CH34 = 59,
+ INPUT_MIXER_SWITCH_HELPER = 60,
+ INPUT_SOURCE_COUNT
+} inputSource_e;
+
+// ../../../src/main/flight/servos.h
+typedef enum {
+ SERVO_GIMBAL_PITCH = 0,
+ SERVO_GIMBAL_ROLL = 1,
+ SERVO_ELEVATOR = 2,
+ SERVO_FLAPPERON_1 = 3,
+ SERVO_FLAPPERON_2 = 4,
+ SERVO_RUDDER = 5,
+
+ SERVO_BICOPTER_LEFT = 4,
+ SERVO_BICOPTER_RIGHT = 5,
+
+ SERVO_DUALCOPTER_LEFT = 4,
+ SERVO_DUALCOPTER_RIGHT = 5,
+
+ SERVO_SINGLECOPTER_1 = 3,
+ SERVO_SINGLECOPTER_2 = 4,
+ SERVO_SINGLECOPTER_3 = 5,
+ SERVO_SINGLECOPTER_4 = 6,
+
+} servoIndex_e;
+
+// ../../../src/main/flight/mixer_profile.h
+typedef enum {
+ MIXERAT_REQUEST_NONE,
+ MIXERAT_REQUEST_RTH,
+ MIXERAT_REQUEST_LAND,
+ MIXERAT_REQUEST_ABORT,
+} mixerProfileATRequest_e;
+
+// ../../../src/main/flight/mixer_profile.h
+typedef enum {
+ MIXERAT_PHASE_IDLE,
+ MIXERAT_PHASE_TRANSITION_INITIALIZE,
+ MIXERAT_PHASE_TRANSITIONING,
+ MIXERAT_PHASE_DONE,
+} mixerProfileATState_e;
+
+// ../../../src/main/flight/pid_autotune.c
+typedef enum {
+ DEMAND_TOO_LOW,
+ DEMAND_UNDERSHOOT,
+ DEMAND_OVERSHOOT,
+ TUNE_UPDATED,
+} pidAutotuneState_e;
+
+// ../../../src/main/flight/servos.c
+typedef enum {
+ AUTOTRIM_IDLE,
+ AUTOTRIM_COLLECTING,
+ AUTOTRIM_SAVE_PENDING,
+ AUTOTRIM_DONE,
+} servoAutotrimState_e;
+
+// ../../../src/main/flight/pid.h
+typedef enum {
+
+ PID_ROLL,
+ PID_PITCH,
+ PID_YAW,
+ PID_POS_Z,
+ PID_POS_XY,
+ PID_VEL_XY,
+ PID_SURFACE,
+ PID_LEVEL,
+ PID_HEADING,
+ PID_VEL_Z,
+ PID_POS_HEADING,
+ PID_ITEM_COUNT
+} pidIndex_e;
+
+// ../../../src/main/flight/pid.h
+typedef enum {
+ PID_TYPE_NONE = 0,
+ PID_TYPE_PID,
+ PID_TYPE_PIFF,
+ PID_TYPE_AUTO,
+} pidType_e;
+
+// ../../../src/main/flight/pid.h
+typedef enum {
+ ITERM_RELAX_OFF = 0,
+ ITERM_RELAX_RP,
+ ITERM_RELAX_RPY
+} itermRelax_e;
+
+// ../../../src/main/flight/pid.h
+typedef enum {
+ FIXED,
+ LIMIT,
+ AUTO,
+} fw_autotune_rate_adjustment_e;
+
+// ../../../src/main/flight/mixer.h
+typedef enum {
+ PLATFORM_MULTIROTOR = 0,
+ PLATFORM_AIRPLANE = 1,
+ PLATFORM_HELICOPTER = 2,
+ PLATFORM_TRICOPTER = 3,
+ PLATFORM_ROVER = 4,
+ PLATFORM_BOAT = 5
+} flyingPlatformType_e;
+
+// ../../../src/main/flight/mixer.h
+typedef enum {
+ OUTPUT_MODE_AUTO = 0,
+ OUTPUT_MODE_MOTORS,
+ OUTPUT_MODE_SERVOS,
+ OUTPUT_MODE_LED
+} outputMode_e;
+
+// ../../../src/main/flight/mixer.h
+typedef enum {
+ MOTOR_STOPPED_USER,
+ MOTOR_STOPPED_AUTO,
+ MOTOR_RUNNING
+} motorStatus_e;
+
+// ../../../src/main/flight/mixer.h
+typedef enum {
+ MOTOR_DIRECTION_FORWARD,
+ MOTOR_DIRECTION_BACKWARD,
+ MOTOR_DIRECTION_DEADBAND
+} reversibleMotorsThrottleState_e;
+
+// ../../../src/main/flight/imu.h
+typedef enum
+{
+ COMPMETHOD_VELNED = 0,
+ COMPMETHOD_TURNRATE,
+ COMPMETHOD_ADAPTIVE
+} imu_inertia_comp_method_e;
+
+// ../../../src/main/flight/failsafe.h
+typedef enum {
+ FAILSAFE_IDLE = 0,
+
+ FAILSAFE_RX_LOSS_DETECTED,
+
+ FAILSAFE_RX_LOSS_IDLE,
+
+ FAILSAFE_RETURN_TO_HOME,
+
+ FAILSAFE_LANDING,
+
+ FAILSAFE_LANDED,
+
+ FAILSAFE_RX_LOSS_MONITORING,
+
+ FAILSAFE_RX_LOSS_RECOVERED
+
+} failsafePhase_e;
+
+// ../../../src/main/flight/failsafe.h
+typedef enum {
+ FAILSAFE_RXLINK_DOWN = 0,
+ FAILSAFE_RXLINK_UP
+} failsafeRxLinkState_e;
+
+// ../../../src/main/flight/failsafe.h
+typedef enum {
+ FAILSAFE_PROCEDURE_AUTO_LANDING = 0,
+ FAILSAFE_PROCEDURE_DROP_IT,
+ FAILSAFE_PROCEDURE_RTH,
+ FAILSAFE_PROCEDURE_NONE
+} failsafeProcedure_e;
+
+// ../../../src/main/flight/failsafe.h
+typedef enum {
+ RTH_IDLE = 0,
+ RTH_IN_PROGRESS,
+ RTH_HAS_LANDED
+} rthState_e;
+
+// ../../../src/main/flight/failsafe.h
+typedef enum {
+ EMERG_LAND_IDLE = 0,
+ EMERG_LAND_IN_PROGRESS,
+ EMERG_LAND_HAS_LANDED
+} emergLandState_e;
+
+// ../../../src/main/flight/failsafe.c
+typedef enum {
+ FAILSAFE_CHANNEL_HOLD,
+ FAILSAFE_CHANNEL_NEUTRAL,
+} failsafeChannelBehavior_e;
+
+// ../../../src/main/fc/fc_core.h
+typedef enum disarmReason_e {
+ DISARM_NONE = 0,
+ DISARM_TIMEOUT = 1,
+ DISARM_STICKS = 2,
+ DISARM_SWITCH_3D = 3,
+ DISARM_SWITCH = 4,
+ DISARM_FAILSAFE = 6,
+ DISARM_NAVIGATION = 7,
+ DISARM_LANDING = 8,
+ DISARM_REASON_COUNT
+} disarmReason_t;
+
+// ../../../src/main/fc/fc_core.h
+enum disarmReason_e {
+ DISARM_NONE = 0,
+ DISARM_TIMEOUT = 1,
+ DISARM_STICKS = 2,
+ DISARM_SWITCH_3D = 3,
+ DISARM_SWITCH = 4,
+ DISARM_FAILSAFE = 6,
+ DISARM_NAVIGATION = 7,
+ DISARM_LANDING = 8,
+ DISARM_REASON_COUNT
+} disarmReason_t;
+typedef enum disarmReason_e disarmReason_e;
+
+// ../../../src/main/fc/fc_init.c
+typedef enum {
+ SYSTEM_STATE_INITIALISING = 0,
+ SYSTEM_STATE_CONFIG_LOADED = (1 << 0),
+ SYSTEM_STATE_SENSORS_READY = (1 << 1),
+ SYSTEM_STATE_MOTORS_READY = (1 << 2),
+ SYSTEM_STATE_TRANSPONDER_ENABLED = (1 << 3),
+ SYSTEM_STATE_READY = (1 << 7)
+} systemState_e;
+
+// ../../../src/main/fc/rc_modes.h
+typedef enum {
+ BOXARM = 0,
+ BOXANGLE = 1,
+ BOXHORIZON = 2,
+ BOXNAVALTHOLD = 3,
+ BOXHEADINGHOLD = 4,
+ BOXHEADFREE = 5,
+ BOXHEADADJ = 6,
+ BOXCAMSTAB = 7,
+ BOXNAVRTH = 8,
+ BOXNAVPOSHOLD = 9,
+ BOXMANUAL = 10,
+ BOXBEEPERON = 11,
+ BOXLEDLOW = 12,
+ BOXLIGHTS = 13,
+ BOXNAVLAUNCH = 14,
+ BOXOSD = 15,
+ BOXTELEMETRY = 16,
+ BOXBLACKBOX = 17,
+ BOXFAILSAFE = 18,
+ BOXNAVWP = 19,
+ BOXAIRMODE = 20,
+ BOXHOMERESET = 21,
+ BOXGCSNAV = 22,
+ BOXSURFACE = 24,
+ BOXFLAPERON = 25,
+ BOXTURNASSIST = 26,
+ BOXAUTOTRIM = 27,
+ BOXAUTOTUNE = 28,
+ BOXCAMERA1 = 29,
+ BOXCAMERA2 = 30,
+ BOXCAMERA3 = 31,
+ BOXOSDALT1 = 32,
+ BOXOSDALT2 = 33,
+ BOXOSDALT3 = 34,
+ BOXNAVCOURSEHOLD = 35,
+ BOXBRAKING = 36,
+ BOXUSER1 = 37,
+ BOXUSER2 = 38,
+ BOXFPVANGLEMIX = 39,
+ BOXLOITERDIRCHN = 40,
+ BOXMSPRCOVERRIDE = 41,
+ BOXPREARM = 42,
+ BOXTURTLE = 43,
+ BOXNAVCRUISE = 44,
+ BOXAUTOLEVEL = 45,
+ BOXPLANWPMISSION = 46,
+ BOXSOARING = 47,
+ BOXUSER3 = 48,
+ BOXUSER4 = 49,
+ BOXCHANGEMISSION = 50,
+ BOXBEEPERMUTE = 51,
+ BOXMULTIFUNCTION = 52,
+ BOXMIXERPROFILE = 53,
+ BOXMIXERTRANSITION = 54,
+ BOXANGLEHOLD = 55,
+ BOXGIMBALTLOCK = 56,
+ BOXGIMBALRLOCK = 57,
+ BOXGIMBALCENTER = 58,
+ BOXGIMBALHTRK = 59,
+ CHECKBOX_ITEM_COUNT
+} boxId_e;
+
+// ../../../src/main/fc/rc_modes.h
+typedef enum {
+ MODE_OPERATOR_OR,
+ MODE_OPERATOR_AND
+} modeActivationOperator_e;
+
+// ../../../src/main/fc/cli.c
+typedef enum {
+ DUMP_MASTER = (1 << 0),
+ DUMP_CONTROL_PROFILE = (1 << 1),
+ DUMP_BATTERY_PROFILE = (1 << 2),
+ DUMP_MIXER_PROFILE = (1 << 3),
+ DUMP_ALL = (1 << 4),
+ DO_DIFF = (1 << 5),
+ SHOW_DEFAULTS = (1 << 6),
+ HIDE_UNUSED = (1 << 7)
+} dumpFlags_e;
+
+// ../../../src/main/fc/settings.h
+typedef enum {
+
+ VAR_UINT8 = (0 << SETTING_TYPE_OFFSET),
+ VAR_INT8 = (1 << SETTING_TYPE_OFFSET),
+ VAR_UINT16 = (2 << SETTING_TYPE_OFFSET),
+ VAR_INT16 = (3 << SETTING_TYPE_OFFSET),
+ VAR_UINT32 = (4 << SETTING_TYPE_OFFSET),
+ VAR_FLOAT = (5 << SETTING_TYPE_OFFSET),
+ VAR_STRING = (6 << SETTING_TYPE_OFFSET)
+} setting_type_e;
+
+// ../../../src/main/fc/settings.h
+typedef enum {
+
+ MASTER_VALUE = (0 << SETTING_SECTION_OFFSET),
+ PROFILE_VALUE = (1 << SETTING_SECTION_OFFSET),
+ CONTROL_VALUE = (2 << SETTING_SECTION_OFFSET),
+ BATTERY_CONFIG_VALUE = (3 << SETTING_SECTION_OFFSET),
+ MIXER_CONFIG_VALUE = (4 << SETTING_SECTION_OFFSET),
+ EZ_TUNE_VALUE = (5 << SETTING_SECTION_OFFSET)
+} setting_section_e;
+
+// ../../../src/main/fc/settings.h
+typedef enum {
+
+ MODE_DIRECT = (0 << SETTING_MODE_OFFSET),
+ MODE_LOOKUP = (1 << SETTING_MODE_OFFSET),
+} setting_mode_e;
+
+// ../../../src/main/fc/fc_init.h
+typedef enum {
+ SYSTEM_STATE_INITIALISING = 0,
+ SYSTEM_STATE_CONFIG_LOADED = (1 << 0),
+ SYSTEM_STATE_SENSORS_READY = (1 << 1),
+ SYSTEM_STATE_MOTORS_READY = (1 << 2),
+ SYSTEM_STATE_TRANSPONDER_ENABLED = (1 << 3),
+ SYSTEM_STATE_READY = (1 << 7)
+} systemState_e;
+
+// ../../../src/main/fc/fc_msp.c
+typedef enum {
+ MSP_SDCARD_STATE_NOT_PRESENT = 0,
+ MSP_SDCARD_STATE_FATAL = 1,
+ MSP_SDCARD_STATE_CARD_INIT = 2,
+ MSP_SDCARD_STATE_FS_INIT = 3,
+ MSP_SDCARD_STATE_READY = 4
+} mspSDCardState_e;
+
+// ../../../src/main/fc/fc_msp.c
+typedef enum {
+ MSP_SDCARD_FLAG_SUPPORTTED = 1
+} mspSDCardFlags_e;
+
+// ../../../src/main/fc/fc_msp.c
+typedef enum {
+ MSP_FLASHFS_BIT_READY = 1,
+ MSP_FLASHFS_BIT_SUPPORTED = 2
+} mspFlashfsFlags_e;
+
+// ../../../src/main/fc/fc_msp.c
+typedef enum {
+ MSP_PASSTHROUGH_SERIAL_ID = 0xFD,
+ MSP_PASSTHROUGH_SERIAL_FUNCTION_ID = 0xFE,
+ MSP_PASSTHROUGH_ESC_4WAY = 0xFF,
+ } mspPassthroughType_e;
+
+// ../../../src/main/fc/rc_controls.h
+typedef enum rc_alias {
+ ROLL = 0,
+ PITCH,
+ YAW,
+ THROTTLE,
+ AUX1,
+ AUX2,
+ AUX3,
+ AUX4,
+ AUX5,
+ AUX6,
+ AUX7,
+ AUX8,
+ AUX9,
+ AUX10,
+ AUX11,
+ AUX12,
+ AUX13,
+ AUX14,
+#ifdef USE_34CHANNELS
+ AUX15,
+ AUX16,
+ AUX17,
+ AUX18,
+ AUX19,
+ AUX20,
+ AUX21,
+ AUX22,
+ AUX23,
+ AUX24,
+ AUX25,
+ AUX26,
+ AUX27,
+ AUX28,
+ AUX29,
+ AUX30,
+#endif
+} rc_alias_e;
+
+// ../../../src/main/fc/rc_controls.h
+typedef enum {
+ THROTTLE_LOW = 0,
+ THROTTLE_HIGH
+} throttleStatus_e;
+
+// ../../../src/main/fc/rc_controls.h
+typedef enum {
+ THROTTLE_STATUS_TYPE_RC = 0,
+ THROTTLE_STATUS_TYPE_COMMAND
+} throttleStatusType_e;
+
+// ../../../src/main/fc/rc_controls.h
+typedef enum {
+ NOT_CENTERED = 0,
+ CENTERED
+} rollPitchStatus_e;
+
+// ../../../src/main/fc/rc_controls.h
+typedef enum {
+ STICK_CENTER = 0,
+ THROTTLE_THRESHOLD,
+ STICK_CENTER_ONCE
+} airmodeHandlingType_e;
+
+// ../../../src/main/fc/rc_controls.h
+typedef enum {
+ ROL_LO = (1 << (2 * ROLL)),
+ ROL_CE = (3 << (2 * ROLL)),
+ ROL_HI = (2 << (2 * ROLL)),
+
+ PIT_LO = (1 << (2 * PITCH)),
+ PIT_CE = (3 << (2 * PITCH)),
+ PIT_HI = (2 << (2 * PITCH)),
+
+ YAW_LO = (1 << (2 * YAW)),
+ YAW_CE = (3 << (2 * YAW)),
+ YAW_HI = (2 << (2 * YAW)),
+
+ THR_LO = (1 << (2 * THROTTLE)),
+ THR_CE = (3 << (2 * THROTTLE)),
+ THR_HI = (2 << (2 * THROTTLE))
+} stickPositions_e;
+
+// ../../../src/main/fc/rc_controls.h
+enum rc_alias {
+ ROLL = 0,
+ PITCH,
+ YAW,
+ THROTTLE,
+ AUX1,
+ AUX2,
+ AUX3,
+ AUX4,
+ AUX5,
+ AUX6,
+ AUX7,
+ AUX8,
+ AUX9,
+ AUX10,
+ AUX11,
+ AUX12,
+ AUX13,
+ AUX14,
+#ifdef USE_34CHANNELS
+ AUX15,
+ AUX16,
+ AUX17,
+ AUX18,
+ AUX19,
+ AUX20,
+ AUX21,
+ AUX22,
+ AUX23,
+ AUX24,
+ AUX25,
+ AUX26,
+ AUX27,
+ AUX28,
+ AUX29,
+ AUX30,
+#endif
+} rc_alias_e;
+typedef enum rc_alias rc_alias;
+
+// ../../../src/main/fc/multifunction.h
+typedef enum {
+ MF_SUSPEND_SAFEHOMES = (1 << 0),
+ MF_SUSPEND_TRACKBACK = (1 << 1),
+ MF_TURTLE_MODE = (1 << 2),
+} multiFunctionFlags_e;
+
+// ../../../src/main/fc/multifunction.h
+typedef enum {
+ MULTI_FUNC_NONE,
+ MULTI_FUNC_1,
+ MULTI_FUNC_2,
+ MULTI_FUNC_3,
+ MULTI_FUNC_4,
+ MULTI_FUNC_5,
+ MULTI_FUNC_END,
+} multi_function_e;
+
+// ../../../src/main/fc/rc_adjustments.h
+typedef enum {
+ ADJUSTMENT_NONE = 0,
+ ADJUSTMENT_RC_RATE = 1,
+ ADJUSTMENT_RC_EXPO = 2,
+ ADJUSTMENT_THROTTLE_EXPO = 3,
+ ADJUSTMENT_PITCH_ROLL_RATE = 4,
+ ADJUSTMENT_YAW_RATE = 5,
+ ADJUSTMENT_PITCH_ROLL_P = 6,
+ ADJUSTMENT_PITCH_ROLL_I = 7,
+ ADJUSTMENT_PITCH_ROLL_D = 8,
+ ADJUSTMENT_PITCH_ROLL_FF = 9,
+ ADJUSTMENT_PITCH_P = 10,
+ ADJUSTMENT_PITCH_I = 11,
+ ADJUSTMENT_PITCH_D = 12,
+ ADJUSTMENT_PITCH_FF = 13,
+ ADJUSTMENT_ROLL_P = 14,
+ ADJUSTMENT_ROLL_I = 15,
+ ADJUSTMENT_ROLL_D = 16,
+ ADJUSTMENT_ROLL_FF = 17,
+ ADJUSTMENT_YAW_P = 18,
+ ADJUSTMENT_YAW_I = 19,
+ ADJUSTMENT_YAW_D = 20,
+ ADJUSTMENT_YAW_FF = 21,
+ ADJUSTMENT_RATE_PROFILE = 22,
+ ADJUSTMENT_PITCH_RATE = 23,
+ ADJUSTMENT_ROLL_RATE = 24,
+ ADJUSTMENT_RC_YAW_EXPO = 25,
+ ADJUSTMENT_MANUAL_RC_EXPO = 26,
+ ADJUSTMENT_MANUAL_RC_YAW_EXPO = 27,
+ ADJUSTMENT_MANUAL_PITCH_ROLL_RATE = 28,
+ ADJUSTMENT_MANUAL_ROLL_RATE = 29,
+ ADJUSTMENT_MANUAL_PITCH_RATE = 30,
+ ADJUSTMENT_MANUAL_YAW_RATE = 31,
+ ADJUSTMENT_NAV_FW_CRUISE_THR = 32,
+ ADJUSTMENT_NAV_FW_PITCH2THR = 33,
+ ADJUSTMENT_ROLL_BOARD_ALIGNMENT = 34,
+ ADJUSTMENT_PITCH_BOARD_ALIGNMENT = 35,
+ ADJUSTMENT_LEVEL_P = 36,
+ ADJUSTMENT_LEVEL_I = 37,
+ ADJUSTMENT_LEVEL_D = 38,
+ ADJUSTMENT_POS_XY_P = 39,
+ ADJUSTMENT_POS_XY_I = 40,
+ ADJUSTMENT_POS_XY_D = 41,
+ ADJUSTMENT_POS_Z_P = 42,
+ ADJUSTMENT_POS_Z_I = 43,
+ ADJUSTMENT_POS_Z_D = 44,
+ ADJUSTMENT_HEADING_P = 45,
+ ADJUSTMENT_VEL_XY_P = 46,
+ ADJUSTMENT_VEL_XY_I = 47,
+ ADJUSTMENT_VEL_XY_D = 48,
+ ADJUSTMENT_VEL_Z_P = 49,
+ ADJUSTMENT_VEL_Z_I = 50,
+ ADJUSTMENT_VEL_Z_D = 51,
+ ADJUSTMENT_FW_MIN_THROTTLE_DOWN_PITCH_ANGLE = 52,
+ ADJUSTMENT_VTX_POWER_LEVEL = 53,
+ ADJUSTMENT_TPA = 54,
+ ADJUSTMENT_TPA_BREAKPOINT = 55,
+ ADJUSTMENT_NAV_FW_CONTROL_SMOOTHNESS = 56,
+ ADJUSTMENT_FW_TPA_TIME_CONSTANT = 57,
+ ADJUSTMENT_FW_LEVEL_TRIM = 58,
+ ADJUSTMENT_NAV_WP_MULTI_MISSION_INDEX = 59,
+ ADJUSTMENT_NAV_FW_ALT_CONTROL_RESPONSE = 60,
+ ADJUSTMENT_FUNCTION_COUNT
+} adjustmentFunction_e;
+
+// ../../../src/main/fc/rc_adjustments.h
+typedef enum {
+ ADJUSTMENT_MODE_STEP,
+ ADJUSTMENT_MODE_SELECT
+} adjustmentMode_e;
+
+// ../../../src/main/fc/config.h
+typedef enum {
+ FEATURE_THR_VBAT_COMP = 1 << 0,
+ FEATURE_VBAT = 1 << 1,
+ FEATURE_TX_PROF_SEL = 1 << 2,
+ FEATURE_BAT_PROFILE_AUTOSWITCH = 1 << 3,
+ FEATURE_GEOZONE = 1 << 4,
+ FEATURE_UNUSED_1 = 1 << 5,
+ FEATURE_SOFTSERIAL = 1 << 6,
+ FEATURE_GPS = 1 << 7,
+ FEATURE_UNUSED_3 = 1 << 8,
+ FEATURE_UNUSED_4 = 1 << 9,
+ FEATURE_TELEMETRY = 1 << 10,
+ FEATURE_CURRENT_METER = 1 << 11,
+ FEATURE_REVERSIBLE_MOTORS = 1 << 12,
+ FEATURE_UNUSED_5 = 1 << 13,
+ FEATURE_UNUSED_6 = 1 << 14,
+ FEATURE_RSSI_ADC = 1 << 15,
+ FEATURE_LED_STRIP = 1 << 16,
+ FEATURE_DASHBOARD = 1 << 17,
+ FEATURE_UNUSED_7 = 1 << 18,
+ FEATURE_BLACKBOX = 1 << 19,
+ FEATURE_UNUSED_10 = 1 << 20,
+ FEATURE_TRANSPONDER = 1 << 21,
+ FEATURE_AIRMODE = 1 << 22,
+ FEATURE_SUPEREXPO_RATES = 1 << 23,
+ FEATURE_VTX = 1 << 24,
+ FEATURE_UNUSED_8 = 1 << 25,
+ FEATURE_UNUSED_9 = 1 << 26,
+ FEATURE_UNUSED_11 = 1 << 27,
+ FEATURE_PWM_OUTPUT_ENABLE = 1 << 28,
+ FEATURE_OSD = 1 << 29,
+ FEATURE_FW_LAUNCH = 1 << 30,
+ FEATURE_FW_AUTOTRIM = 1U << 31,
+} features_e;
+
+// ../../../src/main/fc/runtime_config.h
+typedef enum {
+ ARMED = (1 << 2),
+ WAS_EVER_ARMED = (1 << 3),
+ SIMULATOR_MODE_HITL = (1 << 4),
+ SIMULATOR_MODE_SITL = (1 << 5),
+ ARMING_DISABLED_GEOZONE = (1 << 6),
+ ARMING_DISABLED_FAILSAFE_SYSTEM = (1 << 7),
+ ARMING_DISABLED_NOT_LEVEL = (1 << 8),
+ ARMING_DISABLED_SENSORS_CALIBRATING = (1 << 9),
+ ARMING_DISABLED_SYSTEM_OVERLOADED = (1 << 10),
+ ARMING_DISABLED_NAVIGATION_UNSAFE = (1 << 11),
+ ARMING_DISABLED_COMPASS_NOT_CALIBRATED = (1 << 12),
+ ARMING_DISABLED_ACCELEROMETER_NOT_CALIBRATED = (1 << 13),
+ ARMING_DISABLED_ARM_SWITCH = (1 << 14),
+ ARMING_DISABLED_HARDWARE_FAILURE = (1 << 15),
+ ARMING_DISABLED_BOXFAILSAFE = (1 << 16),
+
+ ARMING_DISABLED_RC_LINK = (1 << 18),
+ ARMING_DISABLED_THROTTLE = (1 << 19),
+ ARMING_DISABLED_CLI = (1 << 20),
+ ARMING_DISABLED_CMS_MENU = (1 << 21),
+ ARMING_DISABLED_OSD_MENU = (1 << 22),
+ ARMING_DISABLED_ROLLPITCH_NOT_CENTERED = (1 << 23),
+ ARMING_DISABLED_SERVO_AUTOTRIM = (1 << 24),
+ ARMING_DISABLED_OOM = (1 << 25),
+ ARMING_DISABLED_INVALID_SETTING = (1 << 26),
+ ARMING_DISABLED_PWM_OUTPUT_ERROR = (1 << 27),
+ ARMING_DISABLED_NO_PREARM = (1 << 28),
+ ARMING_DISABLED_DSHOT_BEEPER = (1 << 29),
+ ARMING_DISABLED_LANDING_DETECTED = (1 << 30),
+
+ ARMING_DISABLED_ALL_FLAGS = (ARMING_DISABLED_GEOZONE | ARMING_DISABLED_FAILSAFE_SYSTEM | ARMING_DISABLED_NOT_LEVEL |
+ ARMING_DISABLED_SENSORS_CALIBRATING | ARMING_DISABLED_SYSTEM_OVERLOADED | ARMING_DISABLED_NAVIGATION_UNSAFE |
+ ARMING_DISABLED_COMPASS_NOT_CALIBRATED | ARMING_DISABLED_ACCELEROMETER_NOT_CALIBRATED |
+ ARMING_DISABLED_ARM_SWITCH | ARMING_DISABLED_HARDWARE_FAILURE | ARMING_DISABLED_BOXFAILSAFE |
+ ARMING_DISABLED_RC_LINK | ARMING_DISABLED_THROTTLE | ARMING_DISABLED_CLI |
+ ARMING_DISABLED_CMS_MENU | ARMING_DISABLED_OSD_MENU | ARMING_DISABLED_ROLLPITCH_NOT_CENTERED |
+ ARMING_DISABLED_SERVO_AUTOTRIM | ARMING_DISABLED_OOM | ARMING_DISABLED_INVALID_SETTING |
+ ARMING_DISABLED_PWM_OUTPUT_ERROR | ARMING_DISABLED_NO_PREARM | ARMING_DISABLED_DSHOT_BEEPER |
+ ARMING_DISABLED_LANDING_DETECTED),
+} armingFlag_e;
+
+// ../../../src/main/fc/runtime_config.h
+typedef enum {
+ ANGLE_MODE = (1 << 0),
+ HORIZON_MODE = (1 << 1),
+ HEADING_MODE = (1 << 2),
+ NAV_ALTHOLD_MODE = (1 << 3),
+ NAV_RTH_MODE = (1 << 4),
+ NAV_POSHOLD_MODE = (1 << 5),
+ HEADFREE_MODE = (1 << 6),
+ NAV_LAUNCH_MODE = (1 << 7),
+ MANUAL_MODE = (1 << 8),
+ FAILSAFE_MODE = (1 << 9),
+ AUTO_TUNE = (1 << 10),
+ NAV_WP_MODE = (1 << 11),
+ NAV_COURSE_HOLD_MODE = (1 << 12),
+ FLAPERON = (1 << 13),
+ TURN_ASSISTANT = (1 << 14),
+ TURTLE_MODE = (1 << 15),
+ SOARING_MODE = (1 << 16),
+ ANGLEHOLD_MODE = (1 << 17),
+ NAV_FW_AUTOLAND = (1 << 18),
+ NAV_SEND_TO = (1 << 19),
+} flightModeFlags_e;
+
+// ../../../src/main/fc/runtime_config.h
+typedef enum {
+ GPS_FIX_HOME = (1 << 0),
+ GPS_FIX = (1 << 1),
+ CALIBRATE_MAG = (1 << 2),
+ SMALL_ANGLE = (1 << 3),
+ FIXED_WING_LEGACY = (1 << 4),
+ ANTI_WINDUP = (1 << 5),
+ FLAPERON_AVAILABLE = (1 << 6),
+ NAV_MOTOR_STOP_OR_IDLE = (1 << 7),
+ COMPASS_CALIBRATED = (1 << 8),
+ ACCELEROMETER_CALIBRATED = (1 << 9),
+#ifdef USE_GPS_FIX_ESTIMATION
+ GPS_ESTIMATED_FIX = (1 << 10),
+#endif
+ NAV_CRUISE_BRAKING = (1 << 11),
+ NAV_CRUISE_BRAKING_BOOST = (1 << 12),
+ NAV_CRUISE_BRAKING_LOCKED = (1 << 13),
+ NAV_EXTRA_ARMING_SAFETY_BYPASSED = (1 << 14),
+ AIRMODE_ACTIVE = (1 << 15),
+ ESC_SENSOR_ENABLED = (1 << 16),
+ AIRPLANE = (1 << 17),
+ MULTIROTOR = (1 << 18),
+ ROVER = (1 << 19),
+ BOAT = (1 << 20),
+ ALTITUDE_CONTROL = (1 << 21),
+ MOVE_FORWARD_ONLY = (1 << 22),
+ SET_REVERSIBLE_MOTORS_FORWARD = (1 << 23),
+ FW_HEADING_USE_YAW = (1 << 24),
+ ANTI_WINDUP_DEACTIVATED = (1 << 25),
+ LANDING_DETECTED = (1 << 26),
+ IN_FLIGHT_EMERG_REARM = (1 << 27),
+ TAILSITTER = (1 << 28),
+} stateFlags_t;
+
+// ../../../src/main/fc/runtime_config.h
+typedef enum {
+ FLM_MANUAL,
+ FLM_ACRO,
+ FLM_ACRO_AIR,
+ FLM_ANGLE,
+ FLM_HORIZON,
+ FLM_ALTITUDE_HOLD,
+ FLM_POSITION_HOLD,
+ FLM_RTH,
+ FLM_MISSION,
+ FLM_COURSE_HOLD,
+ FLM_CRUISE,
+ FLM_LAUNCH,
+ FLM_FAILSAFE,
+ FLM_ANGLEHOLD,
+ FLM_COUNT
+} flightModeForTelemetry_e;
+
+// ../../../src/main/fc/runtime_config.h
+typedef enum {
+ HITL_RESET_FLAGS = (0 << 0),
+ HITL_ENABLE = (1 << 0),
+ HITL_SIMULATE_BATTERY = (1 << 1),
+ HITL_MUTE_BEEPER = (1 << 2),
+ HITL_USE_IMU = (1 << 3),
+ HITL_HAS_NEW_GPS_DATA = (1 << 4),
+ HITL_EXT_BATTERY_VOLTAGE = (1 << 5),
+ HITL_AIRSPEED = (1 << 6),
+ HITL_EXTENDED_FLAGS = (1 << 7),
+ HITL_GPS_TIMEOUT = (1 << 8),
+ HITL_PITOT_FAILURE = (1 << 9)
+} simulatorFlags_t;
+
+// ../../../src/main/drivers/timer.h
+typedef enum {
+ TIM_USE_ANY = 0,
+ TIM_USE_PPM = (1 << 0),
+ TIM_USE_PWM = (1 << 1),
+ TIM_USE_MOTOR = (1 << 2),
+ TIM_USE_SERVO = (1 << 3),
+ TIM_USE_MC_CHNFW = (1 << 4),
+
+
+ TIM_USE_LED = (1 << 24),
+ TIM_USE_BEEPER = (1 << 25),
+} timerUsageFlag_e;
+
+// ../../../src/main/drivers/timer.h
+typedef enum {
+ TCH_DMA_IDLE = 0,
+ TCH_DMA_READY,
+ TCH_DMA_ACTIVE,
+} tchDmaState_e;
+
+// ../../../src/main/drivers/timer.h
+typedef enum {
+ TYPE_FREE,
+ TYPE_PWMINPUT,
+ TYPE_PPMINPUT,
+ TYPE_PWMOUTPUT_MOTOR,
+ TYPE_PWMOUTPUT_FAST,
+ TYPE_PWMOUTPUT_SERVO,
+ TYPE_SOFTSERIAL_RX,
+ TYPE_SOFTSERIAL_TX,
+ TYPE_SOFTSERIAL_RXTX,
+ TYPE_SOFTSERIAL_AUXTIMER,
+ TYPE_ADC,
+ TYPE_SERIAL_RX,
+ TYPE_SERIAL_TX,
+ TYPE_SERIAL_RXTX,
+ TYPE_TIMER
+} channelType_t;
+
+// ../../../src/main/drivers/uart_inverter.h
+typedef enum {
+ UART_INVERTER_LINE_NONE = 0,
+ UART_INVERTER_LINE_RX = 1 << 0,
+ UART_INVERTER_LINE_TX = 1 << 1,
+} uartInverterLine_e;
+
+// ../../../src/main/drivers/serial_softserial.c
+typedef enum {
+ TIMER_MODE_SINGLE,
+ TIMER_MODE_DUAL,
+} timerMode_e;
+
+// ../../../src/main/drivers/display.h
+typedef enum {
+ DISPLAY_TRANSACTION_OPT_NONE = 0,
+ DISPLAY_TRANSACTION_OPT_PROFILED = 1 << 0,
+ DISPLAY_TRANSACTION_OPT_RESET_DRAWING = 1 << 1,
+} displayTransactionOption_e;
+
+// ../../../src/main/drivers/vtx_common.h
+typedef enum {
+ VTXDEV_UNSUPPORTED = 0,
+ VTXDEV_RTC6705 = 1,
+
+ VTXDEV_SMARTAUDIO = 3,
+ VTXDEV_TRAMP = 4,
+ VTXDEV_FFPV = 5,
+ VTXDEV_MSP = 6,
+ VTXDEV_UNKNOWN = 0xFF,
+} vtxDevType_e;
+
+// ../../../src/main/drivers/vtx_common.h
+typedef enum {
+ FREQUENCYGROUP_5G8 = 0,
+ FREQUENCYGROUP_2G4 = 1,
+ FREQUENCYGROUP_1G3 = 2,
+} vtxFrequencyGroups_e;
+
+// ../../../src/main/drivers/sensor.h
+typedef enum {
+ ALIGN_DEFAULT = 0,
+ CW0_DEG = 1,
+ CW90_DEG = 2,
+ CW180_DEG = 3,
+ CW270_DEG = 4,
+ CW0_DEG_FLIP = 5,
+ CW90_DEG_FLIP = 6,
+ CW180_DEG_FLIP = 7,
+ CW270_DEG_FLIP = 8
+} sensor_align_e;
+
+// ../../../src/main/drivers/headtracker_common.h
+typedef enum {
+ HEADTRACKER_NONE = 0,
+ HEADTRACKER_SERIAL = 1,
+ HEADTRACKER_MSP = 2,
+ HEADTRACKER_UNKNOWN = 0xFF
+} headTrackerDevType_e;
+
+// ../../../src/main/drivers/adc.h
+typedef enum {
+ ADC_BATTERY = 0,
+ ADC_RSSI = 1,
+ ADC_CURRENT = 2,
+ ADC_AIRSPEED = 3,
+ ADC_FUNCTION_COUNT
+} adcFunction_e;
+
+// ../../../src/main/drivers/adc.h
+typedef enum {
+ ADC_CHN_NONE = 0,
+ ADC_CHN_1 = 1,
+ ADC_CHN_2,
+ ADC_CHN_3,
+ ADC_CHN_4,
+ ADC_CHN_5,
+ ADC_CHN_6,
+ ADC_CHN_MAX = ADC_CHN_6,
+ ADC_CHN_COUNT
+} adcChannel_e;
+
+// ../../../src/main/drivers/resource.h
+typedef enum {
+ OWNER_FREE = 0,
+ OWNER_PWMIO,
+ OWNER_MOTOR,
+ OWNER_SERVO,
+ OWNER_SOFTSERIAL,
+ OWNER_ADC,
+ OWNER_SERIAL,
+ OWNER_TIMER,
+ OWNER_RANGEFINDER,
+ OWNER_SYSTEM,
+ OWNER_SPI,
+ OWNER_QUADSPI,
+ OWNER_I2C,
+ OWNER_SDCARD,
+ OWNER_FLASH,
+ OWNER_USB,
+ OWNER_BEEPER,
+ OWNER_OSD,
+ OWNER_BARO,
+ OWNER_MPU,
+ OWNER_INVERTER,
+ OWNER_LED_STRIP,
+ OWNER_LED,
+ OWNER_RX,
+ OWNER_TX,
+ OWNER_VTX,
+ OWNER_SPI_PREINIT,
+ OWNER_COMPASS,
+ OWNER_TEMPERATURE,
+ OWNER_1WIRE,
+ OWNER_AIRSPEED,
+ OWNER_OLED_DISPLAY,
+ OWNER_PINIO,
+ OWNER_IRLOCK,
+ OWNER_DRONECAN,
+ OWNER_TOTAL_COUNT
+} resourceOwner_e;
+
+// ../../../src/main/drivers/resource.h
+typedef enum {
+ RESOURCE_NONE = 0,
+ RESOURCE_INPUT, RESOURCE_OUTPUT, RESOURCE_IO,
+ RESOURCE_TIMER,
+ RESOURCE_UART_TX, RESOURCE_UART_RX, RESOURCE_UART_TXRX,
+ RESOURCE_EXTI,
+ RESOURCE_I2C_SCL, RESOURCE_I2C_SDA,
+ RESOURCE_SPI_SCK, RESOURCE_SPI_MOSI, RESOURCE_SPI_MISO, RESOURCE_SPI_CS,
+ RESOURCE_QUADSPI_CLK, RESOURCE_QUADSPI_BK1IO0, RESOURCE_QUADSPI_BK1IO1,
+ RESOURCE_QUADSPI_BK1IO2, RESOURCE_QUADSPI_BK1IO3, RESOURCE_QUADSPI_BK1CS,
+ RESOURCE_QUADSPI_BK2IO0, RESOURCE_QUADSPI_BK2IO1, RESOURCE_QUADSPI_BK2IO2,
+ RESOURCE_QUADSPI_BK2IO3, RESOURCE_QUADSPI_BK2CS,
+ RESOURCE_ADC_CH1, RESOURCE_ADC_CH2, RESOURCE_ADC_CH3, RESOURCE_ADC_CH4,
+ RESOURCE_RX_CE,
+ RESOURCE_CAN_TX, RESOURCE_CAN_RX, RESOURCE_CAN_STANDBY,
+ RESOURCE_TOTAL_COUNT
+} resourceType_e;
+
+// ../../../src/main/drivers/display_canvas.h
+typedef enum {
+ DISPLAY_CANVAS_BITMAP_OPT_INVERT_COLORS = 1 << 0,
+ DISPLAY_CANVAS_BITMAP_OPT_SOLID_BACKGROUND = 1 << 1,
+ DISPLAY_CANVAS_BITMAP_OPT_ERASE_TRANSPARENT = 1 << 2,
+} displayCanvasBitmapOption_t;
+
+// ../../../src/main/drivers/display_canvas.h
+typedef enum {
+ DISPLAY_CANVAS_COLOR_BLACK = 0,
+ DISPLAY_CANVAS_COLOR_TRANSPARENT = 1,
+ DISPLAY_CANVAS_COLOR_WHITE = 2,
+ DISPLAY_CANVAS_COLOR_GRAY = 3,
+} displayCanvasColor_e;
+
+// ../../../src/main/drivers/display_canvas.h
+typedef enum {
+ DISPLAY_CANVAS_OUTLINE_TYPE_NONE = 0,
+ DISPLAY_CANVAS_OUTLINE_TYPE_TOP = 1 << 0,
+ DISPLAY_CANVAS_OUTLINE_TYPE_RIGHT = 1 << 1,
+ DISPLAY_CANVAS_OUTLINE_TYPE_BOTTOM = 1 << 2,
+ DISPLAY_CANVAS_OUTLINE_TYPE_LEFT = 1 << 3,
+} displayCanvasOutlineType_e;
+
+// ../../../src/main/drivers/max7456.h
+enum VIDEO_TYPES { AUTO = 0, PAL, NTSC };
+typedef enum VIDEO_TYPES VIDEO_TYPES;
+
+// ../../../src/main/drivers/serial.h
+typedef enum portMode_t {
+ MODE_RX = 1 << 0,
+ MODE_TX = 1 << 1,
+ MODE_RXTX = MODE_RX | MODE_TX
+} portMode_t;
+
+// ../../../src/main/drivers/serial.h
+typedef enum portOptions_t {
+ SERIAL_NOT_INVERTED = 0 << 0,
+ SERIAL_INVERTED = 1 << 0,
+ SERIAL_STOPBITS_1 = 0 << 1,
+ SERIAL_STOPBITS_2 = 1 << 1,
+ SERIAL_PARITY_NO = 0 << 2,
+ SERIAL_PARITY_EVEN = 1 << 2,
+ SERIAL_UNIDIR = 0 << 3,
+ SERIAL_BIDIR = 1 << 3,
+
+
+ SERIAL_BIDIR_OD = 0 << 4,
+ SERIAL_BIDIR_PP = 1 << 4,
+ SERIAL_BIDIR_NOPULL = 1 << 5,
+ SERIAL_BIDIR_UP = 0 << 5,
+
+ SERIAL_LONGSTOP = 0 << 6,
+ SERIAL_SHORTSTOP = 1 << 6,
+} portOptions_t;
+
+// ../../../src/main/drivers/serial.h
+enum portMode_t {
+ MODE_RX = 1 << 0,
+ MODE_TX = 1 << 1,
+ MODE_RXTX = MODE_RX | MODE_TX
+} portMode_t;
+typedef enum portMode_t portMode_t;
+
+// ../../../src/main/drivers/serial.h
+enum portOptions_t {
+ SERIAL_NOT_INVERTED = 0 << 0,
+ SERIAL_INVERTED = 1 << 0,
+ SERIAL_STOPBITS_1 = 0 << 1,
+ SERIAL_STOPBITS_2 = 1 << 1,
+ SERIAL_PARITY_NO = 0 << 2,
+ SERIAL_PARITY_EVEN = 1 << 2,
+ SERIAL_UNIDIR = 0 << 3,
+ SERIAL_BIDIR = 1 << 3,
+
+
+ SERIAL_BIDIR_OD = 0 << 4,
+ SERIAL_BIDIR_PP = 1 << 4,
+ SERIAL_BIDIR_NOPULL = 1 << 5,
+ SERIAL_BIDIR_UP = 0 << 5,
+
+ SERIAL_LONGSTOP = 0 << 6,
+ SERIAL_SHORTSTOP = 1 << 6,
+} portOptions_t;
+typedef enum portOptions_t portOptions_t;
+
+// ../../../src/main/drivers/light_ws2811strip.h
+typedef enum {
+ LED_PIN_PWM_MODE_SHARED_LOW = 0,
+ LED_PIN_PWM_MODE_SHARED_HIGH = 1,
+ LED_PIN_PWM_MODE_LOW = 2,
+ LED_PIN_PWM_MODE_HIGH = 3
+} led_pin_pwm_mode_e;
+
+// ../../../src/main/drivers/pwm_output.h
+typedef enum {
+ DSHOT_CMD_SPIN_DIRECTION_NORMAL = 20,
+ DSHOT_CMD_SPIN_DIRECTION_REVERSED = 21,
+} dshotCommands_e;
+
+// ../../../src/main/drivers/bus_i2c_stm32f40x.c
+typedef enum {
+ I2C_STATE_STOPPED = 0,
+ I2C_STATE_STOPPING,
+ I2C_STATE_STARTING,
+ I2C_STATE_STARTING_WAIT,
+
+ I2C_STATE_R_ADDR,
+ I2C_STATE_R_ADDR_WAIT,
+ I2C_STATE_R_REGISTER,
+ I2C_STATE_R_REGISTER_WAIT,
+ I2C_STATE_R_RESTARTING,
+ I2C_STATE_R_RESTARTING_WAIT,
+ I2C_STATE_R_RESTART_ADDR,
+ I2C_STATE_R_RESTART_ADDR_WAIT,
+ I2C_STATE_R_TRANSFER_EQ1,
+ I2C_STATE_R_TRANSFER_EQ2,
+ I2C_STATE_R_TRANSFER_GE2,
+
+ I2C_STATE_W_ADDR,
+ I2C_STATE_W_ADDR_WAIT,
+ I2C_STATE_W_REGISTER,
+ I2C_STATE_W_TRANSFER_WAIT,
+ I2C_STATE_W_TRANSFER,
+
+ I2C_STATE_NACK,
+ I2C_STATE_BUS_ERROR,
+} i2cState_t;
+
+// ../../../src/main/drivers/bus_i2c_stm32f40x.c
+typedef enum {
+ I2C_TXN_READ,
+ I2C_TXN_WRITE
+} i2cTransferDirection_t;
+
+// ../../../src/main/drivers/bus_i2c.h
+typedef enum {
+ I2C_SPEED_100KHZ = 2,
+ I2C_SPEED_200KHZ = 3,
+ I2C_SPEED_400KHZ = 0,
+ I2C_SPEED_800KHZ = 1,
+} I2CSpeed;
+
+// ../../../src/main/drivers/bus_i2c.h
+typedef enum I2CDevice {
+ I2CINVALID = -1,
+ I2CDEV_EMULATED = -1,
+ I2CDEV_1 = 0,
+ I2CDEV_2,
+ I2CDEV_3,
+#ifdef USE_I2C_DEVICE_4
+ I2CDEV_4,
+#endif
+ I2CDEV_COUNT
+} I2CDevice;
+
+// ../../../src/main/drivers/bus_i2c.h
+enum I2CDevice {
+ I2CINVALID = -1,
+ I2CDEV_EMULATED = -1,
+ I2CDEV_1 = 0,
+ I2CDEV_2,
+ I2CDEV_3,
+#ifdef USE_I2C_DEVICE_4
+ I2CDEV_4,
+#endif
+ I2CDEV_COUNT
+} I2CDevice;
+typedef enum I2CDevice I2CDevice;
+
+// ../../../src/main/drivers/i2c_application.h
+typedef enum
+{
+ I2C_MEM_ADDR_WIDIH_8 = 0x01,
+ I2C_MEM_ADDR_WIDIH_16 = 0x02,
+} i2c_mem_address_width_type;
+
+// ../../../src/main/drivers/i2c_application.h
+typedef enum
+{
+ I2C_INT_MA_TX = 0,
+ I2C_INT_MA_RX,
+ I2C_INT_SLA_TX,
+ I2C_INT_SLA_RX,
+ I2C_DMA_MA_TX,
+ I2C_DMA_MA_RX,
+ I2C_DMA_SLA_TX,
+ I2C_DMA_SLA_RX,
+} i2c_mode_type;
+
+// ../../../src/main/drivers/i2c_application.h
+typedef enum
+{
+ I2C_OK = 0,
+ I2C_ERR_STEP_1,
+ I2C_ERR_STEP_2,
+ I2C_ERR_STEP_3,
+ I2C_ERR_STEP_4,
+ I2C_ERR_STEP_5,
+ I2C_ERR_STEP_6,
+ I2C_ERR_STEP_7,
+ I2C_ERR_STEP_8,
+ I2C_ERR_STEP_9,
+ I2C_ERR_STEP_10,
+ I2C_ERR_STEP_11,
+ I2C_ERR_STEP_12,
+ I2C_ERR_TCRLD,
+ I2C_ERR_TDC,
+ I2C_ERR_ADDR,
+ I2C_ERR_STOP,
+ I2C_ERR_ACKFAIL,
+ I2C_ERR_TIMEOUT,
+ I2C_ERR_INTERRUPT,
+} i2c_status_type;
+
+// ../../../src/main/drivers/bus_quadspi.h
+typedef enum {
+
+ QUADSPI_CLOCK_INITIALISATION = 255,
+ QUADSPI_CLOCK_SLOW = 19,
+ QUADSPI_CLOCK_STANDARD = 9,
+ QUADSPI_CLOCK_FAST = 3,
+ QUADSPI_CLOCK_ULTRAFAST = 1
+} QUADSPIClockDivider_e;
+
+// ../../../src/main/drivers/bus_quadspi.h
+typedef enum QUADSPIDevice {
+ QUADSPIINVALID = -1,
+ QUADSPIDEV_1 = 0,
+} QUADSPIDevice;
+
+// ../../../src/main/drivers/bus_quadspi.h
+typedef enum {
+ QUADSPI_MODE_BK1_ONLY = 0,
+ QUADSPI_MODE_BK2_ONLY,
+ QUADSPI_MODE_DUAL_FLASH,
+} quadSpiMode_e;
+
+// ../../../src/main/drivers/bus_quadspi.h
+enum QUADSPIDevice {
+ QUADSPIINVALID = -1,
+ QUADSPIDEV_1 = 0,
+} QUADSPIDevice;
+typedef enum QUADSPIDevice QUADSPIDevice;
+
+// ../../../src/main/drivers/flash.h
+typedef enum {
+ FLASH_TYPE_NOR = 0,
+ FLASH_TYPE_NAND
+} flashType_e;
+
+// ../../../src/main/drivers/flash.h
+typedef enum {
+ FLASH_PARTITION_TYPE_UNKNOWN = 0,
+ FLASH_PARTITION_TYPE_PARTITION_TABLE,
+ FLASH_PARTITION_TYPE_FLASHFS,
+ FLASH_PARTITION_TYPE_BADBLOCK_MANAGEMENT,
+ FLASH_PARTITION_TYPE_FIRMWARE,
+ FLASH_PARTITION_TYPE_CONFIG,
+ FLASH_PARTITION_TYPE_FULL_BACKUP,
+ FLASH_PARTITION_TYPE_FIRMWARE_UPDATE_META,
+ FLASH_PARTITION_TYPE_UPDATE_FIRMWARE,
+ FLASH_MAX_PARTITIONS
+} flashPartitionType_e;
+
+// ../../../src/main/drivers/serial_softserial.h
+typedef enum {
+ SOFTSERIAL1 = 0,
+ SOFTSERIAL2
+} softSerialPortIndex_e;
+
+// ../../../src/main/drivers/display_widgets.h
+typedef enum {
+ DISPLAY_WIDGET_TYPE_AHI,
+ DISPLAY_WIDGET_TYPE_SIDEBAR,
+} displayWidgetType_e;
+
+// ../../../src/main/drivers/display_widgets.h
+typedef enum {
+ DISPLAY_WIDGET_AHI_STYLE_STAIRCASE = 0,
+ DISPLAY_WIDGET_AHI_STYLE_LINE = 1,
+} widgetAHIStyle_e;
+
+// ../../../src/main/drivers/display_widgets.h
+typedef enum {
+ DISPLAY_WIDGET_AHI_OPTION_SHOW_CORNERS = 1 << 0,
+} widgetAHIOptions_t;
+
+// ../../../src/main/drivers/display_widgets.h
+typedef enum
+{
+ DISPLAY_WIDGET_SIDEBAR_OPTION_LEFT = 1 << 0,
+ DISPLAY_WIDGET_SIDEBAR_OPTION_REVERSE = 1 << 1,
+ DISPLAY_WIDGET_SIDEBAR_OPTION_UNLABELED = 1 << 2,
+ DISPLAY_WIDGET_SIDEBAR_OPTION_STATIC = 1 << 3,
+} widgetSidebarOptions_t;
+
+// ../../../src/main/drivers/bus_spi.h
+typedef enum {
+ SPI_CLOCK_INITIALIZATON = 0,
+ SPI_CLOCK_SLOW = 1,
+ SPI_CLOCK_STANDARD = 2,
+ SPI_CLOCK_FAST = 3,
+ SPI_CLOCK_ULTRAFAST = 4
+} SPIClockSpeed_e;
+
+// ../../../src/main/drivers/bus_spi.h
+typedef enum SPIDevice {
+ SPIINVALID = -1,
+ SPIDEV_1 = 0,
+ SPIDEV_2,
+ SPIDEV_3,
+ SPIDEV_4
+} SPIDevice;
+
+// ../../../src/main/drivers/bus_spi.h
+enum SPIDevice {
+ SPIINVALID = -1,
+ SPIDEV_1 = 0,
+ SPIDEV_2,
+ SPIDEV_3,
+ SPIDEV_4
+} SPIDevice;
+typedef enum SPIDevice SPIDevice;
+
+// ../../../src/main/drivers/rcc.h
+enum rcc_reg {
+ RCC_EMPTY = 0,
+ RCC_AHB,
+ RCC_APB2,
+ RCC_APB1,
+ RCC_AHB1,
+ RCC_AHB2,
+ RCC_APB1L,
+ RCC_APB1H,
+ RCC_AHB3,
+ RCC_APB3,
+ RCC_AHB4,
+ RCC_APB4
+};
+typedef enum rcc_reg rcc_reg;
+
+// ../../../src/main/drivers/sdio.h
+typedef enum {
+ SDIOINVALID = -1,
+ SDIODEV_1 = 0,
+ SDIODEV_2,
+} SDIODevice;
+
+// ../../../src/main/drivers/osd.h
+typedef enum {
+ VIDEO_SYSTEM_AUTO = 0,
+ VIDEO_SYSTEM_PAL,
+ VIDEO_SYSTEM_NTSC,
+ VIDEO_SYSTEM_HDZERO,
+ VIDEO_SYSTEM_DJIWTF,
+ VIDEO_SYSTEM_AVATAR,
+ VIDEO_SYSTEM_DJICOMPAT,
+ VIDEO_SYSTEM_DJICOMPAT_HD,
+ VIDEO_SYSTEM_DJI_NATIVE
+} videoSystem_e;
+
+// ../../../src/main/drivers/osd.h
+typedef enum {
+ OSD_DRIVER_NONE = 0,
+ OSD_DRIVER_MAX7456 = 1,
+} osdDriver_e;
+
+// ../../../src/main/drivers/bus.h
+typedef enum {
+ BUS_SPEED_INITIALIZATION = 0,
+ BUS_SPEED_SLOW = 1,
+ BUS_SPEED_STANDARD = 2,
+ BUS_SPEED_FAST = 3,
+ BUS_SPEED_ULTRAFAST = 4
+} busSpeed_e;
+
+// ../../../src/main/drivers/bus.h
+typedef enum {
+ BUSTYPE_ANY = 0,
+ BUSTYPE_NONE = 0,
+ BUSTYPE_I2C = 1,
+ BUSTYPE_SPI = 2,
+ BUSTYPE_SDIO = 3,
+} busType_e;
+
+// ../../../src/main/drivers/bus.h
+typedef enum {
+ BUSINDEX_1 = 0,
+ BUSINDEX_2 = 1,
+ BUSINDEX_3 = 2,
+ BUSINDEX_4 = 3
+} busIndex_e;
+
+// ../../../src/main/drivers/bus.h
+typedef enum {
+ DEVHW_NONE = 0,
+
+
+ DEVHW_MPU6000,
+ DEVHW_MPU6500,
+ DEVHW_BMI160,
+ DEVHW_BMI088_GYRO,
+ DEVHW_BMI088_ACC,
+ DEVHW_ICM20689,
+ DEVHW_ICM42605,
+ DEVHW_BMI270,
+ DEVHW_LSM6D,
+ DEVHW_ICM45686,
+
+ DEVHW_MPU9250,
+
+
+ DEVHW_BMP085,
+ DEVHW_BMP280,
+ DEVHW_MS5611,
+ DEVHW_MS5607,
+ DEVHW_LPS25H,
+ DEVHW_SPL06,
+ DEVHW_BMP388,
+ DEVHW_DPS310,
+ DEVHW_B2SMPB,
+
+
+ DEVHW_HMC5883,
+ DEVHW_AK8963,
+ DEVHW_AK8975,
+ DEVHW_IST8310_0,
+ DEVHW_IST8310_1,
+ DEVHW_IST8308,
+ DEVHW_QMC5883,
+ DEVHW_QMC5883P,
+ DEVHW_MAG3110,
+ DEVHW_LIS3MDL,
+ DEVHW_RM3100,
+ DEVHW_VCM5883,
+ DEVHW_MLX90393,
+
+
+ DEVHW_LM75_0,
+ DEVHW_LM75_1,
+ DEVHW_LM75_2,
+ DEVHW_LM75_3,
+ DEVHW_LM75_4,
+ DEVHW_LM75_5,
+ DEVHW_LM75_6,
+ DEVHW_LM75_7,
+
+
+ DEVHW_DS2482,
+
+
+ DEVHW_MAX7456,
+
+
+ DEVHW_SRF10,
+ DEVHW_VL53L0X,
+ DEVHW_VL53L1X,
+ DEVHW_US42,
+ DEVHW_TOF10120_I2C,
+ DEVHW_TERARANGER_EVO_I2C,
+
+
+ DEVHW_MS4525,
+ DEVHW_DLVR,
+ DEVHW_M25P16,
+ DEVHW_W25N,
+ DEVHW_UG2864,
+ DEVHW_SDCARD,
+ DEVHW_IRLOCK,
+ DEVHW_PCF8574,
+} devHardwareType_e;
+
+// ../../../src/main/drivers/bus.h
+typedef enum {
+ DEVFLAGS_NONE = 0,
+ DEVFLAGS_USE_RAW_REGISTERS = (1 << 0),
+
+
+ DEVFLAGS_USE_MANUAL_DEVICE_SELECT = (1 << 1),
+ DEVFLAGS_SPI_MODE_0 = (1 << 2),
+} deviceFlags_e;
+
+// ../../../src/main/drivers/system.h
+typedef enum {
+ FAILURE_DEVELOPER = 0,
+ FAILURE_MISSING_ACC,
+ FAILURE_ACC_INIT,
+ FAILURE_ACC_INCOMPATIBLE,
+ FAILURE_INVALID_EEPROM_CONTENTS,
+ FAILURE_FLASH_WRITE_FAILED,
+ FAILURE_GYRO_INIT_FAILED,
+ FAILURE_FLASH_READ_FAILED,
+} failureMode_e;
+
+// ../../../src/main/drivers/adc_impl.h
+typedef enum ADCDevice {
+ ADCINVALID = -1,
+ ADCDEV_1 = 0,
+#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7)
+ ADCDEV_2,
+ ADCDEV_3,
+ ADCDEV_MAX = ADCDEV_3,
+#else
+ ADCDEV_MAX = ADCDEV_1,
+#endif
+ ADCDEV_COUNT = ADCDEV_MAX + 1
+} ADCDevice;
+
+// ../../../src/main/drivers/adc_impl.h
+enum ADCDevice {
+ ADCINVALID = -1,
+ ADCDEV_1 = 0,
+#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7)
+ ADCDEV_2,
+ ADCDEV_3,
+ ADCDEV_MAX = ADCDEV_3,
+#else
+ ADCDEV_MAX = ADCDEV_1,
+#endif
+ ADCDEV_COUNT = ADCDEV_MAX + 1
+} ADCDevice;
+typedef enum ADCDevice ADCDevice;
+
+// ../../../src/main/drivers/persistent.h
+typedef enum {
+ PERSISTENT_OBJECT_MAGIC = 0,
+ PERSISTENT_OBJECT_RESET_REASON,
+ PERSISTENT_OBJECT_COUNT,
+} persistentObjectId_e;
+
+// ../../../src/main/drivers/gimbal_common.h
+typedef enum {
+ GIMBAL_DEV_UNSUPPORTED = 0,
+ GIMBAL_DEV_SERIAL,
+ GIMBAL_DEV_UNKNOWN=0xFF
+} gimbalDevType_e;
+
+// ../../../src/main/drivers/gimbal_common.h
+typedef enum {
+ GIMBAL_MODE_FOLLOW = 0,
+ GIMBAL_MODE_TILT_LOCK = (1<<0),
+ GIMBAL_MODE_ROLL_LOCK = (1<<1),
+ GIMBAL_MODE_PAN_LOCK = (1<<2),
+} gimbal_htk_mode_e;
+
+// ../../../src/main/drivers/pwm_mapping.h
+typedef enum {
+ PWM_TYPE_STANDARD = 0,
+ PWM_TYPE_ONESHOT125,
+ PWM_TYPE_MULTISHOT,
+ PWM_TYPE_BRUSHED,
+ PWM_TYPE_DSHOT150,
+ PWM_TYPE_DSHOT300,
+ PWM_TYPE_DSHOT600,
+} motorPwmProtocolTypes_e;
+
+// ../../../src/main/drivers/pwm_mapping.h
+typedef enum {
+ SERVO_TYPE_PWM = 0,
+ SERVO_TYPE_SBUS,
+ SERVO_TYPE_SBUS_PWM
+} servoProtocolType_e;
+
+// ../../../src/main/drivers/pwm_mapping.h
+typedef enum {
+ PIN_LABEL_NONE = 0,
+ PIN_LABEL_LED
+} pinLabel_e;
+
+// ../../../src/main/drivers/pwm_mapping.h
+typedef enum {
+ PWM_INIT_ERROR_NONE = 0,
+ PWM_INIT_ERROR_TOO_MANY_MOTORS,
+ PWM_INIT_ERROR_TOO_MANY_SERVOS,
+ PWM_INIT_ERROR_NOT_ENOUGH_MOTOR_OUTPUTS,
+ PWM_INIT_ERROR_NOT_ENOUGH_SERVO_OUTPUTS,
+ PWM_INIT_ERROR_TIMER_INIT_FAILED,
+} pwmInitError_e;
+
+// ../../../src/main/drivers/serial_uart.h
+typedef enum {
+ UARTDEV_1 = 0,
+ UARTDEV_2 = 1,
+ UARTDEV_3 = 2,
+ UARTDEV_4 = 3,
+ UARTDEV_5 = 4,
+ UARTDEV_6 = 5,
+ UARTDEV_7 = 6,
+ UARTDEV_8 = 7,
+ UARTDEV_MAX
+} UARTDevice_e;
+
+// ../../../src/main/drivers/logging_codes.h
+typedef enum {
+ BOOT_EVENT_FLAGS_NONE = 0,
+ BOOT_EVENT_FLAGS_WARNING = 1 << 0,
+ BOOT_EVENT_FLAGS_ERROR = 1 << 1,
+
+ BOOT_EVENT_FLAGS_PARAM16 = 1 << 14,
+ BOOT_EVENT_FLAGS_PARAM32 = 1 << 15
+} bootLogFlags_e;
+
+// ../../../src/main/drivers/logging_codes.h
+typedef enum {
+ BOOT_EVENT_CONFIG_LOADED = 0,
+ BOOT_EVENT_SYSTEM_INIT_DONE = 1,
+ BOOT_EVENT_PWM_INIT_DONE = 2,
+ BOOT_EVENT_EXTRA_BOOT_DELAY = 3,
+ BOOT_EVENT_SENSOR_INIT_DONE = 4,
+ BOOT_EVENT_GPS_INIT_DONE = 5,
+ BOOT_EVENT_LEDSTRIP_INIT_DONE = 6,
+ BOOT_EVENT_TELEMETRY_INIT_DONE = 7,
+ BOOT_EVENT_SYSTEM_READY = 8,
+ BOOT_EVENT_GYRO_DETECTION = 9,
+ BOOT_EVENT_ACC_DETECTION = 10,
+ BOOT_EVENT_BARO_DETECTION = 11,
+ BOOT_EVENT_MAG_DETECTION = 12,
+ BOOT_EVENT_RANGEFINDER_DETECTION = 13,
+ BOOT_EVENT_MAG_INIT_FAILED = 14,
+ BOOT_EVENT_HMC5883L_READ_OK_COUNT = 15,
+ BOOT_EVENT_HMC5883L_READ_FAILED = 16,
+ BOOT_EVENT_HMC5883L_SATURATION = 17,
+ BOOT_EVENT_TIMER_CH_SKIPPED = 18,
+ BOOT_EVENT_TIMER_CH_MAPPED = 19,
+ BOOT_EVENT_PITOT_DETECTION = 20,
+ BOOT_EVENT_TEMP_SENSOR_DETECTION = 21,
+ BOOT_EVENT_1WIRE_DETECTION = 22,
+ BOOT_EVENT_HARDWARE_IO_CONFLICT = 23,
+ BOOT_EVENT_OPFLOW_DETECTION = 24,
+
+ BOOT_EVENT_CODE_COUNT
+} bootLogEventCode_e;
+
+// ../../../src/main/drivers/pwm_esc_detect.h
+typedef enum {
+ MOTOR_UNKNOWN = 0,
+ MOTOR_BRUSHED,
+ MOTOR_BRUSHLESS
+} HardwareMotorTypes_e;
+
+// ../../../src/main/drivers/compass/compass_mpu9250.c
+typedef enum {
+ CHECK_STATUS = 0,
+ WAITING_FOR_STATUS,
+ WAITING_FOR_DATA
+} mpu9250CompassReadState_e;
+
+// ../../../src/main/drivers/accgyro/accgyro_bmi270.c
+typedef enum {
+ BMI270_REG_CHIP_ID = 0x00,
+ BMI270_REG_ERR_REG = 0x02,
+ BMI270_REG_STATUS = 0x03,
+ BMI270_REG_ACC_DATA_X_LSB = 0x0C,
+ BMI270_REG_GYR_DATA_X_LSB = 0x12,
+ BMI270_REG_SENSORTIME_0 = 0x18,
+ BMI270_REG_SENSORTIME_1 = 0x19,
+ BMI270_REG_SENSORTIME_2 = 0x1A,
+ BMI270_REG_EVENT = 0x1B,
+ BMI270_REG_INT_STATUS_0 = 0x1C,
+ BMI270_REG_INT_STATUS_1 = 0x1D,
+ BMI270_REG_INTERNAL_STATUS = 0x21,
+ BMI270_REG_TEMPERATURE_LSB = 0x22,
+ BMI270_REG_TEMPERATURE_MSB = 0x23,
+ BMI270_REG_FIFO_LENGTH_LSB = 0x24,
+ BMI270_REG_FIFO_LENGTH_MSB = 0x25,
+ BMI270_REG_FIFO_DATA = 0x26,
+ BMI270_REG_ACC_CONF = 0x40,
+ BMI270_REG_ACC_RANGE = 0x41,
+ BMI270_REG_GYRO_CONF = 0x42,
+ BMI270_REG_GYRO_RANGE = 0x43,
+ BMI270_REG_AUX_CONF = 0x44,
+ BMI270_REG_FIFO_DOWNS = 0x45,
+ BMI270_REG_FIFO_WTM_0 = 0x46,
+ BMI270_REG_FIFO_WTM_1 = 0x47,
+ BMI270_REG_FIFO_CONFIG_0 = 0x48,
+ BMI270_REG_FIFO_CONFIG_1 = 0x49,
+ BMI270_REG_SATURATION = 0x4A,
+ BMI270_REG_INT1_IO_CTRL = 0x53,
+ BMI270_REG_INT2_IO_CTRL = 0x54,
+ BMI270_REG_INT_LATCH = 0x55,
+ BMI270_REG_INT1_MAP_FEAT = 0x56,
+ BMI270_REG_INT2_MAP_FEAT = 0x57,
+ BMI270_REG_INT_MAP_DATA = 0x58,
+ BMI270_REG_INIT_CTRL = 0x59,
+ BMI270_REG_INIT_DATA = 0x5E,
+ BMI270_REG_ACC_SELF_TEST = 0x6D,
+ BMI270_REG_GYR_SELF_TEST_AXES = 0x6E,
+ BMI270_REG_PWR_CONF = 0x7C,
+ BMI270_REG_PWR_CTRL = 0x7D,
+ BMI270_REG_CMD = 0x7E,
+} bmi270Register_e;
+
+// ../../../src/main/drivers/accgyro/accgyro_mpu.h
+enum gyro_fsr_e {
+ INV_FSR_250DPS = 0,
+ INV_FSR_500DPS,
+ INV_FSR_1000DPS,
+ INV_FSR_2000DPS,
+ NUM_GYRO_FSR
+};
+typedef enum gyro_fsr_e gyro_fsr_e;
+
+// ../../../src/main/drivers/accgyro/accgyro_mpu.h
+enum fchoice_b {
+ FCB_DISABLED = 0,
+ FCB_8800_32,
+ FCB_3600_32
+};
+typedef enum fchoice_b fchoice_b;
+
+// ../../../src/main/drivers/accgyro/accgyro_mpu.h
+enum clock_sel_e {
+ INV_CLK_INTERNAL = 0,
+ INV_CLK_PLL,
+ NUM_CLK
+};
+typedef enum clock_sel_e clock_sel_e;
+
+// ../../../src/main/drivers/accgyro/accgyro_mpu.h
+enum accel_fsr_e {
+ INV_FSR_2G = 0,
+ INV_FSR_4G,
+ INV_FSR_8G,
+ INV_FSR_16G,
+ NUM_ACCEL_FSR
+};
+typedef enum accel_fsr_e accel_fsr_e;
+
+// ../../../src/main/drivers/accgyro/accgyro_lsm6dxx.h
+typedef enum {
+ LSM6DXX_REG_COUNTER_BDR1 = 0x0B,
+ LSM6DXX_REG_INT1_CTRL = 0x0D,
+ LSM6DXX_REG_INT2_CTRL = 0x0E,
+ LSM6DXX_REG_WHO_AM_I = 0x0F,
+ LSM6DXX_REG_CTRL1_XL = 0x10,
+ LSM6DXX_REG_CTRL2_G = 0x11,
+ LSM6DXX_REG_CTRL3_C = 0x12,
+ LSM6DXX_REG_CTRL4_C = 0x13,
+ LSM6DXX_REG_CTRL5_C = 0x14,
+ LSM6DXX_REG_CTRL6_C = 0x15,
+ LSM6DXX_REG_CTRL7_G = 0x16,
+ LSM6DXX_REG_CTRL8_XL = 0x17,
+ LSM6DXX_REG_CTRL9_XL = 0x18,
+ LSM6DXX_REG_CTRL10_C = 0x19,
+ LSM6DXX_REG_STATUS = 0x1E,
+ LSM6DXX_REG_OUT_TEMP_L = 0x20,
+ LSM6DXX_REG_OUT_TEMP_H = 0x21,
+ LSM6DXX_REG_OUTX_L_G = 0x22,
+ LSM6DXX_REG_OUTX_H_G = 0x23,
+ LSM6DXX_REG_OUTY_L_G = 0x24,
+ LSM6DXX_REG_OUTY_H_G = 0x25,
+ LSM6DXX_REG_OUTZ_L_G = 0x26,
+ LSM6DXX_REG_OUTZ_H_G = 0x27,
+ LSM6DXX_REG_OUTX_L_A = 0x28,
+ LSM6DXX_REG_OUTX_H_A = 0x29,
+ LSM6DXX_REG_OUTY_L_A = 0x2A,
+ LSM6DXX_REG_OUTY_H_A = 0x2B,
+ LSM6DXX_REG_OUTZ_L_A = 0x2C,
+ LSM6DXX_REG_OUTZ_H_A = 0x2D,
+} lsm6dxxRegister_e;
+
+// ../../../src/main/drivers/accgyro/accgyro_lsm6dxx.h
+typedef enum {
+ LSM6DXX_VAL_COUNTER_BDR1_DDRY_PM = BIT(7),
+ LSM6DXX_VAL_INT1_CTRL = 0x02,
+ LSM6DXX_VAL_INT2_CTRL = 0x00,
+ LSM6DXX_VAL_CTRL1_XL_ODR833 = 0x07,
+ LSM6DXX_VAL_CTRL1_XL_ODR1667 = 0x08,
+ LSM6DXX_VAL_CTRL1_XL_ODR3332 = 0x09,
+ LSM6DXX_VAL_CTRL1_XL_ODR3333 = 0x0A,
+ LSM6DXX_VAL_CTRL1_XL_8G = 0x03,
+ LSM6DXX_VAL_CTRL1_XL_16G = 0x01,
+ LSM6DXX_VAL_CTRL1_XL_LPF1 = 0x00,
+ LSM6DXX_VAL_CTRL1_XL_LPF2 = 0x01,
+ LSM6DXX_VAL_CTRL2_G_ODR6664 = 0x0A,
+ LSM6DXX_VAL_CTRL2_G_2000DPS = 0x03,
+
+ LSM6DXX_VAL_CTRL3_C_H_LACTIVE = 0,
+ LSM6DXX_VAL_CTRL3_C_PP_OD = 0,
+ LSM6DXX_VAL_CTRL3_C_SIM = 0,
+ LSM6DXX_VAL_CTRL3_C_IF_INC = BIT(2),
+ LSM6DXX_VAL_CTRL4_C_DRDY_MASK = BIT(3),
+ LSM6DXX_VAL_CTRL4_C_I2C_DISABLE = BIT(2),
+ LSM6DXX_VAL_CTRL4_C_LPF1_SEL_G = BIT(1),
+ LSM6DXX_VAL_CTRL6_C_XL_HM_MODE = 0,
+ LSM6DXX_VAL_CTRL6_C_FTYPE_300HZ = 0x00,
+ LSM6DXX_VAL_CTRL6_C_FTYPE_201HZ = 0x01,
+ LSM6DXX_VAL_CTRL6_C_FTYPE_102HZ = 0x02,
+ LSM6DXX_VAL_CTRL6_C_FTYPE_603HZ = 0x03,
+ LSM6DXX_VAL_CTRL7_G_HP_EN_G = BIT(6),
+ LSM6DXX_VAL_CTRL7_G_HPM_G_16 = 0x00,
+ LSM6DXX_VAL_CTRL7_G_HPM_G_65 = 0x01,
+ LSM6DXX_VAL_CTRL7_G_HPM_G_260 = 0x02,
+ LSM6DXX_VAL_CTRL7_G_HPM_G_1040 = 0x03,
+ LSM6DXX_VAL_CTRL9_XL_I3C_DISABLE = BIT(1),
+} lsm6dxxConfigValues_e;
+
+// ../../../src/main/drivers/accgyro/accgyro_lsm6dxx.h
+typedef enum {
+ LSM6DXX_MASK_COUNTER_BDR1 = 0x80,
+ LSM6DXX_MASK_CTRL3_C = 0x3C,
+ LSM6DXX_MASK_CTRL3_C_RESET = BIT(0),
+ LSM6DXX_MASK_CTRL4_C = 0x0E,
+ LSM6DXX_MASK_CTRL6_C = 0x17,
+ LSM6DXX_MASK_CTRL7_G = 0x70,
+ LSM6DXX_MASK_CTRL9_XL = 0x02,
+ LSM6DSL_MASK_CTRL6_C = 0x13,
+
+} lsm6dxxConfigMasks_e;
+
+// ../../../src/main/drivers/accgyro/accgyro_lsm6dxx.h
+typedef enum {
+ GYRO_HARDWARE_LPF_NORMAL,
+ GYRO_HARDWARE_LPF_OPTION_1,
+ GYRO_HARDWARE_LPF_OPTION_2,
+ GYRO_HARDWARE_LPF_EXPERIMENTAL,
+ GYRO_HARDWARE_LPF_COUNT
+} gyroHardwareLpf_e;
+
+// ../../../src/main/drivers/dronecan/dronecan.c
+enum dronecanState_e {
+ STATE_DRONECAN_INIT,
+ STATE_DRONECAN_NORMAL,
+ STATE_DRONECAN_BUS_OFF
+};
+typedef enum dronecanState_e dronecanState_e;
+
+// ../../../src/main/drivers/dronecan/dronecan.h
+typedef enum {
+ DRONECAN_BITRATE_125KBPS = 0,
+ DRONECAN_BITRATE_250KBPS,
+ DRONECAN_BITRATE_500KBPS,
+ DRONECAN_BITRATE_1000KBPS,
+ DRONECAN_BITRATE_COUNT
+} dronecanBitrate_e;
+
+// ../../../src/main/drivers/dronecan/libcanard/canard_sitl_driver.c
+typedef enum {
+ SITL_CAN_MODE_STUB = 0,
+ SITL_CAN_MODE_SOCKETCAN
+} sitlCANMode_e;
+
+// ../../../src/main/drivers/dronecan/libcanard/canard.h
+typedef enum
+{
+ CanardTransferTypeResponse = 0,
+ CanardTransferTypeRequest = 1,
+ CanardTransferTypeBroadcast = 2
+} CanardTransferType;
+
+// ../../../src/main/drivers/dronecan/libcanard/canard.h
+typedef enum
+{
+ CanardResponse,
+ CanardRequest
+} CanardRequestResponse;
+
+// ../../../src/main/drivers/rangefinder/rangefinder_vl53l0x.c
+typedef enum {
+ VcselPeriodPreRange,
+ VcselPeriodFinalRange
+} vcselPeriodType_e;
+
+// ../../../src/main/drivers/rangefinder/rangefinder_vl53l0x.c
+typedef enum {
+ MEASUREMENT_START,
+ MEASUREMENT_WAIT,
+ MEASUREMENT_READ,
+} measurementSteps_e;
+
+// ../../../src/main/drivers/sdcard/sdmmc_sdio_f4xx.c
+typedef enum
+{
+ SD_SINGLE_BLOCK = 0,
+ SD_MULTIPLE_BLOCK = 1,
+} SD_Operation_t;
+
+// ../../../src/main/drivers/sdcard/sdmmc_sdio_f4xx.c
+typedef enum
+{
+ SD_CARD_READY = ((uint32_t)0x00000001),
+ SD_CARD_IDENTIFICATION = ((uint32_t)0x00000002),
+ SD_CARD_STANDBY = ((uint32_t)0x00000003),
+ SD_CARD_TRANSFER = ((uint32_t)0x00000004),
+ SD_CARD_SENDING = ((uint32_t)0x00000005),
+ SD_CARD_RECEIVING = ((uint32_t)0x00000006),
+ SD_CARD_PROGRAMMING = ((uint32_t)0x00000007),
+ SD_CARD_DISCONNECTED = ((uint32_t)0x00000008),
+ SD_CARD_ERROR = ((uint32_t)0x000000FF)
+} SD_CardState_t;
+
+// ../../../src/main/drivers/sdcard/sdmmc_sdio.h
+typedef enum
+{
+
+ SD_CMD_CRC_FAIL = (1),
+ SD_DATA_CRC_FAIL = (2),
+ SD_CMD_RSP_TIMEOUT = (3),
+ SD_DATA_TIMEOUT = (4),
+ SD_TX_UNDERRUN = (5),
+ SD_RX_OVERRUN = (6),
+ SD_START_BIT_ERR = (7),
+ SD_CMD_OUT_OF_RANGE = (8),
+ SD_ADDR_MISALIGNED = (9),
+ SD_BLOCK_LEN_ERR = (10),
+ SD_ERASE_SEQ_ERR = (11),
+ SD_BAD_ERASE_PARAM = (12),
+ SD_WRITE_PROT_VIOLATION = (13),
+ SD_LOCK_UNLOCK_FAILED = (14),
+ SD_COM_CRC_FAILED = (15),
+ SD_ILLEGAL_CMD = (16),
+ SD_CARD_ECC_FAILED = (17),
+ SD_CC_ERROR = (18),
+ SD_GENERAL_UNKNOWN_ERROR = (19),
+ SD_STREAM_READ_UNDERRUN = (20),
+ SD_STREAM_WRITE_OVERRUN = (21),
+ SD_CID_CSD_OVERWRITE = (22),
+ SD_WP_ERASE_SKIP = (23),
+ SD_CARD_ECC_DISABLED = (24),
+ SD_ERASE_RESET = (25),
+ SD_AKE_SEQ_ERROR = (26),
+ SD_INVALID_VOLTRANGE = (27),
+ SD_ADDR_OUT_OF_RANGE = (28),
+ SD_SWITCH_ERROR = (29),
+ SD_SDMMC_DISABLED = (30),
+ SD_SDMMC_FUNCTION_BUSY = (31),
+ SD_SDMMC_FUNCTION_FAILED = (32),
+ SD_SDMMC_UNKNOWN_FUNCTION = (33),
+ SD_OUT_OF_BOUND = (34),
+
+
+
+ SD_INTERNAL_ERROR = (35),
+ SD_NOT_CONFIGURED = (36),
+ SD_REQUEST_PENDING = (37),
+ SD_REQUEST_NOT_APPLICABLE = (38),
+ SD_INVALID_PARAMETER = (39),
+ SD_UNSUPPORTED_FEATURE = (40),
+ SD_UNSUPPORTED_HW = (41),
+ SD_ERROR = (42),
+ SD_BUSY = (43),
+ SD_OK = (0)
+} SD_Error_t;
+
+// ../../../src/main/drivers/sdcard/sdmmc_sdio.h
+typedef enum
+{
+ SD_STD_CAPACITY_V1_1 = 0,
+ SD_STD_CAPACITY_V2_0 = 1,
+ SD_HIGH_CAPACITY = 2,
+ SD_MULTIMEDIA = 3,
+ SD_SECURE_DIGITAL_IO = 4,
+ SD_HIGH_SPEED_MULTIMEDIA = 5,
+ SD_SECURE_DIGITAL_IO_COMBO = 6,
+ SD_HIGH_CAPACITY_MMC = 7,
+} SD_CardType_t;
+
+// ../../../src/main/drivers/sdcard/sdcard_sdio.c
+typedef enum {
+ SDCARD_RECEIVE_SUCCESS,
+ SDCARD_RECEIVE_BLOCK_IN_PROGRESS,
+ SDCARD_RECEIVE_ERROR
+} sdcardReceiveBlockStatus_e;
+
+// ../../../src/main/drivers/sdcard/sdcard.h
+typedef enum {
+ SDCARD_BLOCK_OPERATION_READ,
+ SDCARD_BLOCK_OPERATION_WRITE,
+ SDCARD_BLOCK_OPERATION_ERASE,
+} sdcardBlockOperation_e;
+
+// ../../../src/main/drivers/sdcard/sdcard.h
+typedef enum {
+ SDCARD_OPERATION_IN_PROGRESS,
+ SDCARD_OPERATION_BUSY,
+ SDCARD_OPERATION_SUCCESS,
+ SDCARD_OPERATION_FAILURE
+} sdcardOperationStatus_e;
+
+// ../../../src/main/drivers/sdcard/sdcard_impl.h
+typedef enum {
+
+ SDCARD_STATE_NOT_PRESENT = 0,
+ SDCARD_STATE_RESET,
+ SDCARD_STATE_CARD_INIT_IN_PROGRESS,
+ SDCARD_STATE_INITIALIZATION_RECEIVE_CID,
+
+
+ SDCARD_STATE_READY,
+ SDCARD_STATE_READING,
+ SDCARD_STATE_SENDING_WRITE,
+ SDCARD_STATE_WAITING_FOR_WRITE,
+ SDCARD_STATE_WRITING_MULTIPLE_BLOCKS,
+ SDCARD_STATE_STOPPING_MULTIPLE_BLOCK_WRITE,
+} sdcardState_e;
+
+// ../../../src/main/drivers/sdcard/sdcard_spi.c
+typedef enum {
+ SDCARD_RECEIVE_SUCCESS,
+ SDCARD_RECEIVE_BLOCK_IN_PROGRESS,
+ SDCARD_RECEIVE_ERROR,
+} sdcardReceiveBlockStatus_e;
+
diff --git a/src/main/fc/fc_mavlink.c b/src/main/fc/fc_mavlink.c
index f59b91cd690..0fe195332c5 100644
--- a/src/main/fc/fc_mavlink.c
+++ b/src/main/fc/fc_mavlink.c
@@ -180,6 +180,17 @@ static void mavlinkParseRxStats(const mavlink_radio_status_t *msg) {
rxLinkStatistics.uplinkSNR = msg->noise;
rxLinkStatistics.uplinkLQ = scaleRange(msg->rssi, 0, 255, 0, 100);
break;
+ case MAVLINK_RADIO_MLRS:
+ // rssi/remrssi are 0-254 AP scale; back-convert to dBm: range is -120 to -50
+ rxLinkStatistics.uplinkRSSI = msg->rssi != 255
+ ? (int8_t)(((int32_t)msg->rssi * (-50 - -120) / 254) + (-120))
+ : 0;
+ // noise field is actually: clamp(-SNR + 10, 0, 127), so SNR = -(noise - 10) = 10 - noise
+ rxLinkStatistics.uplinkSNR = 10 - (int8_t)msg->noise;
+ rxLinkStatistics.uplinkLQ = msg->rssi != 255
+ ? scaleRange(msg->rssi, 0, 254, 0, 100)
+ : 0;
+ break;
case MAVLINK_RADIO_GENERIC:
default:
rxLinkStatistics.uplinkRSSI = msg->rssi;
diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml
index 769c53b6b33..3c00d9ceca5 100644
--- a/src/main/fc/settings.yaml
+++ b/src/main/fc/settings.yaml
@@ -199,7 +199,7 @@ tables:
values: ["NONE", "SERIAL", "MSP"]
enum: headTrackerDevType_e
- name: mavlink_radio_type
- values: ["GENERIC", "ELRS", "SIK", "NONE"]
+ values: ["GENERIC", "ELRS", "SIK", "MLRS", "NONE"]
enum: mavlinkRadio_e
- name: mavlink_autopilot_type
values: ["GENERIC", "ARDUPILOT"]
diff --git a/src/main/mavlink/mavlink_types.h b/src/main/mavlink/mavlink_types.h
index 70a2e5d1157..c30bd267eec 100644
--- a/src/main/mavlink/mavlink_types.h
+++ b/src/main/mavlink/mavlink_types.h
@@ -39,8 +39,8 @@
#define MAV_DATA_STREAM_HEARTBEAT (MAV_DATA_STREAM_EXTENDED_SYS_STATE + 1)
#define MAVLINK_STREAM_COUNT (MAV_DATA_STREAM_HEARTBEAT + 1)
#define ARDUPILOT_VERSION_MAJOR 4
-#define ARDUPILOT_VERSION_MINOR 6
-#define ARDUPILOT_VERSION_PATCH 3
+#define ARDUPILOT_VERSION_MINOR 7
+#define ARDUPILOT_VERSION_PATCH 0
#define MAVLINK_MAX_ROUTES 32
#define MAVLINK_PORT_MASK(portIndex) (1U << (portIndex))
#define MAXSTREAMS MAVLINK_STREAM_COUNT
diff --git a/src/main/navigation/navigation.h b/src/main/navigation/navigation.h
index 572b8ff2cde..999a3b315c3 100644
--- a/src/main/navigation/navigation.h
+++ b/src/main/navigation/navigation.h
@@ -239,18 +239,18 @@ void abortForcedPosHold(void);
#define NAV_ACCEL_CUTOFF_FREQUENCY_HZ 2 // low-pass filter on XY-acceleration target
-enum {
+typedef enum {
NAV_GPS_ATTI = 0, // Pitch/roll stick controls attitude (pitch/roll lean angles)
NAV_GPS_CRUISE = 1 // Pitch/roll stick controls velocity (forward/right speed)
-};
+} nav_control_type_e;
-enum {
+typedef enum {
NAV_LOITER_RIGHT = 0, // Loitering direction right
NAV_LOITER_LEFT = 1, // Loitering direction left
NAV_LOITER_YAW = 2
-};
+} nav_loiter_type_e;
-enum {
+typedef enum {
NAV_RTH_NO_ALT = 0, // Maintain current altitude
NAV_RTH_EXTRA_ALT = 1, // Maintain current altitude + predefined safety margin
NAV_RTH_CONST_ALT = 2, // Climb/descend to predefined altitude
@@ -258,18 +258,18 @@ enum {
NAV_RTH_AT_LEAST_ALT = 4, // Climb to predefined altitude if below it
NAV_RTH_AT_LEAST_ALT_LINEAR_DESCENT = 5, // Climb to predefined altitude if below it,
// descend linearly to reach home at predefined altitude if above it
-};
+} nav_rth_alt_profile_e;
-enum {
+typedef enum {
NAV_RTH_CLIMB_STAGE_AT_LEAST = 0, // Will climb to the lesser of rth_climb_first_stage_altitude or rth_altitude, before turning
NAV_RTH_CLIMB_STAGE_EXTRA = 1, // Will climb the lesser of rth_climb_first_stage_altitude above the current altitude or to nav_rth_altitude, before turning
-};
+} nav_rth_climb_profile_e;
-enum {
+typedef enum {
NAV_HEADING_CONTROL_NONE = 0,
NAV_HEADING_CONTROL_AUTO,
NAV_HEADING_CONTROL_MANUAL
-};
+} nav_heading_control_e;
typedef enum {
NAV_RESET_NEVER = 0,
diff --git a/src/main/telemetry/telemetry.h b/src/main/telemetry/telemetry.h
index 9b1f0a6bca0..176ce6fc6f3 100644
--- a/src/main/telemetry/telemetry.h
+++ b/src/main/telemetry/telemetry.h
@@ -39,13 +39,15 @@ typedef enum {
typedef enum {
MAVLINK_AUTOPILOT_GENERIC,
- MAVLINK_AUTOPILOT_ARDUPILOT
+ MAVLINK_AUTOPILOT_ARDUPILOT,
+ MAVLINK_AUTOPILOT_INAV // For future use, nothing implemented
} mavlinkAutopilotType_e;
typedef enum {
MAVLINK_RADIO_GENERIC,
MAVLINK_RADIO_ELRS,
MAVLINK_RADIO_SIK,
+ MAVLINK_RADIO_MLRS,
MAVLINK_RADIO_NONE // Not a radio
} mavlinkRadio_e;
From 9e5f8421e390d77bdd760500ab0517fdae43ee73 Mon Sep 17 00:00:00 2001
From: frogmane <7685285+xznhj8129@users.noreply.github.com>
Date: Sat, 18 Apr 2026 12:44:51 -0400
Subject: [PATCH 44/46] regenerate mavlink headers + compile all dialect
---
.../MAVLink/ardupilotmega/ardupilotmega.h | 876 +++
lib/main/MAVLink/ardupilotmega/mavlink.h | 34 +
.../ardupilotmega/mavlink_msg_adap_tuning.h | 596 ++
.../MAVLink/ardupilotmega/mavlink_msg_ahrs.h | 428 ++
.../MAVLink/ardupilotmega/mavlink_msg_ahrs2.h | 400 ++
.../MAVLink/ardupilotmega/mavlink_msg_ahrs3.h | 512 ++
.../mavlink_msg_airspeed_autocal.h | 568 ++
.../ardupilotmega/mavlink_msg_aoa_ssa.h | 316 ++
.../ardupilotmega/mavlink_msg_ap_adc.h | 400 ++
.../mavlink_msg_autopilot_version_request.h | 288 +
.../ardupilotmega/mavlink_msg_battery2.h | 288 +
.../mavlink_msg_camera_feedback.h | 624 +++
.../ardupilotmega/mavlink_msg_camera_status.h | 484 ++
.../mavlink_msg_compassmot_status.h | 400 ++
.../ardupilotmega/mavlink_msg_data16.h | 306 ++
.../ardupilotmega/mavlink_msg_data32.h | 306 ++
.../ardupilotmega/mavlink_msg_data64.h | 306 ++
.../ardupilotmega/mavlink_msg_data96.h | 306 ++
.../ardupilotmega/mavlink_msg_deepstall.h | 512 ++
.../mavlink_msg_device_op_read.h | 502 ++
.../mavlink_msg_device_op_read_reply.h | 390 ++
.../mavlink_msg_device_op_write.h | 531 ++
.../mavlink_msg_device_op_write_reply.h | 288 +
.../mavlink_msg_digicam_configure.h | 540 ++
.../mavlink_msg_digicam_control.h | 512 ++
.../mavlink_msg_ekf_status_report.h | 428 ++
.../mavlink_msg_esc_telemetry_13_to_16.h | 405 ++
.../mavlink_msg_esc_telemetry_17_to_20.h | 405 ++
.../mavlink_msg_esc_telemetry_1_to_4.h | 405 ++
.../mavlink_msg_esc_telemetry_21_to_24.h | 405 ++
.../mavlink_msg_esc_telemetry_25_to_28.h | 405 ++
.../mavlink_msg_esc_telemetry_29_to_32.h | 405 ++
.../mavlink_msg_esc_telemetry_5_to_8.h | 405 ++
.../mavlink_msg_esc_telemetry_9_to_12.h | 405 ++
.../mavlink_msg_fence_fetch_point.h | 316 ++
.../ardupilotmega/mavlink_msg_fence_point.h | 400 ++
.../mavlink_msg_gimbal_control.h | 372 ++
.../ardupilotmega/mavlink_msg_gimbal_report.h | 568 ++
.../mavlink_msg_gimbal_torque_cmd_report.h | 372 ++
.../mavlink_msg_gopro_get_request.h | 316 ++
.../mavlink_msg_gopro_get_response.h | 306 ++
.../mavlink_msg_gopro_heartbeat.h | 316 ++
.../mavlink_msg_gopro_set_request.h | 334 ++
.../mavlink_msg_gopro_set_response.h | 288 +
.../ardupilotmega/mavlink_msg_hwstatus.h | 288 +
.../ardupilotmega/mavlink_msg_led_control.h | 390 ++
.../ardupilotmega/mavlink_msg_limits_status.h | 484 ++
.../mavlink_msg_mag_cal_progress.h | 474 ++
.../ardupilotmega/mavlink_msg_mcu_status.h | 372 ++
.../ardupilotmega/mavlink_msg_meminfo.h | 316 ++
.../mavlink_msg_mount_configure.h | 400 ++
.../ardupilotmega/mavlink_msg_mount_control.h | 400 ++
.../ardupilotmega/mavlink_msg_mount_status.h | 400 ++
.../mavlink_msg_named_value_string.h | 307 ++
.../mavlink_msg_obstacle_distance_3d.h | 484 ++
.../mavlink_msg_osd_param_config.h | 502 ++
.../mavlink_msg_osd_param_config_reply.h | 288 +
.../mavlink_msg_osd_param_show_config.h | 372 ++
.../mavlink_msg_osd_param_show_config_reply.h | 418 ++
.../ardupilotmega/mavlink_msg_pid_tuning.h | 484 ++
.../MAVLink/ardupilotmega/mavlink_msg_radio.h | 428 ++
.../mavlink_msg_rally_fetch_point.h | 316 ++
.../ardupilotmega/mavlink_msg_rally_point.h | 512 ++
.../ardupilotmega/mavlink_msg_rangefinder.h | 288 +
.../mavlink_msg_remote_log_block_status.h | 344 ++
.../mavlink_msg_remote_log_data_block.h | 334 ++
.../MAVLink/ardupilotmega/mavlink_msg_rpm.h | 288 +
.../mavlink_msg_secure_command.h | 418 ++
.../mavlink_msg_secure_command_reply.h | 362 ++
.../mavlink_msg_sensor_offsets.h | 568 ++
.../mavlink_msg_set_mag_offsets.h | 372 ++
.../ardupilotmega/mavlink_msg_simstate.h | 540 ++
.../mavlink_msg_vision_position_delta.h | 363 ++
.../ardupilotmega/mavlink_msg_water_depth.h | 540 ++
.../MAVLink/ardupilotmega/mavlink_msg_wind.h | 316 ++
lib/main/MAVLink/ardupilotmega/testsuite.h | 4808 +++++++++++++++++
lib/main/MAVLink/ardupilotmega/version.h | 14 +
lib/main/MAVLink/common/common.h | 464 +-
lib/main/MAVLink/common/mavlink.h | 2 +-
.../MAVLink/common/mavlink_msg_adsb_vehicle.h | 24 +-
.../MAVLink/common/mavlink_msg_airspeed.h | 372 ++
.../MAVLink/common/mavlink_msg_ais_vessel.h | 36 +-
.../common/mavlink_msg_attitude_target.h | 12 +-
.../common/mavlink_msg_camera_information.h | 12 +-
.../mavlink_msg_change_operator_control.h | 12 +-
.../MAVLink/common/mavlink_msg_data_stream.h | 12 +-
.../MAVLink/common/mavlink_msg_esc_info.h | 12 +-
.../MAVLink/common/mavlink_msg_esc_status.h | 12 +-
...avlink_msg_figure_eight_execution_status.h | 456 ++
.../mavlink_msg_file_transfer_protocol.h | 12 +-
.../mavlink_msg_gimbal_device_information.h | 82 +-
.../mavlink_msg_global_position_sensor.h | 596 ++
.../common/mavlink_msg_manual_control.h | 12 +-
.../mavlink_msg_onboard_computer_status.h | 54 +-
.../MAVLink/common/mavlink_msg_param_error.h | 362 ++
.../mavlink_msg_protocol_version.h | 0
.../MAVLink/common/mavlink_msg_relay_status.h | 316 ++
.../common/mavlink_msg_request_data_stream.h | 12 +-
.../common/mavlink_msg_set_attitude_target.h | 12 +-
.../MAVLink/common/mavlink_msg_statustext.h | 12 +-
lib/main/MAVLink/common/testsuite.h | 479 +-
lib/main/MAVLink/common/version.h | 2 +-
lib/main/MAVLink/csAirLink/csAirLink.h | 77 +
lib/main/MAVLink/csAirLink/mavlink.h | 34 +
.../csAirLink/mavlink_msg_airlink_auth.h | 289 +
.../mavlink_msg_airlink_auth_response.h | 260 +
lib/main/MAVLink/csAirLink/testsuite.h | 156 +
lib/main/MAVLink/csAirLink/version.h | 14 +
lib/main/MAVLink/cubepilot/cubepilot.h | 70 +
lib/main/MAVLink/cubepilot/mavlink.h | 34 +
...vlink_msg_cubepilot_firmware_update_resp.h | 316 ++
...link_msg_cubepilot_firmware_update_start.h | 344 ++
.../cubepilot/mavlink_msg_cubepilot_raw_rc.h | 260 +
.../cubepilot/mavlink_msg_herelink_telem.h | 428 ++
...nk_msg_herelink_video_stream_information.h | 446 ++
lib/main/MAVLink/cubepilot/testsuite.h | 353 ++
lib/main/MAVLink/cubepilot/version.h | 14 +
lib/main/MAVLink/generate.sh | 2 +-
lib/main/MAVLink/icarous/icarous.h | 93 +
lib/main/MAVLink/icarous/mavlink.h | 34 +
.../icarous/mavlink_msg_icarous_heartbeat.h | 260 +
.../mavlink_msg_icarous_kinematic_bands.h | 680 +++
lib/main/MAVLink/icarous/testsuite.h | 170 +
lib/main/MAVLink/icarous/version.h | 14 +
lib/main/MAVLink/loweheiser/loweheiser.h | 66 +
lib/main/MAVLink/loweheiser/mavlink.h | 34 +
.../mavlink_msg_loweheiser_gov_efi.h | 876 +++
lib/main/MAVLink/loweheiser/testsuite.h | 117 +
lib/main/MAVLink/loweheiser/version.h | 14 +
lib/main/MAVLink/minimal/mavlink.h | 2 +-
lib/main/MAVLink/minimal/minimal.h | 9 +-
lib/main/MAVLink/minimal/testsuite.h | 64 -
lib/main/MAVLink/minimal/version.h | 4 +-
lib/main/MAVLink/standard/mavlink.h | 2 +-
.../mavlink_msg_global_position_int.h | 0
lib/main/MAVLink/standard/standard.h | 11 +-
lib/main/MAVLink/standard/testsuite.h | 68 +
lib/main/MAVLink/standard/version.h | 2 +-
lib/main/MAVLink/storm32/mavlink.h | 34 +
...sg_autopilot_state_for_gimbal_device_ext.h | 400 ++
.../mavlink_msg_frsky_passthrough_array.h | 306 ++
...mavlink_msg_mlrs_radio_link_flow_control.h | 372 ++
.../mavlink_msg_mlrs_radio_link_information.h | 615 +++
.../mavlink_msg_mlrs_radio_link_stats.h | 680 +++
.../storm32/mavlink_msg_param_value_array.h | 362 ++
.../storm32/mavlink_msg_qshot_status.h | 288 +
...vlink_msg_storm32_gimbal_manager_control.h | 502 ++
..._storm32_gimbal_manager_control_pitchyaw.h | 512 ++
..._msg_storm32_gimbal_manager_correct_roll.h | 372 ++
...k_msg_storm32_gimbal_manager_information.h | 484 ++
...avlink_msg_storm32_gimbal_manager_status.h | 372 ++
lib/main/MAVLink/storm32/storm32.h | 542 ++
lib/main/MAVLink/storm32/testsuite.h | 833 +++
lib/main/MAVLink/storm32/version.h | 14 +
lib/main/MAVLink/uAvionix/mavlink.h | 34 +
.../uAvionix/mavlink_msg_uavionix_adsb_get.h | 260 +
.../mavlink_msg_uavionix_adsb_out_cfg.h | 446 ++
...vlink_msg_uavionix_adsb_out_cfg_flightid.h | 260 +
...k_msg_uavionix_adsb_out_cfg_registration.h | 260 +
.../mavlink_msg_uavionix_adsb_out_control.h | 390 ++
.../mavlink_msg_uavionix_adsb_out_dynamic.h | 680 +++
.../mavlink_msg_uavionix_adsb_out_status.h | 390 ++
..._uavionix_adsb_transceiver_health_report.h | 260 +
lib/main/MAVLink/uAvionix/testsuite.h | 547 ++
lib/main/MAVLink/uAvionix/uAvionix.h | 282 +
lib/main/MAVLink/uAvionix/version.h | 14 +
src/main/mavlink/mavlink_modes.c | 8 +-
src/main/mavlink/mavlink_modes.h | 64 -
src/main/mavlink/mavlink_types.h | 2 +-
src/main/rx/mavlink.h | 2 +-
170 files changed, 54067 insertions(+), 673 deletions(-)
create mode 100644 lib/main/MAVLink/ardupilotmega/ardupilotmega.h
create mode 100644 lib/main/MAVLink/ardupilotmega/mavlink.h
create mode 100644 lib/main/MAVLink/ardupilotmega/mavlink_msg_adap_tuning.h
create mode 100644 lib/main/MAVLink/ardupilotmega/mavlink_msg_ahrs.h
create mode 100644 lib/main/MAVLink/ardupilotmega/mavlink_msg_ahrs2.h
create mode 100644 lib/main/MAVLink/ardupilotmega/mavlink_msg_ahrs3.h
create mode 100644 lib/main/MAVLink/ardupilotmega/mavlink_msg_airspeed_autocal.h
create mode 100644 lib/main/MAVLink/ardupilotmega/mavlink_msg_aoa_ssa.h
create mode 100644 lib/main/MAVLink/ardupilotmega/mavlink_msg_ap_adc.h
create mode 100644 lib/main/MAVLink/ardupilotmega/mavlink_msg_autopilot_version_request.h
create mode 100644 lib/main/MAVLink/ardupilotmega/mavlink_msg_battery2.h
create mode 100644 lib/main/MAVLink/ardupilotmega/mavlink_msg_camera_feedback.h
create mode 100644 lib/main/MAVLink/ardupilotmega/mavlink_msg_camera_status.h
create mode 100644 lib/main/MAVLink/ardupilotmega/mavlink_msg_compassmot_status.h
create mode 100644 lib/main/MAVLink/ardupilotmega/mavlink_msg_data16.h
create mode 100644 lib/main/MAVLink/ardupilotmega/mavlink_msg_data32.h
create mode 100644 lib/main/MAVLink/ardupilotmega/mavlink_msg_data64.h
create mode 100644 lib/main/MAVLink/ardupilotmega/mavlink_msg_data96.h
create mode 100644 lib/main/MAVLink/ardupilotmega/mavlink_msg_deepstall.h
create mode 100644 lib/main/MAVLink/ardupilotmega/mavlink_msg_device_op_read.h
create mode 100644 lib/main/MAVLink/ardupilotmega/mavlink_msg_device_op_read_reply.h
create mode 100644 lib/main/MAVLink/ardupilotmega/mavlink_msg_device_op_write.h
create mode 100644 lib/main/MAVLink/ardupilotmega/mavlink_msg_device_op_write_reply.h
create mode 100644 lib/main/MAVLink/ardupilotmega/mavlink_msg_digicam_configure.h
create mode 100644 lib/main/MAVLink/ardupilotmega/mavlink_msg_digicam_control.h
create mode 100644 lib/main/MAVLink/ardupilotmega/mavlink_msg_ekf_status_report.h
create mode 100644 lib/main/MAVLink/ardupilotmega/mavlink_msg_esc_telemetry_13_to_16.h
create mode 100644 lib/main/MAVLink/ardupilotmega/mavlink_msg_esc_telemetry_17_to_20.h
create mode 100644 lib/main/MAVLink/ardupilotmega/mavlink_msg_esc_telemetry_1_to_4.h
create mode 100644 lib/main/MAVLink/ardupilotmega/mavlink_msg_esc_telemetry_21_to_24.h
create mode 100644 lib/main/MAVLink/ardupilotmega/mavlink_msg_esc_telemetry_25_to_28.h
create mode 100644 lib/main/MAVLink/ardupilotmega/mavlink_msg_esc_telemetry_29_to_32.h
create mode 100644 lib/main/MAVLink/ardupilotmega/mavlink_msg_esc_telemetry_5_to_8.h
create mode 100644 lib/main/MAVLink/ardupilotmega/mavlink_msg_esc_telemetry_9_to_12.h
create mode 100644 lib/main/MAVLink/ardupilotmega/mavlink_msg_fence_fetch_point.h
create mode 100644 lib/main/MAVLink/ardupilotmega/mavlink_msg_fence_point.h
create mode 100644 lib/main/MAVLink/ardupilotmega/mavlink_msg_gimbal_control.h
create mode 100644 lib/main/MAVLink/ardupilotmega/mavlink_msg_gimbal_report.h
create mode 100644 lib/main/MAVLink/ardupilotmega/mavlink_msg_gimbal_torque_cmd_report.h
create mode 100644 lib/main/MAVLink/ardupilotmega/mavlink_msg_gopro_get_request.h
create mode 100644 lib/main/MAVLink/ardupilotmega/mavlink_msg_gopro_get_response.h
create mode 100644 lib/main/MAVLink/ardupilotmega/mavlink_msg_gopro_heartbeat.h
create mode 100644 lib/main/MAVLink/ardupilotmega/mavlink_msg_gopro_set_request.h
create mode 100644 lib/main/MAVLink/ardupilotmega/mavlink_msg_gopro_set_response.h
create mode 100644 lib/main/MAVLink/ardupilotmega/mavlink_msg_hwstatus.h
create mode 100644 lib/main/MAVLink/ardupilotmega/mavlink_msg_led_control.h
create mode 100644 lib/main/MAVLink/ardupilotmega/mavlink_msg_limits_status.h
create mode 100644 lib/main/MAVLink/ardupilotmega/mavlink_msg_mag_cal_progress.h
create mode 100644 lib/main/MAVLink/ardupilotmega/mavlink_msg_mcu_status.h
create mode 100644 lib/main/MAVLink/ardupilotmega/mavlink_msg_meminfo.h
create mode 100644 lib/main/MAVLink/ardupilotmega/mavlink_msg_mount_configure.h
create mode 100644 lib/main/MAVLink/ardupilotmega/mavlink_msg_mount_control.h
create mode 100644 lib/main/MAVLink/ardupilotmega/mavlink_msg_mount_status.h
create mode 100644 lib/main/MAVLink/ardupilotmega/mavlink_msg_named_value_string.h
create mode 100644 lib/main/MAVLink/ardupilotmega/mavlink_msg_obstacle_distance_3d.h
create mode 100644 lib/main/MAVLink/ardupilotmega/mavlink_msg_osd_param_config.h
create mode 100644 lib/main/MAVLink/ardupilotmega/mavlink_msg_osd_param_config_reply.h
create mode 100644 lib/main/MAVLink/ardupilotmega/mavlink_msg_osd_param_show_config.h
create mode 100644 lib/main/MAVLink/ardupilotmega/mavlink_msg_osd_param_show_config_reply.h
create mode 100644 lib/main/MAVLink/ardupilotmega/mavlink_msg_pid_tuning.h
create mode 100644 lib/main/MAVLink/ardupilotmega/mavlink_msg_radio.h
create mode 100644 lib/main/MAVLink/ardupilotmega/mavlink_msg_rally_fetch_point.h
create mode 100644 lib/main/MAVLink/ardupilotmega/mavlink_msg_rally_point.h
create mode 100644 lib/main/MAVLink/ardupilotmega/mavlink_msg_rangefinder.h
create mode 100644 lib/main/MAVLink/ardupilotmega/mavlink_msg_remote_log_block_status.h
create mode 100644 lib/main/MAVLink/ardupilotmega/mavlink_msg_remote_log_data_block.h
create mode 100644 lib/main/MAVLink/ardupilotmega/mavlink_msg_rpm.h
create mode 100644 lib/main/MAVLink/ardupilotmega/mavlink_msg_secure_command.h
create mode 100644 lib/main/MAVLink/ardupilotmega/mavlink_msg_secure_command_reply.h
create mode 100644 lib/main/MAVLink/ardupilotmega/mavlink_msg_sensor_offsets.h
create mode 100644 lib/main/MAVLink/ardupilotmega/mavlink_msg_set_mag_offsets.h
create mode 100644 lib/main/MAVLink/ardupilotmega/mavlink_msg_simstate.h
create mode 100644 lib/main/MAVLink/ardupilotmega/mavlink_msg_vision_position_delta.h
create mode 100644 lib/main/MAVLink/ardupilotmega/mavlink_msg_water_depth.h
create mode 100644 lib/main/MAVLink/ardupilotmega/mavlink_msg_wind.h
create mode 100644 lib/main/MAVLink/ardupilotmega/testsuite.h
create mode 100644 lib/main/MAVLink/ardupilotmega/version.h
create mode 100644 lib/main/MAVLink/common/mavlink_msg_airspeed.h
create mode 100644 lib/main/MAVLink/common/mavlink_msg_figure_eight_execution_status.h
create mode 100644 lib/main/MAVLink/common/mavlink_msg_global_position_sensor.h
create mode 100644 lib/main/MAVLink/common/mavlink_msg_param_error.h
rename lib/main/MAVLink/{minimal => common}/mavlink_msg_protocol_version.h (100%)
create mode 100644 lib/main/MAVLink/common/mavlink_msg_relay_status.h
create mode 100644 lib/main/MAVLink/csAirLink/csAirLink.h
create mode 100644 lib/main/MAVLink/csAirLink/mavlink.h
create mode 100644 lib/main/MAVLink/csAirLink/mavlink_msg_airlink_auth.h
create mode 100644 lib/main/MAVLink/csAirLink/mavlink_msg_airlink_auth_response.h
create mode 100644 lib/main/MAVLink/csAirLink/testsuite.h
create mode 100644 lib/main/MAVLink/csAirLink/version.h
create mode 100644 lib/main/MAVLink/cubepilot/cubepilot.h
create mode 100644 lib/main/MAVLink/cubepilot/mavlink.h
create mode 100644 lib/main/MAVLink/cubepilot/mavlink_msg_cubepilot_firmware_update_resp.h
create mode 100644 lib/main/MAVLink/cubepilot/mavlink_msg_cubepilot_firmware_update_start.h
create mode 100644 lib/main/MAVLink/cubepilot/mavlink_msg_cubepilot_raw_rc.h
create mode 100644 lib/main/MAVLink/cubepilot/mavlink_msg_herelink_telem.h
create mode 100644 lib/main/MAVLink/cubepilot/mavlink_msg_herelink_video_stream_information.h
create mode 100644 lib/main/MAVLink/cubepilot/testsuite.h
create mode 100644 lib/main/MAVLink/cubepilot/version.h
create mode 100644 lib/main/MAVLink/icarous/icarous.h
create mode 100644 lib/main/MAVLink/icarous/mavlink.h
create mode 100644 lib/main/MAVLink/icarous/mavlink_msg_icarous_heartbeat.h
create mode 100644 lib/main/MAVLink/icarous/mavlink_msg_icarous_kinematic_bands.h
create mode 100644 lib/main/MAVLink/icarous/testsuite.h
create mode 100644 lib/main/MAVLink/icarous/version.h
create mode 100644 lib/main/MAVLink/loweheiser/loweheiser.h
create mode 100644 lib/main/MAVLink/loweheiser/mavlink.h
create mode 100644 lib/main/MAVLink/loweheiser/mavlink_msg_loweheiser_gov_efi.h
create mode 100644 lib/main/MAVLink/loweheiser/testsuite.h
create mode 100644 lib/main/MAVLink/loweheiser/version.h
rename lib/main/MAVLink/{common => standard}/mavlink_msg_global_position_int.h (100%)
mode change 100755 => 100644
create mode 100644 lib/main/MAVLink/storm32/mavlink.h
create mode 100644 lib/main/MAVLink/storm32/mavlink_msg_autopilot_state_for_gimbal_device_ext.h
create mode 100644 lib/main/MAVLink/storm32/mavlink_msg_frsky_passthrough_array.h
create mode 100644 lib/main/MAVLink/storm32/mavlink_msg_mlrs_radio_link_flow_control.h
create mode 100644 lib/main/MAVLink/storm32/mavlink_msg_mlrs_radio_link_information.h
create mode 100644 lib/main/MAVLink/storm32/mavlink_msg_mlrs_radio_link_stats.h
create mode 100644 lib/main/MAVLink/storm32/mavlink_msg_param_value_array.h
create mode 100644 lib/main/MAVLink/storm32/mavlink_msg_qshot_status.h
create mode 100644 lib/main/MAVLink/storm32/mavlink_msg_storm32_gimbal_manager_control.h
create mode 100644 lib/main/MAVLink/storm32/mavlink_msg_storm32_gimbal_manager_control_pitchyaw.h
create mode 100644 lib/main/MAVLink/storm32/mavlink_msg_storm32_gimbal_manager_correct_roll.h
create mode 100644 lib/main/MAVLink/storm32/mavlink_msg_storm32_gimbal_manager_information.h
create mode 100644 lib/main/MAVLink/storm32/mavlink_msg_storm32_gimbal_manager_status.h
create mode 100644 lib/main/MAVLink/storm32/storm32.h
create mode 100644 lib/main/MAVLink/storm32/testsuite.h
create mode 100644 lib/main/MAVLink/storm32/version.h
create mode 100644 lib/main/MAVLink/uAvionix/mavlink.h
create mode 100644 lib/main/MAVLink/uAvionix/mavlink_msg_uavionix_adsb_get.h
create mode 100644 lib/main/MAVLink/uAvionix/mavlink_msg_uavionix_adsb_out_cfg.h
create mode 100644 lib/main/MAVLink/uAvionix/mavlink_msg_uavionix_adsb_out_cfg_flightid.h
create mode 100644 lib/main/MAVLink/uAvionix/mavlink_msg_uavionix_adsb_out_cfg_registration.h
create mode 100644 lib/main/MAVLink/uAvionix/mavlink_msg_uavionix_adsb_out_control.h
create mode 100644 lib/main/MAVLink/uAvionix/mavlink_msg_uavionix_adsb_out_dynamic.h
create mode 100644 lib/main/MAVLink/uAvionix/mavlink_msg_uavionix_adsb_out_status.h
create mode 100644 lib/main/MAVLink/uAvionix/mavlink_msg_uavionix_adsb_transceiver_health_report.h
create mode 100644 lib/main/MAVLink/uAvionix/testsuite.h
create mode 100644 lib/main/MAVLink/uAvionix/uAvionix.h
create mode 100644 lib/main/MAVLink/uAvionix/version.h
diff --git a/lib/main/MAVLink/ardupilotmega/ardupilotmega.h b/lib/main/MAVLink/ardupilotmega/ardupilotmega.h
new file mode 100644
index 00000000000..f598cb10e24
--- /dev/null
+++ b/lib/main/MAVLink/ardupilotmega/ardupilotmega.h
@@ -0,0 +1,876 @@
+/** @file
+ * @brief MAVLink comm protocol generated from ardupilotmega.xml
+ * @see http://mavlink.org
+ */
+#pragma once
+#ifndef MAVLINK_ARDUPILOTMEGA_H
+#define MAVLINK_ARDUPILOTMEGA_H
+
+#ifndef MAVLINK_H
+ #error Wrong include order: MAVLINK_ARDUPILOTMEGA.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_ARDUPILOTMEGA_XML_HASH -8353338523788949766
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+// MESSAGE LENGTHS AND CRCS
+
+#ifndef MAVLINK_MESSAGE_LENGTHS
+#define MAVLINK_MESSAGE_LENGTHS {}
+#endif
+
+#ifndef MAVLINK_MESSAGE_CRCS
+#define MAVLINK_MESSAGE_CRCS {{0, 50, 9, 9, 0, 0, 0}, {1, 124, 31, 43, 0, 0, 0}, {2, 137, 12, 12, 0, 0, 0}, {4, 237, 14, 14, 3, 12, 13}, {5, 217, 28, 28, 1, 0, 0}, {6, 104, 3, 3, 0, 0, 0}, {7, 119, 32, 32, 0, 0, 0}, {8, 117, 36, 36, 0, 0, 0}, {11, 89, 6, 6, 1, 4, 0}, {20, 214, 20, 20, 3, 2, 3}, {21, 159, 2, 2, 3, 0, 1}, {22, 220, 25, 25, 0, 0, 0}, {23, 168, 23, 23, 3, 4, 5}, {24, 24, 30, 52, 0, 0, 0}, {25, 23, 101, 101, 0, 0, 0}, {26, 170, 22, 24, 0, 0, 0}, {27, 144, 26, 29, 0, 0, 0}, {28, 67, 16, 16, 0, 0, 0}, {29, 115, 14, 16, 0, 0, 0}, {30, 39, 28, 28, 0, 0, 0}, {31, 246, 32, 48, 0, 0, 0}, {32, 185, 28, 28, 0, 0, 0}, {33, 104, 28, 28, 0, 0, 0}, {34, 237, 22, 22, 0, 0, 0}, {35, 244, 22, 22, 0, 0, 0}, {36, 222, 21, 37, 0, 0, 0}, {37, 212, 6, 7, 3, 4, 5}, {38, 9, 6, 7, 3, 4, 5}, {39, 254, 37, 38, 3, 32, 33}, {40, 230, 4, 5, 3, 2, 3}, {41, 28, 4, 4, 3, 2, 3}, {42, 28, 2, 18, 0, 0, 0}, {43, 132, 2, 3, 3, 0, 1}, {44, 221, 4, 9, 3, 2, 3}, {45, 232, 2, 3, 3, 0, 1}, {46, 11, 2, 2, 0, 0, 0}, {47, 153, 3, 8, 3, 0, 1}, {48, 41, 13, 21, 1, 12, 0}, {49, 39, 12, 20, 0, 0, 0}, {50, 78, 37, 37, 3, 18, 19}, {51, 196, 4, 5, 3, 2, 3}, {54, 15, 27, 27, 3, 24, 25}, {55, 3, 25, 25, 0, 0, 0}, {61, 167, 72, 72, 0, 0, 0}, {62, 183, 26, 26, 0, 0, 0}, {63, 119, 181, 181, 0, 0, 0}, {64, 191, 225, 225, 0, 0, 0}, {65, 118, 42, 42, 0, 0, 0}, {66, 148, 6, 6, 3, 2, 3}, {67, 21, 4, 4, 0, 0, 0}, {69, 243, 11, 30, 1, 10, 0}, {70, 124, 18, 38, 3, 16, 17}, {73, 38, 37, 38, 3, 32, 33}, {74, 20, 20, 20, 0, 0, 0}, {75, 158, 35, 35, 3, 30, 31}, {76, 152, 33, 33, 3, 30, 31}, {77, 143, 3, 10, 3, 8, 9}, {80, 14, 4, 4, 3, 2, 3}, {81, 106, 22, 22, 0, 0, 0}, {82, 49, 39, 51, 3, 36, 37}, {83, 22, 37, 37, 0, 0, 0}, {84, 143, 53, 53, 3, 50, 51}, {85, 140, 51, 51, 0, 0, 0}, {86, 5, 53, 53, 3, 50, 51}, {87, 150, 51, 51, 0, 0, 0}, {89, 231, 28, 28, 0, 0, 0}, {90, 183, 56, 56, 0, 0, 0}, {91, 63, 42, 42, 0, 0, 0}, {92, 54, 33, 33, 0, 0, 0}, {93, 47, 81, 81, 0, 0, 0}, {100, 175, 26, 34, 0, 0, 0}, {101, 102, 32, 117, 0, 0, 0}, {102, 158, 32, 117, 0, 0, 0}, {103, 208, 20, 57, 0, 0, 0}, {104, 56, 32, 116, 0, 0, 0}, {105, 93, 62, 63, 0, 0, 0}, {106, 138, 44, 44, 0, 0, 0}, {107, 108, 64, 65, 0, 0, 0}, {108, 32, 84, 92, 0, 0, 0}, {109, 185, 9, 9, 0, 0, 0}, {110, 84, 254, 254, 3, 1, 2}, {111, 34, 16, 18, 3, 16, 17}, {112, 174, 12, 12, 0, 0, 0}, {113, 124, 36, 39, 0, 0, 0}, {114, 237, 44, 44, 0, 0, 0}, {115, 4, 64, 64, 0, 0, 0}, {116, 76, 22, 24, 0, 0, 0}, {117, 128, 6, 6, 3, 4, 5}, {118, 56, 14, 14, 0, 0, 0}, {119, 116, 12, 12, 3, 10, 11}, {120, 134, 97, 97, 0, 0, 0}, {121, 237, 2, 2, 3, 0, 1}, {122, 203, 2, 2, 3, 0, 1}, {123, 250, 113, 113, 3, 0, 1}, {124, 87, 35, 57, 0, 0, 0}, {125, 203, 6, 6, 0, 0, 0}, {126, 220, 79, 81, 3, 79, 80}, {127, 25, 35, 35, 0, 0, 0}, {128, 226, 35, 35, 0, 0, 0}, {129, 46, 22, 24, 0, 0, 0}, {130, 29, 13, 13, 0, 0, 0}, {131, 223, 255, 255, 0, 0, 0}, {132, 85, 14, 39, 0, 0, 0}, {133, 6, 18, 18, 0, 0, 0}, {134, 229, 43, 43, 0, 0, 0}, {135, 203, 8, 8, 0, 0, 0}, {136, 1, 22, 22, 0, 0, 0}, {137, 195, 14, 16, 0, 0, 0}, {138, 109, 36, 120, 0, 0, 0}, {139, 168, 43, 43, 3, 41, 42}, {140, 181, 41, 41, 0, 0, 0}, {141, 47, 32, 32, 0, 0, 0}, {142, 72, 243, 243, 0, 0, 0}, {143, 131, 14, 16, 0, 0, 0}, {144, 127, 93, 93, 0, 0, 0}, {146, 103, 100, 100, 0, 0, 0}, {147, 154, 36, 54, 0, 0, 0}, {148, 178, 60, 78, 0, 0, 0}, {149, 200, 30, 60, 0, 0, 0}, {150, 134, 42, 42, 0, 0, 0}, {151, 219, 8, 8, 3, 6, 7}, {152, 208, 4, 8, 0, 0, 0}, {153, 188, 12, 12, 0, 0, 0}, {154, 84, 15, 15, 3, 6, 7}, {155, 22, 13, 13, 3, 4, 5}, {156, 19, 6, 6, 3, 0, 1}, {157, 21, 15, 15, 3, 12, 13}, {158, 134, 14, 15, 3, 12, 13}, {160, 78, 12, 12, 3, 8, 9}, {161, 68, 3, 3, 3, 0, 1}, {162, 189, 8, 9, 0, 0, 0}, {163, 127, 28, 28, 0, 0, 0}, {164, 154, 44, 44, 0, 0, 0}, {165, 21, 3, 3, 0, 0, 0}, {166, 21, 9, 9, 0, 0, 0}, {167, 144, 22, 22, 0, 0, 0}, {168, 1, 12, 12, 0, 0, 0}, {169, 234, 18, 18, 0, 0, 0}, {170, 73, 34, 34, 0, 0, 0}, {171, 181, 66, 66, 0, 0, 0}, {172, 22, 98, 98, 0, 0, 0}, {173, 83, 8, 8, 0, 0, 0}, {174, 167, 48, 48, 0, 0, 0}, {175, 138, 19, 19, 3, 14, 15}, {176, 234, 3, 3, 3, 0, 1}, {177, 240, 20, 20, 0, 0, 0}, {178, 47, 24, 24, 0, 0, 0}, {179, 189, 29, 29, 1, 26, 0}, {180, 52, 45, 47, 1, 42, 0}, {181, 174, 4, 4, 0, 0, 0}, {182, 229, 40, 40, 0, 0, 0}, {183, 85, 2, 2, 3, 0, 1}, {184, 159, 206, 206, 3, 4, 5}, {185, 186, 7, 7, 3, 4, 5}, {186, 72, 29, 29, 3, 0, 1}, {191, 92, 27, 27, 0, 0, 0}, {192, 36, 44, 54, 0, 0, 0}, {193, 71, 22, 26, 0, 0, 0}, {194, 98, 25, 33, 0, 0, 0}, {195, 120, 37, 37, 0, 0, 0}, {200, 134, 42, 42, 3, 40, 41}, {201, 205, 14, 14, 3, 12, 13}, {214, 69, 8, 8, 3, 6, 7}, {215, 101, 3, 3, 0, 0, 0}, {216, 50, 3, 3, 3, 0, 1}, {217, 202, 6, 6, 0, 0, 0}, {218, 17, 7, 7, 3, 0, 1}, {219, 162, 2, 2, 0, 0, 0}, {225, 208, 65, 73, 0, 0, 0}, {226, 207, 8, 8, 0, 0, 0}, {230, 163, 42, 42, 0, 0, 0}, {231, 105, 40, 40, 0, 0, 0}, {232, 151, 63, 65, 0, 0, 0}, {233, 35, 182, 182, 0, 0, 0}, {234, 150, 40, 40, 0, 0, 0}, {235, 179, 42, 42, 0, 0, 0}, {241, 90, 32, 32, 0, 0, 0}, {242, 104, 52, 60, 0, 0, 0}, {243, 85, 53, 61, 1, 52, 0}, {244, 95, 6, 6, 0, 0, 0}, {245, 130, 2, 2, 0, 0, 0}, {246, 184, 38, 38, 0, 0, 0}, {247, 81, 19, 19, 0, 0, 0}, {248, 8, 254, 254, 3, 3, 4}, {249, 204, 36, 36, 0, 0, 0}, {250, 49, 30, 30, 0, 0, 0}, {251, 170, 18, 18, 0, 0, 0}, {252, 44, 18, 18, 0, 0, 0}, {253, 83, 51, 54, 0, 0, 0}, {254, 46, 9, 9, 0, 0, 0}, {256, 71, 42, 42, 3, 8, 9}, {257, 131, 9, 9, 0, 0, 0}, {258, 187, 32, 232, 3, 0, 1}, {259, 92, 235, 237, 0, 0, 0}, {260, 146, 5, 14, 0, 0, 0}, {261, 179, 27, 61, 0, 0, 0}, {262, 12, 18, 23, 0, 0, 0}, {263, 133, 255, 255, 0, 0, 0}, {264, 49, 28, 32, 0, 0, 0}, {265, 26, 16, 20, 0, 0, 0}, {266, 193, 255, 255, 3, 2, 3}, {267, 35, 255, 255, 3, 2, 3}, {268, 14, 4, 4, 3, 2, 3}, {269, 109, 213, 215, 0, 0, 0}, {270, 59, 19, 20, 0, 0, 0}, {271, 22, 52, 53, 0, 0, 0}, {275, 126, 31, 32, 0, 0, 0}, {276, 18, 49, 50, 0, 0, 0}, {277, 62, 30, 30, 0, 0, 0}, {280, 70, 33, 33, 0, 0, 0}, {281, 48, 13, 13, 0, 0, 0}, {282, 123, 35, 35, 3, 32, 33}, {283, 74, 144, 149, 0, 0, 0}, {284, 99, 32, 32, 3, 30, 31}, {285, 137, 40, 49, 3, 38, 39}, {286, 210, 53, 57, 3, 50, 51}, {287, 1, 23, 23, 3, 20, 21}, {288, 20, 23, 23, 3, 20, 21}, {290, 251, 46, 46, 0, 0, 0}, {291, 10, 57, 57, 0, 0, 0}, {295, 234, 12, 12, 0, 0, 0}, {296, 158, 41, 41, 3, 36, 37}, {299, 19, 96, 98, 0, 0, 0}, {300, 217, 22, 22, 0, 0, 0}, {301, 243, 58, 58, 0, 0, 0}, {310, 28, 17, 17, 0, 0, 0}, {311, 95, 116, 116, 0, 0, 0}, {320, 243, 20, 20, 3, 2, 3}, {321, 88, 2, 2, 3, 0, 1}, {322, 243, 149, 149, 0, 0, 0}, {323, 78, 147, 147, 3, 0, 1}, {324, 132, 146, 146, 0, 0, 0}, {330, 23, 158, 167, 0, 0, 0}, {331, 91, 230, 233, 0, 0, 0}, {332, 236, 239, 239, 0, 0, 0}, {333, 231, 109, 109, 0, 0, 0}, {334, 72, 10, 10, 0, 0, 0}, {335, 225, 24, 24, 0, 0, 0}, {336, 245, 84, 84, 0, 0, 0}, {339, 199, 5, 5, 0, 0, 0}, {340, 99, 70, 70, 0, 0, 0}, {345, 209, 21, 21, 3, 2, 3}, {350, 232, 20, 252, 0, 0, 0}, {360, 11, 25, 25, 0, 0, 0}, {361, 93, 33, 33, 0, 0, 0}, {370, 75, 87, 109, 0, 0, 0}, {371, 10, 26, 26, 0, 0, 0}, {372, 26, 140, 140, 0, 0, 0}, {373, 117, 42, 42, 0, 0, 0}, {375, 251, 140, 140, 0, 0, 0}, {376, 199, 8, 8, 0, 0, 0}, {380, 232, 20, 20, 0, 0, 0}, {385, 147, 133, 133, 3, 2, 3}, {386, 132, 16, 16, 3, 4, 5}, {387, 4, 72, 72, 3, 4, 5}, {388, 8, 37, 37, 3, 32, 33}, {390, 156, 238, 240, 0, 0, 0}, {395, 0, 212, 212, 0, 0, 0}, {396, 50, 160, 160, 0, 0, 0}, {397, 182, 108, 108, 0, 0, 0}, {400, 110, 254, 254, 3, 4, 5}, {401, 183, 6, 6, 3, 4, 5}, {410, 160, 53, 53, 0, 0, 0}, {411, 106, 3, 3, 0, 0, 0}, {412, 33, 6, 6, 3, 4, 5}, {413, 77, 7, 7, 3, 4, 5}, {435, 134, 46, 46, 0, 0, 0}, {436, 193, 9, 9, 0, 0, 0}, {437, 30, 1, 1, 0, 0, 0}, {440, 66, 35, 35, 0, 0, 0}, {9000, 113, 137, 137, 0, 0, 0}, {9005, 117, 34, 34, 0, 0, 0}, {10001, 209, 20, 20, 0, 0, 0}, {10002, 186, 41, 41, 0, 0, 0}, {10003, 4, 1, 1, 0, 0, 0}, {10004, 133, 9, 9, 0, 0, 0}, {10005, 103, 9, 9, 0, 0, 0}, {10006, 193, 4, 4, 0, 0, 0}, {10007, 71, 17, 17, 0, 0, 0}, {10008, 240, 14, 14, 0, 0, 0}, {10151, 195, 85, 85, 0, 0, 0}, {11000, 134, 51, 52, 3, 4, 5}, {11001, 15, 135, 136, 0, 0, 0}, {11002, 234, 179, 180, 3, 4, 5}, {11003, 64, 5, 5, 0, 0, 0}, {11004, 11, 232, 232, 3, 8, 9}, {11005, 93, 230, 230, 0, 0, 0}, {11010, 46, 49, 49, 0, 0, 0}, {11011, 106, 44, 44, 0, 0, 0}, {11020, 205, 16, 16, 0, 0, 0}, {11030, 144, 44, 44, 0, 0, 0}, {11031, 133, 44, 44, 0, 0, 0}, {11032, 85, 44, 44, 0, 0, 0}, {11033, 195, 37, 37, 3, 16, 17}, {11034, 79, 5, 5, 0, 0, 0}, {11035, 128, 8, 8, 3, 4, 5}, {11036, 177, 34, 34, 0, 0, 0}, {11037, 130, 28, 28, 0, 0, 0}, {11038, 47, 38, 38, 0, 0, 0}, {11039, 142, 9, 9, 0, 0, 0}, {11040, 132, 44, 44, 0, 0, 0}, {11041, 208, 44, 44, 0, 0, 0}, {11042, 201, 44, 44, 0, 0, 0}, {11043, 193, 44, 44, 0, 0, 0}, {11044, 189, 44, 44, 0, 0, 0}, {11060, 162, 78, 78, 0, 0, 0}, {12900, 114, 44, 44, 3, 0, 1}, {12901, 254, 59, 59, 3, 30, 31}, {12902, 140, 53, 53, 3, 4, 5}, {12903, 249, 46, 46, 3, 0, 1}, {12904, 77, 54, 54, 3, 28, 29}, {12905, 49, 43, 43, 3, 0, 1}, {12915, 94, 249, 249, 3, 0, 1}, {12918, 139, 51, 51, 0, 0, 0}, {12919, 7, 18, 18, 3, 16, 17}, {12920, 20, 5, 5, 0, 0, 0}, {42000, 227, 1, 1, 0, 0, 0}, {42001, 239, 46, 46, 0, 0, 0}, {50001, 246, 32, 32, 0, 0, 0}, {50002, 181, 246, 246, 0, 0, 0}, {50003, 62, 19, 19, 0, 0, 0}, {50004, 240, 10, 10, 3, 8, 9}, {50005, 152, 6, 6, 3, 4, 5}, {52000, 13, 100, 100, 0, 0, 0}, {52001, 239, 1, 1, 0, 0, 0}}
+#endif
+
+#include "../protocol.h"
+
+#define MAVLINK_ENABLED_ARDUPILOTMEGA
+
+// ENUM DEFINITIONS
+
+
+/** @brief */
+#ifndef HAVE_ENUM_ACCELCAL_VEHICLE_POS
+#define HAVE_ENUM_ACCELCAL_VEHICLE_POS
+typedef enum ACCELCAL_VEHICLE_POS
+{
+ ACCELCAL_VEHICLE_POS_LEVEL=1, /* | */
+ ACCELCAL_VEHICLE_POS_LEFT=2, /* | */
+ ACCELCAL_VEHICLE_POS_RIGHT=3, /* | */
+ ACCELCAL_VEHICLE_POS_NOSEDOWN=4, /* | */
+ ACCELCAL_VEHICLE_POS_NOSEUP=5, /* | */
+ ACCELCAL_VEHICLE_POS_BACK=6, /* | */
+ ACCELCAL_VEHICLE_POS_SUCCESS=16777215, /* | */
+ ACCELCAL_VEHICLE_POS_FAILED=16777216, /* | */
+ ACCELCAL_VEHICLE_POS_ENUM_END=16777217, /* | */
+} ACCELCAL_VEHICLE_POS;
+#endif
+
+/** @brief */
+#ifndef HAVE_ENUM_HEADING_TYPE
+#define HAVE_ENUM_HEADING_TYPE
+typedef enum HEADING_TYPE
+{
+ HEADING_TYPE_COURSE_OVER_GROUND=0, /* | */
+ HEADING_TYPE_HEADING=1, /* | */
+ HEADING_TYPE_DEFAULT=2, /* | */
+ HEADING_TYPE_ENUM_END=3, /* | */
+} HEADING_TYPE;
+#endif
+
+/** @brief */
+#ifndef HAVE_ENUM_SCRIPTING_CMD
+#define HAVE_ENUM_SCRIPTING_CMD
+typedef enum SCRIPTING_CMD
+{
+ SCRIPTING_CMD_REPL_START=0, /* Start a REPL session. | */
+ SCRIPTING_CMD_REPL_STOP=1, /* End a REPL session. | */
+ SCRIPTING_CMD_STOP=2, /* Stop execution of scripts. | */
+ SCRIPTING_CMD_STOP_AND_RESTART=3, /* Stop execution of scripts and restart. | */
+ SCRIPTING_CMD_ENUM_END=4, /* | */
+} SCRIPTING_CMD;
+#endif
+
+/** @brief */
+#ifndef HAVE_ENUM_SECURE_COMMAND_OP
+#define HAVE_ENUM_SECURE_COMMAND_OP
+typedef enum SECURE_COMMAND_OP
+{
+ SECURE_COMMAND_GET_SESSION_KEY=0, /* Get an 8 byte session key which is used for remote secure updates which operate on flight controller data such as bootloader public keys. Return data will be 8 bytes on success. The session key remains valid until either the flight controller reboots or another SECURE_COMMAND_GET_SESSION_KEY is run. | */
+ SECURE_COMMAND_GET_REMOTEID_SESSION_KEY=1, /* Get an 8 byte session key which is used for remote secure updates which operate on RemoteID module data. Return data will be 8 bytes on success. The session key remains valid until either the remote ID module reboots or another SECURE_COMMAND_GET_REMOTEID_SESSION_KEY is run. | */
+ SECURE_COMMAND_REMOVE_PUBLIC_KEYS=2, /* Remove range of public keys from the bootloader. Command data consists of two bytes, first byte if index of first public key to remove. Second byte is the number of keys to remove. If all keys are removed then secure boot is disabled and insecure firmware can be loaded. | */
+ SECURE_COMMAND_GET_PUBLIC_KEYS=3, /* Get current public keys from the bootloader. Command data consists of two bytes, first byte is index of first public key to fetch, 2nd byte is number of keys to fetch. Total data needs to fit in data portion of reply (max 6 keys for 32 byte keys). Reply data has the index of the first key in the first byte, followed by the keys. Returned keys may be less than the number of keys requested if there are less keys installed than requested. | */
+ SECURE_COMMAND_SET_PUBLIC_KEYS=4, /* Set current public keys in the bootloader. Data consists of a one byte public key index followed by the public keys. With 32 byte keys this allows for up to 6 keys to be set in one request. Keys outside of the range that is being set will remain unchanged. | */
+ SECURE_COMMAND_GET_REMOTEID_CONFIG=5, /* Get config data for remote ID module. This command should be sent to the component ID of the flight controller which will forward it to the RemoteID module either over mavlink or DroneCAN. Data format is specific to the RemoteID implementation, see RemoteID firmware documentation for details. | */
+ SECURE_COMMAND_SET_REMOTEID_CONFIG=6, /* Set config data for remote ID module. This command should be sent to the component ID of the flight controller which will forward it to the RemoteID module either over mavlink or DroneCAN. Data format is specific to the RemoteID implementation, see RemoteID firmware documentation for details. | */
+ SECURE_COMMAND_FLASH_BOOTLOADER=7, /* Flash bootloader from local storage. Data is the filename to use for the bootloader. This is intended to be used with MAVFtp to upload a new bootloader to a microSD before flashing. | */
+ SECURE_COMMAND_OP_ENUM_END=8, /* | */
+} SECURE_COMMAND_OP;
+#endif
+
+/** @brief */
+#ifndef HAVE_ENUM_LIMITS_STATE
+#define HAVE_ENUM_LIMITS_STATE
+typedef enum LIMITS_STATE
+{
+ LIMITS_INIT=0, /* Pre-initialization. | */
+ LIMITS_DISABLED=1, /* Disabled. | */
+ LIMITS_ENABLED=2, /* Checking limits. | */
+ LIMITS_TRIGGERED=3, /* A limit has been breached. | */
+ LIMITS_RECOVERING=4, /* Taking action e.g. Return/RTL. | */
+ LIMITS_RECOVERED=5, /* We're no longer in breach of a limit. | */
+ LIMITS_STATE_ENUM_END=6, /* | */
+} LIMITS_STATE;
+#endif
+
+/** @brief */
+#ifndef HAVE_ENUM_LIMIT_MODULE
+#define HAVE_ENUM_LIMIT_MODULE
+typedef enum LIMIT_MODULE
+{
+ LIMIT_GPSLOCK=1, /* Pre-initialization. | */
+ LIMIT_GEOFENCE=2, /* Disabled. | */
+ LIMIT_ALTITUDE=4, /* Checking limits. | */
+ LIMIT_MODULE_ENUM_END=5, /* | */
+} LIMIT_MODULE;
+#endif
+
+/** @brief Flags in RALLY_POINT message. */
+#ifndef HAVE_ENUM_RALLY_FLAGS
+#define HAVE_ENUM_RALLY_FLAGS
+typedef enum RALLY_FLAGS
+{
+ FAVORABLE_WIND=1, /* Flag set when requiring favorable winds for landing. | */
+ LAND_IMMEDIATELY=2, /* Flag set when plane is to immediately descend to break altitude and land without GCS intervention. Flag not set when plane is to loiter at Rally point until commanded to land. | */
+ ALT_FRAME_VALID=4, /* True if the following altitude frame value is valid. | */
+ ALT_FRAME=24, /* 2 bit value representing altitude frame. 0: absolute, 1: relative home, 2: relative origin, 3: relative terrain | */
+ RALLY_FLAGS_ENUM_END=25, /* | */
+} RALLY_FLAGS;
+#endif
+
+/** @brief */
+#ifndef HAVE_ENUM_CAMERA_STATUS_TYPES
+#define HAVE_ENUM_CAMERA_STATUS_TYPES
+typedef enum CAMERA_STATUS_TYPES
+{
+ CAMERA_STATUS_TYPE_HEARTBEAT=0, /* Camera heartbeat, announce camera component ID at 1Hz. | */
+ CAMERA_STATUS_TYPE_TRIGGER=1, /* Camera image triggered. | */
+ CAMERA_STATUS_TYPE_DISCONNECT=2, /* Camera connection lost. | */
+ CAMERA_STATUS_TYPE_ERROR=3, /* Camera unknown error. | */
+ CAMERA_STATUS_TYPE_LOWBATT=4, /* Camera battery low. Parameter p1 shows reported voltage. | */
+ CAMERA_STATUS_TYPE_LOWSTORE=5, /* Camera storage low. Parameter p1 shows reported shots remaining. | */
+ CAMERA_STATUS_TYPE_LOWSTOREV=6, /* Camera storage low. Parameter p1 shows reported video minutes remaining. | */
+ CAMERA_STATUS_TYPES_ENUM_END=7, /* | */
+} CAMERA_STATUS_TYPES;
+#endif
+
+/** @brief */
+#ifndef HAVE_ENUM_CAMERA_FEEDBACK_FLAGS
+#define HAVE_ENUM_CAMERA_FEEDBACK_FLAGS
+typedef enum CAMERA_FEEDBACK_FLAGS
+{
+ CAMERA_FEEDBACK_PHOTO=0, /* Shooting photos, not video. | */
+ CAMERA_FEEDBACK_VIDEO=1, /* Shooting video, not stills. | */
+ CAMERA_FEEDBACK_BADEXPOSURE=2, /* Unable to achieve requested exposure (e.g. shutter speed too low). | */
+ CAMERA_FEEDBACK_CLOSEDLOOP=3, /* Closed loop feedback from camera, we know for sure it has successfully taken a picture. | */
+ CAMERA_FEEDBACK_OPENLOOP=4, /* Open loop camera, an image trigger has been requested but we can't know for sure it has successfully taken a picture. | */
+ CAMERA_FEEDBACK_FLAGS_ENUM_END=5, /* | */
+} CAMERA_FEEDBACK_FLAGS;
+#endif
+
+/** @brief */
+#ifndef HAVE_ENUM_MAV_MODE_GIMBAL
+#define HAVE_ENUM_MAV_MODE_GIMBAL
+typedef enum MAV_MODE_GIMBAL
+{
+ MAV_MODE_GIMBAL_UNINITIALIZED=0, /* Gimbal is powered on but has not started initializing yet. | */
+ MAV_MODE_GIMBAL_CALIBRATING_PITCH=1, /* Gimbal is currently running calibration on the pitch axis. | */
+ MAV_MODE_GIMBAL_CALIBRATING_ROLL=2, /* Gimbal is currently running calibration on the roll axis. | */
+ MAV_MODE_GIMBAL_CALIBRATING_YAW=3, /* Gimbal is currently running calibration on the yaw axis. | */
+ MAV_MODE_GIMBAL_INITIALIZED=4, /* Gimbal has finished calibrating and initializing, but is relaxed pending reception of first rate command from copter. | */
+ MAV_MODE_GIMBAL_ACTIVE=5, /* Gimbal is actively stabilizing. | */
+ MAV_MODE_GIMBAL_RATE_CMD_TIMEOUT=6, /* Gimbal is relaxed because it missed more than 10 expected rate command messages in a row. Gimbal will move back to active mode when it receives a new rate command. | */
+ MAV_MODE_GIMBAL_ENUM_END=7, /* | */
+} MAV_MODE_GIMBAL;
+#endif
+
+/** @brief */
+#ifndef HAVE_ENUM_GIMBAL_AXIS
+#define HAVE_ENUM_GIMBAL_AXIS
+typedef enum GIMBAL_AXIS
+{
+ GIMBAL_AXIS_YAW=0, /* Gimbal yaw axis. | */
+ GIMBAL_AXIS_PITCH=1, /* Gimbal pitch axis. | */
+ GIMBAL_AXIS_ROLL=2, /* Gimbal roll axis. | */
+ GIMBAL_AXIS_ENUM_END=3, /* | */
+} GIMBAL_AXIS;
+#endif
+
+/** @brief */
+#ifndef HAVE_ENUM_GIMBAL_AXIS_CALIBRATION_STATUS
+#define HAVE_ENUM_GIMBAL_AXIS_CALIBRATION_STATUS
+typedef enum GIMBAL_AXIS_CALIBRATION_STATUS
+{
+ GIMBAL_AXIS_CALIBRATION_STATUS_IN_PROGRESS=0, /* Axis calibration is in progress. | */
+ GIMBAL_AXIS_CALIBRATION_STATUS_SUCCEEDED=1, /* Axis calibration succeeded. | */
+ GIMBAL_AXIS_CALIBRATION_STATUS_FAILED=2, /* Axis calibration failed. | */
+ GIMBAL_AXIS_CALIBRATION_STATUS_ENUM_END=3, /* | */
+} GIMBAL_AXIS_CALIBRATION_STATUS;
+#endif
+
+/** @brief */
+#ifndef HAVE_ENUM_GIMBAL_AXIS_CALIBRATION_REQUIRED
+#define HAVE_ENUM_GIMBAL_AXIS_CALIBRATION_REQUIRED
+typedef enum GIMBAL_AXIS_CALIBRATION_REQUIRED
+{
+ GIMBAL_AXIS_CALIBRATION_REQUIRED_UNKNOWN=0, /* Whether or not this axis requires calibration is unknown at this time. | */
+ GIMBAL_AXIS_CALIBRATION_REQUIRED_TRUE=1, /* This axis requires calibration. | */
+ GIMBAL_AXIS_CALIBRATION_REQUIRED_FALSE=2, /* This axis does not require calibration. | */
+ GIMBAL_AXIS_CALIBRATION_REQUIRED_ENUM_END=3, /* | */
+} GIMBAL_AXIS_CALIBRATION_REQUIRED;
+#endif
+
+/** @brief */
+#ifndef HAVE_ENUM_GOPRO_HEARTBEAT_STATUS
+#define HAVE_ENUM_GOPRO_HEARTBEAT_STATUS
+typedef enum GOPRO_HEARTBEAT_STATUS
+{
+ GOPRO_HEARTBEAT_STATUS_DISCONNECTED=0, /* No GoPro connected. | */
+ GOPRO_HEARTBEAT_STATUS_INCOMPATIBLE=1, /* The detected GoPro is not HeroBus compatible. | */
+ GOPRO_HEARTBEAT_STATUS_CONNECTED=2, /* A HeroBus compatible GoPro is connected. | */
+ GOPRO_HEARTBEAT_STATUS_ERROR=3, /* An unrecoverable error was encountered with the connected GoPro, it may require a power cycle. | */
+ GOPRO_HEARTBEAT_STATUS_ENUM_END=4, /* | */
+} GOPRO_HEARTBEAT_STATUS;
+#endif
+
+/** @brief */
+#ifndef HAVE_ENUM_GOPRO_HEARTBEAT_FLAGS
+#define HAVE_ENUM_GOPRO_HEARTBEAT_FLAGS
+typedef enum GOPRO_HEARTBEAT_FLAGS
+{
+ GOPRO_FLAG_RECORDING=1, /* GoPro is currently recording. | */
+ GOPRO_HEARTBEAT_FLAGS_ENUM_END=2, /* | */
+} GOPRO_HEARTBEAT_FLAGS;
+#endif
+
+/** @brief */
+#ifndef HAVE_ENUM_GOPRO_REQUEST_STATUS
+#define HAVE_ENUM_GOPRO_REQUEST_STATUS
+typedef enum GOPRO_REQUEST_STATUS
+{
+ GOPRO_REQUEST_SUCCESS=0, /* The write message with ID indicated succeeded. | */
+ GOPRO_REQUEST_FAILED=1, /* The write message with ID indicated failed. | */
+ GOPRO_REQUEST_STATUS_ENUM_END=2, /* | */
+} GOPRO_REQUEST_STATUS;
+#endif
+
+/** @brief */
+#ifndef HAVE_ENUM_GOPRO_COMMAND
+#define HAVE_ENUM_GOPRO_COMMAND
+typedef enum GOPRO_COMMAND
+{
+ GOPRO_COMMAND_POWER=0, /* (Get/Set). | */
+ GOPRO_COMMAND_CAPTURE_MODE=1, /* (Get/Set). | */
+ GOPRO_COMMAND_SHUTTER=2, /* (___/Set). | */
+ GOPRO_COMMAND_BATTERY=3, /* (Get/___). | */
+ GOPRO_COMMAND_MODEL=4, /* (Get/___). | */
+ GOPRO_COMMAND_VIDEO_SETTINGS=5, /* (Get/Set). | */
+ GOPRO_COMMAND_LOW_LIGHT=6, /* (Get/Set). | */
+ GOPRO_COMMAND_PHOTO_RESOLUTION=7, /* (Get/Set). | */
+ GOPRO_COMMAND_PHOTO_BURST_RATE=8, /* (Get/Set). | */
+ GOPRO_COMMAND_PROTUNE=9, /* (Get/Set). | */
+ GOPRO_COMMAND_PROTUNE_WHITE_BALANCE=10, /* (Get/Set) Hero 3+ Only. | */
+ GOPRO_COMMAND_PROTUNE_COLOUR=11, /* (Get/Set) Hero 3+ Only. | */
+ GOPRO_COMMAND_PROTUNE_GAIN=12, /* (Get/Set) Hero 3+ Only. | */
+ GOPRO_COMMAND_PROTUNE_SHARPNESS=13, /* (Get/Set) Hero 3+ Only. | */
+ GOPRO_COMMAND_PROTUNE_EXPOSURE=14, /* (Get/Set) Hero 3+ Only. | */
+ GOPRO_COMMAND_TIME=15, /* (Get/Set). | */
+ GOPRO_COMMAND_CHARGING=16, /* (Get/Set). | */
+ GOPRO_COMMAND_ENUM_END=17, /* | */
+} GOPRO_COMMAND;
+#endif
+
+/** @brief */
+#ifndef HAVE_ENUM_GOPRO_CAPTURE_MODE
+#define HAVE_ENUM_GOPRO_CAPTURE_MODE
+typedef enum GOPRO_CAPTURE_MODE
+{
+ GOPRO_CAPTURE_MODE_VIDEO=0, /* Video mode. | */
+ GOPRO_CAPTURE_MODE_PHOTO=1, /* Photo mode. | */
+ GOPRO_CAPTURE_MODE_BURST=2, /* Burst mode, Hero 3+ only. | */
+ GOPRO_CAPTURE_MODE_TIME_LAPSE=3, /* Time lapse mode, Hero 3+ only. | */
+ GOPRO_CAPTURE_MODE_MULTI_SHOT=4, /* Multi shot mode, Hero 4 only. | */
+ GOPRO_CAPTURE_MODE_PLAYBACK=5, /* Playback mode, Hero 4 only, silver only except when LCD or HDMI is connected to black. | */
+ GOPRO_CAPTURE_MODE_SETUP=6, /* Playback mode, Hero 4 only. | */
+ GOPRO_CAPTURE_MODE_UNKNOWN=255, /* Mode not yet known. | */
+ GOPRO_CAPTURE_MODE_ENUM_END=256, /* | */
+} GOPRO_CAPTURE_MODE;
+#endif
+
+/** @brief */
+#ifndef HAVE_ENUM_GOPRO_RESOLUTION
+#define HAVE_ENUM_GOPRO_RESOLUTION
+typedef enum GOPRO_RESOLUTION
+{
+ GOPRO_RESOLUTION_480p=0, /* 848 x 480 (480p). | */
+ GOPRO_RESOLUTION_720p=1, /* 1280 x 720 (720p). | */
+ GOPRO_RESOLUTION_960p=2, /* 1280 x 960 (960p). | */
+ GOPRO_RESOLUTION_1080p=3, /* 1920 x 1080 (1080p). | */
+ GOPRO_RESOLUTION_1440p=4, /* 1920 x 1440 (1440p). | */
+ GOPRO_RESOLUTION_2_7k_17_9=5, /* 2704 x 1440 (2.7k-17:9). | */
+ GOPRO_RESOLUTION_2_7k_16_9=6, /* 2704 x 1524 (2.7k-16:9). | */
+ GOPRO_RESOLUTION_2_7k_4_3=7, /* 2704 x 2028 (2.7k-4:3). | */
+ GOPRO_RESOLUTION_4k_16_9=8, /* 3840 x 2160 (4k-16:9). | */
+ GOPRO_RESOLUTION_4k_17_9=9, /* 4096 x 2160 (4k-17:9). | */
+ GOPRO_RESOLUTION_720p_SUPERVIEW=10, /* 1280 x 720 (720p-SuperView). | */
+ GOPRO_RESOLUTION_1080p_SUPERVIEW=11, /* 1920 x 1080 (1080p-SuperView). | */
+ GOPRO_RESOLUTION_2_7k_SUPERVIEW=12, /* 2704 x 1520 (2.7k-SuperView). | */
+ GOPRO_RESOLUTION_4k_SUPERVIEW=13, /* 3840 x 2160 (4k-SuperView). | */
+ GOPRO_RESOLUTION_ENUM_END=14, /* | */
+} GOPRO_RESOLUTION;
+#endif
+
+/** @brief */
+#ifndef HAVE_ENUM_GOPRO_FRAME_RATE
+#define HAVE_ENUM_GOPRO_FRAME_RATE
+typedef enum GOPRO_FRAME_RATE
+{
+ GOPRO_FRAME_RATE_12=0, /* 12 FPS. | */
+ GOPRO_FRAME_RATE_15=1, /* 15 FPS. | */
+ GOPRO_FRAME_RATE_24=2, /* 24 FPS. | */
+ GOPRO_FRAME_RATE_25=3, /* 25 FPS. | */
+ GOPRO_FRAME_RATE_30=4, /* 30 FPS. | */
+ GOPRO_FRAME_RATE_48=5, /* 48 FPS. | */
+ GOPRO_FRAME_RATE_50=6, /* 50 FPS. | */
+ GOPRO_FRAME_RATE_60=7, /* 60 FPS. | */
+ GOPRO_FRAME_RATE_80=8, /* 80 FPS. | */
+ GOPRO_FRAME_RATE_90=9, /* 90 FPS. | */
+ GOPRO_FRAME_RATE_100=10, /* 100 FPS. | */
+ GOPRO_FRAME_RATE_120=11, /* 120 FPS. | */
+ GOPRO_FRAME_RATE_240=12, /* 240 FPS. | */
+ GOPRO_FRAME_RATE_12_5=13, /* 12.5 FPS. | */
+ GOPRO_FRAME_RATE_ENUM_END=14, /* | */
+} GOPRO_FRAME_RATE;
+#endif
+
+/** @brief */
+#ifndef HAVE_ENUM_GOPRO_FIELD_OF_VIEW
+#define HAVE_ENUM_GOPRO_FIELD_OF_VIEW
+typedef enum GOPRO_FIELD_OF_VIEW
+{
+ GOPRO_FIELD_OF_VIEW_WIDE=0, /* 0x00: Wide. | */
+ GOPRO_FIELD_OF_VIEW_MEDIUM=1, /* 0x01: Medium. | */
+ GOPRO_FIELD_OF_VIEW_NARROW=2, /* 0x02: Narrow. | */
+ GOPRO_FIELD_OF_VIEW_ENUM_END=3, /* | */
+} GOPRO_FIELD_OF_VIEW;
+#endif
+
+/** @brief */
+#ifndef HAVE_ENUM_GOPRO_VIDEO_SETTINGS_FLAGS
+#define HAVE_ENUM_GOPRO_VIDEO_SETTINGS_FLAGS
+typedef enum GOPRO_VIDEO_SETTINGS_FLAGS
+{
+ GOPRO_VIDEO_SETTINGS_TV_MODE=1, /* 0=NTSC, 1=PAL. | */
+ GOPRO_VIDEO_SETTINGS_FLAGS_ENUM_END=2, /* | */
+} GOPRO_VIDEO_SETTINGS_FLAGS;
+#endif
+
+/** @brief */
+#ifndef HAVE_ENUM_GOPRO_PHOTO_RESOLUTION
+#define HAVE_ENUM_GOPRO_PHOTO_RESOLUTION
+typedef enum GOPRO_PHOTO_RESOLUTION
+{
+ GOPRO_PHOTO_RESOLUTION_5MP_MEDIUM=0, /* 5MP Medium. | */
+ GOPRO_PHOTO_RESOLUTION_7MP_MEDIUM=1, /* 7MP Medium. | */
+ GOPRO_PHOTO_RESOLUTION_7MP_WIDE=2, /* 7MP Wide. | */
+ GOPRO_PHOTO_RESOLUTION_10MP_WIDE=3, /* 10MP Wide. | */
+ GOPRO_PHOTO_RESOLUTION_12MP_WIDE=4, /* 12MP Wide. | */
+ GOPRO_PHOTO_RESOLUTION_ENUM_END=5, /* | */
+} GOPRO_PHOTO_RESOLUTION;
+#endif
+
+/** @brief */
+#ifndef HAVE_ENUM_GOPRO_PROTUNE_WHITE_BALANCE
+#define HAVE_ENUM_GOPRO_PROTUNE_WHITE_BALANCE
+typedef enum GOPRO_PROTUNE_WHITE_BALANCE
+{
+ GOPRO_PROTUNE_WHITE_BALANCE_AUTO=0, /* Auto. | */
+ GOPRO_PROTUNE_WHITE_BALANCE_3000K=1, /* 3000K. | */
+ GOPRO_PROTUNE_WHITE_BALANCE_5500K=2, /* 5500K. | */
+ GOPRO_PROTUNE_WHITE_BALANCE_6500K=3, /* 6500K. | */
+ GOPRO_PROTUNE_WHITE_BALANCE_RAW=4, /* Camera Raw. | */
+ GOPRO_PROTUNE_WHITE_BALANCE_ENUM_END=5, /* | */
+} GOPRO_PROTUNE_WHITE_BALANCE;
+#endif
+
+/** @brief */
+#ifndef HAVE_ENUM_GOPRO_PROTUNE_COLOUR
+#define HAVE_ENUM_GOPRO_PROTUNE_COLOUR
+typedef enum GOPRO_PROTUNE_COLOUR
+{
+ GOPRO_PROTUNE_COLOUR_STANDARD=0, /* Auto. | */
+ GOPRO_PROTUNE_COLOUR_NEUTRAL=1, /* Neutral. | */
+ GOPRO_PROTUNE_COLOUR_ENUM_END=2, /* | */
+} GOPRO_PROTUNE_COLOUR;
+#endif
+
+/** @brief */
+#ifndef HAVE_ENUM_GOPRO_PROTUNE_GAIN
+#define HAVE_ENUM_GOPRO_PROTUNE_GAIN
+typedef enum GOPRO_PROTUNE_GAIN
+{
+ GOPRO_PROTUNE_GAIN_400=0, /* ISO 400. | */
+ GOPRO_PROTUNE_GAIN_800=1, /* ISO 800 (Only Hero 4). | */
+ GOPRO_PROTUNE_GAIN_1600=2, /* ISO 1600. | */
+ GOPRO_PROTUNE_GAIN_3200=3, /* ISO 3200 (Only Hero 4). | */
+ GOPRO_PROTUNE_GAIN_6400=4, /* ISO 6400. | */
+ GOPRO_PROTUNE_GAIN_ENUM_END=5, /* | */
+} GOPRO_PROTUNE_GAIN;
+#endif
+
+/** @brief */
+#ifndef HAVE_ENUM_GOPRO_PROTUNE_SHARPNESS
+#define HAVE_ENUM_GOPRO_PROTUNE_SHARPNESS
+typedef enum GOPRO_PROTUNE_SHARPNESS
+{
+ GOPRO_PROTUNE_SHARPNESS_LOW=0, /* Low Sharpness. | */
+ GOPRO_PROTUNE_SHARPNESS_MEDIUM=1, /* Medium Sharpness. | */
+ GOPRO_PROTUNE_SHARPNESS_HIGH=2, /* High Sharpness. | */
+ GOPRO_PROTUNE_SHARPNESS_ENUM_END=3, /* | */
+} GOPRO_PROTUNE_SHARPNESS;
+#endif
+
+/** @brief */
+#ifndef HAVE_ENUM_GOPRO_PROTUNE_EXPOSURE
+#define HAVE_ENUM_GOPRO_PROTUNE_EXPOSURE
+typedef enum GOPRO_PROTUNE_EXPOSURE
+{
+ GOPRO_PROTUNE_EXPOSURE_NEG_5_0=0, /* -5.0 EV (Hero 3+ Only). | */
+ GOPRO_PROTUNE_EXPOSURE_NEG_4_5=1, /* -4.5 EV (Hero 3+ Only). | */
+ GOPRO_PROTUNE_EXPOSURE_NEG_4_0=2, /* -4.0 EV (Hero 3+ Only). | */
+ GOPRO_PROTUNE_EXPOSURE_NEG_3_5=3, /* -3.5 EV (Hero 3+ Only). | */
+ GOPRO_PROTUNE_EXPOSURE_NEG_3_0=4, /* -3.0 EV (Hero 3+ Only). | */
+ GOPRO_PROTUNE_EXPOSURE_NEG_2_5=5, /* -2.5 EV (Hero 3+ Only). | */
+ GOPRO_PROTUNE_EXPOSURE_NEG_2_0=6, /* -2.0 EV. | */
+ GOPRO_PROTUNE_EXPOSURE_NEG_1_5=7, /* -1.5 EV. | */
+ GOPRO_PROTUNE_EXPOSURE_NEG_1_0=8, /* -1.0 EV. | */
+ GOPRO_PROTUNE_EXPOSURE_NEG_0_5=9, /* -0.5 EV. | */
+ GOPRO_PROTUNE_EXPOSURE_ZERO=10, /* 0.0 EV. | */
+ GOPRO_PROTUNE_EXPOSURE_POS_0_5=11, /* +0.5 EV. | */
+ GOPRO_PROTUNE_EXPOSURE_POS_1_0=12, /* +1.0 EV. | */
+ GOPRO_PROTUNE_EXPOSURE_POS_1_5=13, /* +1.5 EV. | */
+ GOPRO_PROTUNE_EXPOSURE_POS_2_0=14, /* +2.0 EV. | */
+ GOPRO_PROTUNE_EXPOSURE_POS_2_5=15, /* +2.5 EV (Hero 3+ Only). | */
+ GOPRO_PROTUNE_EXPOSURE_POS_3_0=16, /* +3.0 EV (Hero 3+ Only). | */
+ GOPRO_PROTUNE_EXPOSURE_POS_3_5=17, /* +3.5 EV (Hero 3+ Only). | */
+ GOPRO_PROTUNE_EXPOSURE_POS_4_0=18, /* +4.0 EV (Hero 3+ Only). | */
+ GOPRO_PROTUNE_EXPOSURE_POS_4_5=19, /* +4.5 EV (Hero 3+ Only). | */
+ GOPRO_PROTUNE_EXPOSURE_POS_5_0=20, /* +5.0 EV (Hero 3+ Only). | */
+ GOPRO_PROTUNE_EXPOSURE_ENUM_END=21, /* | */
+} GOPRO_PROTUNE_EXPOSURE;
+#endif
+
+/** @brief */
+#ifndef HAVE_ENUM_GOPRO_CHARGING
+#define HAVE_ENUM_GOPRO_CHARGING
+typedef enum GOPRO_CHARGING
+{
+ GOPRO_CHARGING_DISABLED=0, /* Charging disabled. | */
+ GOPRO_CHARGING_ENABLED=1, /* Charging enabled. | */
+ GOPRO_CHARGING_ENUM_END=2, /* | */
+} GOPRO_CHARGING;
+#endif
+
+/** @brief */
+#ifndef HAVE_ENUM_GOPRO_MODEL
+#define HAVE_ENUM_GOPRO_MODEL
+typedef enum GOPRO_MODEL
+{
+ GOPRO_MODEL_UNKNOWN=0, /* Unknown gopro model. | */
+ GOPRO_MODEL_HERO_3_PLUS_SILVER=1, /* Hero 3+ Silver (HeroBus not supported by GoPro). | */
+ GOPRO_MODEL_HERO_3_PLUS_BLACK=2, /* Hero 3+ Black. | */
+ GOPRO_MODEL_HERO_4_SILVER=3, /* Hero 4 Silver. | */
+ GOPRO_MODEL_HERO_4_BLACK=4, /* Hero 4 Black. | */
+ GOPRO_MODEL_ENUM_END=5, /* | */
+} GOPRO_MODEL;
+#endif
+
+/** @brief */
+#ifndef HAVE_ENUM_GOPRO_BURST_RATE
+#define HAVE_ENUM_GOPRO_BURST_RATE
+typedef enum GOPRO_BURST_RATE
+{
+ GOPRO_BURST_RATE_3_IN_1_SECOND=0, /* 3 Shots / 1 Second. | */
+ GOPRO_BURST_RATE_5_IN_1_SECOND=1, /* 5 Shots / 1 Second. | */
+ GOPRO_BURST_RATE_10_IN_1_SECOND=2, /* 10 Shots / 1 Second. | */
+ GOPRO_BURST_RATE_10_IN_2_SECOND=3, /* 10 Shots / 2 Second. | */
+ GOPRO_BURST_RATE_10_IN_3_SECOND=4, /* 10 Shots / 3 Second (Hero 4 Only). | */
+ GOPRO_BURST_RATE_30_IN_1_SECOND=5, /* 30 Shots / 1 Second. | */
+ GOPRO_BURST_RATE_30_IN_2_SECOND=6, /* 30 Shots / 2 Second. | */
+ GOPRO_BURST_RATE_30_IN_3_SECOND=7, /* 30 Shots / 3 Second. | */
+ GOPRO_BURST_RATE_30_IN_6_SECOND=8, /* 30 Shots / 6 Second. | */
+ GOPRO_BURST_RATE_ENUM_END=9, /* | */
+} GOPRO_BURST_RATE;
+#endif
+
+/** @brief */
+#ifndef HAVE_ENUM_MAV_CMD_DO_AUX_FUNCTION_SWITCH_LEVEL
+#define HAVE_ENUM_MAV_CMD_DO_AUX_FUNCTION_SWITCH_LEVEL
+typedef enum MAV_CMD_DO_AUX_FUNCTION_SWITCH_LEVEL
+{
+ MAV_CMD_DO_AUX_FUNCTION_SWITCH_LEVEL_LOW=0, /* Switch Low. |Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */
+ MAV_CMD_DO_AUX_FUNCTION_SWITCH_LEVEL_MIDDLE=1, /* Switch Middle. |Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */
+ MAV_CMD_DO_AUX_FUNCTION_SWITCH_LEVEL_HIGH=2, /* Switch High. |Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */
+ MAV_CMD_DO_AUX_FUNCTION_SWITCH_LEVEL_ENUM_END=3, /* | */
+} MAV_CMD_DO_AUX_FUNCTION_SWITCH_LEVEL;
+#endif
+
+/** @brief */
+#ifndef HAVE_ENUM_LED_CONTROL_PATTERN
+#define HAVE_ENUM_LED_CONTROL_PATTERN
+typedef enum LED_CONTROL_PATTERN
+{
+ LED_CONTROL_PATTERN_OFF=0, /* LED patterns off (return control to regular vehicle control). | */
+ LED_CONTROL_PATTERN_FIRMWAREUPDATE=1, /* LEDs show pattern during firmware update. | */
+ LED_CONTROL_PATTERN_CUSTOM=255, /* Custom Pattern using custom bytes fields. | */
+ LED_CONTROL_PATTERN_ENUM_END=256, /* | */
+} LED_CONTROL_PATTERN;
+#endif
+
+/** @brief Flags in EKF_STATUS message. */
+#ifndef HAVE_ENUM_EKF_STATUS_FLAGS
+#define HAVE_ENUM_EKF_STATUS_FLAGS
+typedef enum EKF_STATUS_FLAGS
+{
+ EKF_ATTITUDE=1, /* Set if EKF's attitude estimate is good. | */
+ EKF_VELOCITY_HORIZ=2, /* Set if EKF's horizontal velocity estimate is good. | */
+ EKF_VELOCITY_VERT=4, /* Set if EKF's vertical velocity estimate is good. | */
+ EKF_POS_HORIZ_REL=8, /* Set if EKF's horizontal position (relative) estimate is good. | */
+ EKF_POS_HORIZ_ABS=16, /* Set if EKF's horizontal position (absolute) estimate is good. | */
+ EKF_POS_VERT_ABS=32, /* Set if EKF's vertical position (absolute) estimate is good. | */
+ EKF_POS_VERT_AGL=64, /* Set if EKF's vertical position (above ground) estimate is good. | */
+ EKF_CONST_POS_MODE=128, /* EKF is in constant position mode and does not know it's absolute or relative position. | */
+ EKF_PRED_POS_HORIZ_REL=256, /* Set if EKF's predicted horizontal position (relative) estimate is good. | */
+ EKF_PRED_POS_HORIZ_ABS=512, /* Set if EKF's predicted horizontal position (absolute) estimate is good. | */
+ EKF_UNINITIALIZED=1024, /* Set if EKF has never been healthy. | */
+ EKF_GPS_GLITCHING=32768, /* Set if EKF believes the GPS input data is faulty. | */
+ EKF_STATUS_FLAGS_ENUM_END=32769, /* | */
+} EKF_STATUS_FLAGS;
+#endif
+
+/** @brief */
+#ifndef HAVE_ENUM_PID_TUNING_AXIS
+#define HAVE_ENUM_PID_TUNING_AXIS
+typedef enum PID_TUNING_AXIS
+{
+ PID_TUNING_ROLL=1, /* | */
+ PID_TUNING_PITCH=2, /* | */
+ PID_TUNING_YAW=3, /* | */
+ PID_TUNING_ACCZ=4, /* | */
+ PID_TUNING_STEER=5, /* | */
+ PID_TUNING_LANDING=6, /* | */
+ PID_TUNING_AXIS_ENUM_END=7, /* | */
+} PID_TUNING_AXIS;
+#endif
+
+/** @brief Special ACK block numbers control activation of dataflash log streaming. */
+#ifndef HAVE_ENUM_MAV_REMOTE_LOG_DATA_BLOCK_COMMANDS
+#define HAVE_ENUM_MAV_REMOTE_LOG_DATA_BLOCK_COMMANDS
+typedef enum MAV_REMOTE_LOG_DATA_BLOCK_COMMANDS
+{
+ MAV_REMOTE_LOG_DATA_BLOCK_STOP=2147483645, /* UAV to stop sending DataFlash blocks. | */
+ MAV_REMOTE_LOG_DATA_BLOCK_START=2147483646, /* UAV to start sending DataFlash blocks. | */
+ MAV_REMOTE_LOG_DATA_BLOCK_COMMANDS_ENUM_END=2147483647, /* | */
+} MAV_REMOTE_LOG_DATA_BLOCK_COMMANDS;
+#endif
+
+/** @brief Possible remote log data block statuses. */
+#ifndef HAVE_ENUM_MAV_REMOTE_LOG_DATA_BLOCK_STATUSES
+#define HAVE_ENUM_MAV_REMOTE_LOG_DATA_BLOCK_STATUSES
+typedef enum MAV_REMOTE_LOG_DATA_BLOCK_STATUSES
+{
+ MAV_REMOTE_LOG_DATA_BLOCK_NACK=0, /* This block has NOT been received. | */
+ MAV_REMOTE_LOG_DATA_BLOCK_ACK=1, /* This block has been received. | */
+ MAV_REMOTE_LOG_DATA_BLOCK_STATUSES_ENUM_END=2, /* | */
+} MAV_REMOTE_LOG_DATA_BLOCK_STATUSES;
+#endif
+
+/** @brief Bus types for device operations. */
+#ifndef HAVE_ENUM_DEVICE_OP_BUSTYPE
+#define HAVE_ENUM_DEVICE_OP_BUSTYPE
+typedef enum DEVICE_OP_BUSTYPE
+{
+ DEVICE_OP_BUSTYPE_I2C=0, /* I2C Device operation. | */
+ DEVICE_OP_BUSTYPE_SPI=1, /* SPI Device operation. | */
+ DEVICE_OP_BUSTYPE_ENUM_END=2, /* | */
+} DEVICE_OP_BUSTYPE;
+#endif
+
+/** @brief Deepstall flight stage. */
+#ifndef HAVE_ENUM_DEEPSTALL_STAGE
+#define HAVE_ENUM_DEEPSTALL_STAGE
+typedef enum DEEPSTALL_STAGE
+{
+ DEEPSTALL_STAGE_FLY_TO_LANDING=0, /* Flying to the landing point. | */
+ DEEPSTALL_STAGE_ESTIMATE_WIND=1, /* Building an estimate of the wind. | */
+ DEEPSTALL_STAGE_WAIT_FOR_BREAKOUT=2, /* Waiting to breakout of the loiter to fly the approach. | */
+ DEEPSTALL_STAGE_FLY_TO_ARC=3, /* Flying to the first arc point to turn around to the landing point. | */
+ DEEPSTALL_STAGE_ARC=4, /* Turning around back to the deepstall landing point. | */
+ DEEPSTALL_STAGE_APPROACH=5, /* Approaching the landing point. | */
+ DEEPSTALL_STAGE_LAND=6, /* Stalling and steering towards the land point. | */
+ DEEPSTALL_STAGE_ENUM_END=7, /* | */
+} DEEPSTALL_STAGE;
+#endif
+
+/** @brief A mapping of plane flight modes for custom_mode field of heartbeat. */
+#ifndef HAVE_ENUM_PLANE_MODE
+#define HAVE_ENUM_PLANE_MODE
+typedef enum PLANE_MODE
+{
+ PLANE_MODE_MANUAL=0, /* MANUAL | */
+ PLANE_MODE_CIRCLE=1, /* CIRCLE | */
+ PLANE_MODE_STABILIZE=2, /* STABILIZE | */
+ PLANE_MODE_TRAINING=3, /* TRAINING | */
+ PLANE_MODE_ACRO=4, /* ACRO | */
+ PLANE_MODE_FLY_BY_WIRE_A=5, /* FBWA | */
+ PLANE_MODE_FLY_BY_WIRE_B=6, /* FBWB | */
+ PLANE_MODE_CRUISE=7, /* CRUISE | */
+ PLANE_MODE_AUTOTUNE=8, /* AUTOTUNE | */
+ PLANE_MODE_AUTO=10, /* AUTO | */
+ PLANE_MODE_RTL=11, /* RTL | */
+ PLANE_MODE_LOITER=12, /* LOITER | */
+ PLANE_MODE_TAKEOFF=13, /* TAKEOFF | */
+ PLANE_MODE_AVOID_ADSB=14, /* AVOID ADSB | */
+ PLANE_MODE_GUIDED=15, /* GUIDED | */
+ PLANE_MODE_INITIALIZING=16, /* INITIALISING | */
+ PLANE_MODE_QSTABILIZE=17, /* QSTABILIZE | */
+ PLANE_MODE_QHOVER=18, /* QHOVER | */
+ PLANE_MODE_QLOITER=19, /* QLOITER | */
+ PLANE_MODE_QLAND=20, /* QLAND | */
+ PLANE_MODE_QRTL=21, /* QRTL | */
+ PLANE_MODE_QAUTOTUNE=22, /* QAUTOTUNE | */
+ PLANE_MODE_QACRO=23, /* QACRO | */
+ PLANE_MODE_THERMAL=24, /* THERMAL | */
+ PLANE_MODE_LOITER_ALT_QLAND=25, /* LOITER2QLAND | */
+ PLANE_MODE_AUTOLAND=26, /* AUTOLAND | */
+ PLANE_MODE_ENUM_END=27, /* | */
+} PLANE_MODE;
+#endif
+
+/** @brief A mapping of copter flight modes for custom_mode field of heartbeat. */
+#ifndef HAVE_ENUM_COPTER_MODE
+#define HAVE_ENUM_COPTER_MODE
+typedef enum COPTER_MODE
+{
+ COPTER_MODE_STABILIZE=0, /* STABILIZE | */
+ COPTER_MODE_ACRO=1, /* ACRO | */
+ COPTER_MODE_ALT_HOLD=2, /* ALT HOLD | */
+ COPTER_MODE_AUTO=3, /* AUTO | */
+ COPTER_MODE_GUIDED=4, /* GUIDED | */
+ COPTER_MODE_LOITER=5, /* LOITER | */
+ COPTER_MODE_RTL=6, /* RTL | */
+ COPTER_MODE_CIRCLE=7, /* CIRCLE | */
+ COPTER_MODE_LAND=9, /* LAND | */
+ COPTER_MODE_DRIFT=11, /* DRIFT | */
+ COPTER_MODE_SPORT=13, /* SPORT | */
+ COPTER_MODE_FLIP=14, /* FLIP | */
+ COPTER_MODE_AUTOTUNE=15, /* AUTOTUNE | */
+ COPTER_MODE_POSHOLD=16, /* POSHOLD | */
+ COPTER_MODE_BRAKE=17, /* BRAKE | */
+ COPTER_MODE_THROW=18, /* THROW | */
+ COPTER_MODE_AVOID_ADSB=19, /* AVOID ADSB | */
+ COPTER_MODE_GUIDED_NOGPS=20, /* GUIDED NOGPS | */
+ COPTER_MODE_SMART_RTL=21, /* SMARTRTL | */
+ COPTER_MODE_FLOWHOLD=22, /* FLOWHOLD | */
+ COPTER_MODE_FOLLOW=23, /* FOLLOW | */
+ COPTER_MODE_ZIGZAG=24, /* ZIGZAG | */
+ COPTER_MODE_SYSTEMID=25, /* SYSTEMID | */
+ COPTER_MODE_AUTOROTATE=26, /* AUTOROTATE | */
+ COPTER_MODE_AUTO_RTL=27, /* AUTO RTL | */
+ COPTER_MODE_TURTLE=28, /* TURTLE | */
+ COPTER_MODE_RATE_ACRO=29, /* RATE_ACRO | */
+ COPTER_MODE_ENUM_END=30, /* | */
+} COPTER_MODE;
+#endif
+
+/** @brief A mapping of sub flight modes for custom_mode field of heartbeat. */
+#ifndef HAVE_ENUM_SUB_MODE
+#define HAVE_ENUM_SUB_MODE
+typedef enum SUB_MODE
+{
+ SUB_MODE_STABILIZE=0, /* STABILIZE | */
+ SUB_MODE_ACRO=1, /* ACRO | */
+ SUB_MODE_ALT_HOLD=2, /* ALT HOLD | */
+ SUB_MODE_AUTO=3, /* AUTO | */
+ SUB_MODE_GUIDED=4, /* GUIDED | */
+ SUB_MODE_CIRCLE=7, /* CIRCLE | */
+ SUB_MODE_SURFACE=9, /* SURFACE | */
+ SUB_MODE_POSHOLD=16, /* POSHOLD | */
+ SUB_MODE_MANUAL=19, /* MANUAL | */
+ SUB_MODE_MOTORDETECT=20, /* MOTORDETECT | */
+ SUB_MODE_SURFTRAK=21, /* SURFTRAK | */
+ SUB_MODE_ENUM_END=22, /* | */
+} SUB_MODE;
+#endif
+
+/** @brief A mapping of rover flight modes for custom_mode field of heartbeat. */
+#ifndef HAVE_ENUM_ROVER_MODE
+#define HAVE_ENUM_ROVER_MODE
+typedef enum ROVER_MODE
+{
+ ROVER_MODE_MANUAL=0, /* MANUAL | */
+ ROVER_MODE_ACRO=1, /* ACRO | */
+ ROVER_MODE_STEERING=3, /* STEERING | */
+ ROVER_MODE_HOLD=4, /* HOLD | */
+ ROVER_MODE_LOITER=5, /* LOITER | */
+ ROVER_MODE_FOLLOW=6, /* FOLLOW | */
+ ROVER_MODE_SIMPLE=7, /* SIMPLE | */
+ ROVER_MODE_DOCK=8, /* DOCK | */
+ ROVER_MODE_CIRCLE=9, /* CIRCLE | */
+ ROVER_MODE_AUTO=10, /* AUTO | */
+ ROVER_MODE_RTL=11, /* RTL | */
+ ROVER_MODE_SMART_RTL=12, /* SMART RTL | */
+ ROVER_MODE_GUIDED=15, /* GUIDED | */
+ ROVER_MODE_INITIALIZING=16, /* INITIALISING | */
+ ROVER_MODE_ENUM_END=17, /* | */
+} ROVER_MODE;
+#endif
+
+/** @brief A mapping of antenna tracker flight modes for custom_mode field of heartbeat. */
+#ifndef HAVE_ENUM_TRACKER_MODE
+#define HAVE_ENUM_TRACKER_MODE
+typedef enum TRACKER_MODE
+{
+ TRACKER_MODE_MANUAL=0, /* MANUAL | */
+ TRACKER_MODE_STOP=1, /* STOP | */
+ TRACKER_MODE_SCAN=2, /* SCAN | */
+ TRACKER_MODE_SERVO_TEST=3, /* SERVO TEST | */
+ TRACKER_MODE_GUIDED=4, /* GUIDED | */
+ TRACKER_MODE_AUTO=10, /* AUTO | */
+ TRACKER_MODE_INITIALIZING=16, /* INITIALISING | */
+ TRACKER_MODE_ENUM_END=17, /* | */
+} TRACKER_MODE;
+#endif
+
+/** @brief The type of parameter for the OSD parameter editor. */
+#ifndef HAVE_ENUM_OSD_PARAM_CONFIG_TYPE
+#define HAVE_ENUM_OSD_PARAM_CONFIG_TYPE
+typedef enum OSD_PARAM_CONFIG_TYPE
+{
+ OSD_PARAM_NONE=0, /* | */
+ OSD_PARAM_SERIAL_PROTOCOL=1, /* | */
+ OSD_PARAM_SERVO_FUNCTION=2, /* | */
+ OSD_PARAM_AUX_FUNCTION=3, /* | */
+ OSD_PARAM_FLIGHT_MODE=4, /* | */
+ OSD_PARAM_FAILSAFE_ACTION=5, /* | */
+ OSD_PARAM_FAILSAFE_ACTION_1=6, /* | */
+ OSD_PARAM_FAILSAFE_ACTION_2=7, /* | */
+ OSD_PARAM_NUM_TYPES=8, /* | */
+ OSD_PARAM_CONFIG_TYPE_ENUM_END=9, /* | */
+} OSD_PARAM_CONFIG_TYPE;
+#endif
+
+/** @brief The error type for the OSD parameter editor. */
+#ifndef HAVE_ENUM_OSD_PARAM_CONFIG_ERROR
+#define HAVE_ENUM_OSD_PARAM_CONFIG_ERROR
+typedef enum OSD_PARAM_CONFIG_ERROR
+{
+ OSD_PARAM_SUCCESS=0, /* | */
+ OSD_PARAM_INVALID_SCREEN=1, /* | */
+ OSD_PARAM_INVALID_PARAMETER_INDEX=2, /* | */
+ OSD_PARAM_INVALID_PARAMETER=3, /* | */
+ OSD_PARAM_CONFIG_ERROR_ENUM_END=4, /* | */
+} OSD_PARAM_CONFIG_ERROR;
+#endif
+
+// MAVLINK VERSION
+
+#ifndef MAVLINK_VERSION
+#define MAVLINK_VERSION 2
+#endif
+
+#if (MAVLINK_VERSION == 0)
+#undef MAVLINK_VERSION
+#define MAVLINK_VERSION 2
+#endif
+
+// MESSAGE DEFINITIONS
+#include "./mavlink_msg_sensor_offsets.h"
+#include "./mavlink_msg_set_mag_offsets.h"
+#include "./mavlink_msg_meminfo.h"
+#include "./mavlink_msg_ap_adc.h"
+#include "./mavlink_msg_digicam_configure.h"
+#include "./mavlink_msg_digicam_control.h"
+#include "./mavlink_msg_mount_configure.h"
+#include "./mavlink_msg_mount_control.h"
+#include "./mavlink_msg_mount_status.h"
+#include "./mavlink_msg_fence_point.h"
+#include "./mavlink_msg_fence_fetch_point.h"
+#include "./mavlink_msg_ahrs.h"
+#include "./mavlink_msg_simstate.h"
+#include "./mavlink_msg_hwstatus.h"
+#include "./mavlink_msg_radio.h"
+#include "./mavlink_msg_limits_status.h"
+#include "./mavlink_msg_wind.h"
+#include "./mavlink_msg_data16.h"
+#include "./mavlink_msg_data32.h"
+#include "./mavlink_msg_data64.h"
+#include "./mavlink_msg_data96.h"
+#include "./mavlink_msg_rangefinder.h"
+#include "./mavlink_msg_airspeed_autocal.h"
+#include "./mavlink_msg_rally_point.h"
+#include "./mavlink_msg_rally_fetch_point.h"
+#include "./mavlink_msg_compassmot_status.h"
+#include "./mavlink_msg_ahrs2.h"
+#include "./mavlink_msg_camera_status.h"
+#include "./mavlink_msg_camera_feedback.h"
+#include "./mavlink_msg_battery2.h"
+#include "./mavlink_msg_ahrs3.h"
+#include "./mavlink_msg_autopilot_version_request.h"
+#include "./mavlink_msg_remote_log_data_block.h"
+#include "./mavlink_msg_remote_log_block_status.h"
+#include "./mavlink_msg_led_control.h"
+#include "./mavlink_msg_mag_cal_progress.h"
+#include "./mavlink_msg_ekf_status_report.h"
+#include "./mavlink_msg_pid_tuning.h"
+#include "./mavlink_msg_deepstall.h"
+#include "./mavlink_msg_gimbal_report.h"
+#include "./mavlink_msg_gimbal_control.h"
+#include "./mavlink_msg_gimbal_torque_cmd_report.h"
+#include "./mavlink_msg_gopro_heartbeat.h"
+#include "./mavlink_msg_gopro_get_request.h"
+#include "./mavlink_msg_gopro_get_response.h"
+#include "./mavlink_msg_gopro_set_request.h"
+#include "./mavlink_msg_gopro_set_response.h"
+#include "./mavlink_msg_rpm.h"
+#include "./mavlink_msg_device_op_read.h"
+#include "./mavlink_msg_device_op_read_reply.h"
+#include "./mavlink_msg_device_op_write.h"
+#include "./mavlink_msg_device_op_write_reply.h"
+#include "./mavlink_msg_secure_command.h"
+#include "./mavlink_msg_secure_command_reply.h"
+#include "./mavlink_msg_adap_tuning.h"
+#include "./mavlink_msg_vision_position_delta.h"
+#include "./mavlink_msg_aoa_ssa.h"
+#include "./mavlink_msg_esc_telemetry_1_to_4.h"
+#include "./mavlink_msg_esc_telemetry_5_to_8.h"
+#include "./mavlink_msg_esc_telemetry_9_to_12.h"
+#include "./mavlink_msg_osd_param_config.h"
+#include "./mavlink_msg_osd_param_config_reply.h"
+#include "./mavlink_msg_osd_param_show_config.h"
+#include "./mavlink_msg_osd_param_show_config_reply.h"
+#include "./mavlink_msg_obstacle_distance_3d.h"
+#include "./mavlink_msg_water_depth.h"
+#include "./mavlink_msg_mcu_status.h"
+#include "./mavlink_msg_esc_telemetry_13_to_16.h"
+#include "./mavlink_msg_esc_telemetry_17_to_20.h"
+#include "./mavlink_msg_esc_telemetry_21_to_24.h"
+#include "./mavlink_msg_esc_telemetry_25_to_28.h"
+#include "./mavlink_msg_esc_telemetry_29_to_32.h"
+#include "./mavlink_msg_named_value_string.h"
+
+// base include
+#include "../common/common.h"
+#include "../uAvionix/uAvionix.h"
+#include "../icarous/icarous.h"
+#include "../loweheiser/loweheiser.h"
+#include "../cubepilot/cubepilot.h"
+#include "../csAirLink/csAirLink.h"
+
+
+#if MAVLINK_ARDUPILOTMEGA_XML_HASH == MAVLINK_PRIMARY_XML_HASH
+# define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_SYS_STATUS, MAVLINK_MESSAGE_INFO_SYSTEM_TIME, MAVLINK_MESSAGE_INFO_PING, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK, MAVLINK_MESSAGE_INFO_AUTH_KEY, MAVLINK_MESSAGE_INFO_LINK_NODE_STATUS, MAVLINK_MESSAGE_INFO_SET_MODE, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_VALUE, MAVLINK_MESSAGE_INFO_PARAM_SET, MAVLINK_MESSAGE_INFO_GPS_RAW_INT, MAVLINK_MESSAGE_INFO_GPS_STATUS, MAVLINK_MESSAGE_INFO_SCALED_IMU, MAVLINK_MESSAGE_INFO_RAW_IMU, MAVLINK_MESSAGE_INFO_RAW_PRESSURE, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE, MAVLINK_MESSAGE_INFO_ATTITUDE, MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT, MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED, MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW, MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_WRITE_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_ITEM, MAVLINK_MESSAGE_INFO_MISSION_REQUEST, MAVLINK_MESSAGE_INFO_MISSION_SET_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_LIST, MAVLINK_MESSAGE_INFO_MISSION_COUNT, MAVLINK_MESSAGE_INFO_MISSION_CLEAR_ALL, MAVLINK_MESSAGE_INFO_MISSION_ITEM_REACHED, MAVLINK_MESSAGE_INFO_MISSION_ACK, MAVLINK_MESSAGE_INFO_SET_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_PARAM_MAP_RC, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_INT, MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION_COV, MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT_COV, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_COV, MAVLINK_MESSAGE_INFO_RC_CHANNELS, MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM, MAVLINK_MESSAGE_INFO_DATA_STREAM, MAVLINK_MESSAGE_INFO_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE, MAVLINK_MESSAGE_INFO_MISSION_ITEM_INT, MAVLINK_MESSAGE_INFO_VFR_HUD, MAVLINK_MESSAGE_INFO_COMMAND_INT, MAVLINK_MESSAGE_INFO_COMMAND_LONG, MAVLINK_MESSAGE_INFO_COMMAND_ACK, MAVLINK_MESSAGE_INFO_COMMAND_CANCEL, MAVLINK_MESSAGE_INFO_MANUAL_SETPOINT, MAVLINK_MESSAGE_INFO_SET_ATTITUDE_TARGET, MAVLINK_MESSAGE_INFO_ATTITUDE_TARGET, MAVLINK_MESSAGE_INFO_SET_POSITION_TARGET_LOCAL_NED, MAVLINK_MESSAGE_INFO_POSITION_TARGET_LOCAL_NED, MAVLINK_MESSAGE_INFO_SET_POSITION_TARGET_GLOBAL_INT, MAVLINK_MESSAGE_INFO_POSITION_TARGET_GLOBAL_INT, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, MAVLINK_MESSAGE_INFO_HIL_STATE, MAVLINK_MESSAGE_INFO_HIL_CONTROLS, MAVLINK_MESSAGE_INFO_HIL_RC_INPUTS_RAW, MAVLINK_MESSAGE_INFO_HIL_ACTUATOR_CONTROLS, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_GLOBAL_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE, MAVLINK_MESSAGE_INFO_VICON_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_HIGHRES_IMU, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW_RAD, MAVLINK_MESSAGE_INFO_HIL_SENSOR, MAVLINK_MESSAGE_INFO_SIM_STATE, MAVLINK_MESSAGE_INFO_RADIO_STATUS, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_PROTOCOL, MAVLINK_MESSAGE_INFO_TIMESYNC, MAVLINK_MESSAGE_INFO_CAMERA_TRIGGER, MAVLINK_MESSAGE_INFO_HIL_GPS, MAVLINK_MESSAGE_INFO_HIL_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_HIL_STATE_QUATERNION, MAVLINK_MESSAGE_INFO_SCALED_IMU2, MAVLINK_MESSAGE_INFO_LOG_REQUEST_LIST, MAVLINK_MESSAGE_INFO_LOG_ENTRY, MAVLINK_MESSAGE_INFO_LOG_REQUEST_DATA, MAVLINK_MESSAGE_INFO_LOG_DATA, MAVLINK_MESSAGE_INFO_LOG_ERASE, MAVLINK_MESSAGE_INFO_LOG_REQUEST_END, MAVLINK_MESSAGE_INFO_GPS_INJECT_DATA, MAVLINK_MESSAGE_INFO_GPS2_RAW, MAVLINK_MESSAGE_INFO_POWER_STATUS, MAVLINK_MESSAGE_INFO_SERIAL_CONTROL, MAVLINK_MESSAGE_INFO_GPS_RTK, MAVLINK_MESSAGE_INFO_GPS2_RTK, MAVLINK_MESSAGE_INFO_SCALED_IMU3, MAVLINK_MESSAGE_INFO_DATA_TRANSMISSION_HANDSHAKE, MAVLINK_MESSAGE_INFO_ENCAPSULATED_DATA, MAVLINK_MESSAGE_INFO_DISTANCE_SENSOR, MAVLINK_MESSAGE_INFO_TERRAIN_REQUEST, MAVLINK_MESSAGE_INFO_TERRAIN_DATA, MAVLINK_MESSAGE_INFO_TERRAIN_CHECK, MAVLINK_MESSAGE_INFO_TERRAIN_REPORT, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE2, MAVLINK_MESSAGE_INFO_ATT_POS_MOCAP, MAVLINK_MESSAGE_INFO_SET_ACTUATOR_CONTROL_TARGET, MAVLINK_MESSAGE_INFO_ACTUATOR_CONTROL_TARGET, MAVLINK_MESSAGE_INFO_ALTITUDE, MAVLINK_MESSAGE_INFO_RESOURCE_REQUEST, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE3, MAVLINK_MESSAGE_INFO_FOLLOW_TARGET, MAVLINK_MESSAGE_INFO_CONTROL_SYSTEM_STATE, MAVLINK_MESSAGE_INFO_BATTERY_STATUS, MAVLINK_MESSAGE_INFO_AUTOPILOT_VERSION, MAVLINK_MESSAGE_INFO_LANDING_TARGET, MAVLINK_MESSAGE_INFO_SENSOR_OFFSETS, MAVLINK_MESSAGE_INFO_SET_MAG_OFFSETS, MAVLINK_MESSAGE_INFO_MEMINFO, MAVLINK_MESSAGE_INFO_AP_ADC, MAVLINK_MESSAGE_INFO_DIGICAM_CONFIGURE, MAVLINK_MESSAGE_INFO_DIGICAM_CONTROL, MAVLINK_MESSAGE_INFO_MOUNT_CONFIGURE, MAVLINK_MESSAGE_INFO_MOUNT_CONTROL, MAVLINK_MESSAGE_INFO_MOUNT_STATUS, MAVLINK_MESSAGE_INFO_FENCE_POINT, MAVLINK_MESSAGE_INFO_FENCE_FETCH_POINT, MAVLINK_MESSAGE_INFO_FENCE_STATUS, MAVLINK_MESSAGE_INFO_AHRS, MAVLINK_MESSAGE_INFO_SIMSTATE, MAVLINK_MESSAGE_INFO_HWSTATUS, MAVLINK_MESSAGE_INFO_RADIO, MAVLINK_MESSAGE_INFO_LIMITS_STATUS, MAVLINK_MESSAGE_INFO_WIND, MAVLINK_MESSAGE_INFO_DATA16, MAVLINK_MESSAGE_INFO_DATA32, MAVLINK_MESSAGE_INFO_DATA64, MAVLINK_MESSAGE_INFO_DATA96, MAVLINK_MESSAGE_INFO_RANGEFINDER, MAVLINK_MESSAGE_INFO_AIRSPEED_AUTOCAL, MAVLINK_MESSAGE_INFO_RALLY_POINT, MAVLINK_MESSAGE_INFO_RALLY_FETCH_POINT, MAVLINK_MESSAGE_INFO_COMPASSMOT_STATUS, MAVLINK_MESSAGE_INFO_AHRS2, MAVLINK_MESSAGE_INFO_CAMERA_STATUS, MAVLINK_MESSAGE_INFO_CAMERA_FEEDBACK, MAVLINK_MESSAGE_INFO_BATTERY2, MAVLINK_MESSAGE_INFO_AHRS3, MAVLINK_MESSAGE_INFO_AUTOPILOT_VERSION_REQUEST, MAVLINK_MESSAGE_INFO_REMOTE_LOG_DATA_BLOCK, MAVLINK_MESSAGE_INFO_REMOTE_LOG_BLOCK_STATUS, MAVLINK_MESSAGE_INFO_LED_CONTROL, MAVLINK_MESSAGE_INFO_MAG_CAL_PROGRESS, MAVLINK_MESSAGE_INFO_MAG_CAL_REPORT, MAVLINK_MESSAGE_INFO_EKF_STATUS_REPORT, MAVLINK_MESSAGE_INFO_PID_TUNING, MAVLINK_MESSAGE_INFO_DEEPSTALL, MAVLINK_MESSAGE_INFO_GIMBAL_REPORT, MAVLINK_MESSAGE_INFO_GIMBAL_CONTROL, MAVLINK_MESSAGE_INFO_GIMBAL_TORQUE_CMD_REPORT, MAVLINK_MESSAGE_INFO_GOPRO_HEARTBEAT, MAVLINK_MESSAGE_INFO_GOPRO_GET_REQUEST, MAVLINK_MESSAGE_INFO_GOPRO_GET_RESPONSE, MAVLINK_MESSAGE_INFO_GOPRO_SET_REQUEST, MAVLINK_MESSAGE_INFO_GOPRO_SET_RESPONSE, MAVLINK_MESSAGE_INFO_EFI_STATUS, MAVLINK_MESSAGE_INFO_RPM, MAVLINK_MESSAGE_INFO_ESTIMATOR_STATUS, MAVLINK_MESSAGE_INFO_WIND_COV, MAVLINK_MESSAGE_INFO_GPS_INPUT, MAVLINK_MESSAGE_INFO_GPS_RTCM_DATA, MAVLINK_MESSAGE_INFO_HIGH_LATENCY, MAVLINK_MESSAGE_INFO_HIGH_LATENCY2, MAVLINK_MESSAGE_INFO_VIBRATION, MAVLINK_MESSAGE_INFO_HOME_POSITION, MAVLINK_MESSAGE_INFO_SET_HOME_POSITION, MAVLINK_MESSAGE_INFO_MESSAGE_INTERVAL, MAVLINK_MESSAGE_INFO_EXTENDED_SYS_STATE, MAVLINK_MESSAGE_INFO_ADSB_VEHICLE, MAVLINK_MESSAGE_INFO_COLLISION, MAVLINK_MESSAGE_INFO_V2_EXTENSION, MAVLINK_MESSAGE_INFO_MEMORY_VECT, MAVLINK_MESSAGE_INFO_DEBUG_VECT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT, MAVLINK_MESSAGE_INFO_STATUSTEXT, MAVLINK_MESSAGE_INFO_DEBUG, MAVLINK_MESSAGE_INFO_SETUP_SIGNING, MAVLINK_MESSAGE_INFO_BUTTON_CHANGE, MAVLINK_MESSAGE_INFO_PLAY_TUNE, MAVLINK_MESSAGE_INFO_CAMERA_INFORMATION, MAVLINK_MESSAGE_INFO_CAMERA_SETTINGS, MAVLINK_MESSAGE_INFO_STORAGE_INFORMATION, MAVLINK_MESSAGE_INFO_CAMERA_CAPTURE_STATUS, MAVLINK_MESSAGE_INFO_CAMERA_IMAGE_CAPTURED, MAVLINK_MESSAGE_INFO_FLIGHT_INFORMATION, MAVLINK_MESSAGE_INFO_MOUNT_ORIENTATION, MAVLINK_MESSAGE_INFO_LOGGING_DATA, MAVLINK_MESSAGE_INFO_LOGGING_DATA_ACKED, MAVLINK_MESSAGE_INFO_LOGGING_ACK, MAVLINK_MESSAGE_INFO_VIDEO_STREAM_INFORMATION, MAVLINK_MESSAGE_INFO_VIDEO_STREAM_STATUS, MAVLINK_MESSAGE_INFO_CAMERA_FOV_STATUS, MAVLINK_MESSAGE_INFO_CAMERA_TRACKING_IMAGE_STATUS, MAVLINK_MESSAGE_INFO_CAMERA_TRACKING_GEO_STATUS, MAVLINK_MESSAGE_INFO_CAMERA_THERMAL_RANGE, MAVLINK_MESSAGE_INFO_GIMBAL_MANAGER_INFORMATION, MAVLINK_MESSAGE_INFO_GIMBAL_MANAGER_STATUS, MAVLINK_MESSAGE_INFO_GIMBAL_MANAGER_SET_ATTITUDE, MAVLINK_MESSAGE_INFO_GIMBAL_DEVICE_INFORMATION, MAVLINK_MESSAGE_INFO_GIMBAL_DEVICE_SET_ATTITUDE, MAVLINK_MESSAGE_INFO_GIMBAL_DEVICE_ATTITUDE_STATUS, MAVLINK_MESSAGE_INFO_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE, MAVLINK_MESSAGE_INFO_GIMBAL_MANAGER_SET_PITCHYAW, MAVLINK_MESSAGE_INFO_GIMBAL_MANAGER_SET_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_ESC_INFO, MAVLINK_MESSAGE_INFO_ESC_STATUS, MAVLINK_MESSAGE_INFO_AIRSPEED, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_SENSOR, MAVLINK_MESSAGE_INFO_WIFI_CONFIG_AP, MAVLINK_MESSAGE_INFO_PROTOCOL_VERSION, MAVLINK_MESSAGE_INFO_AIS_VESSEL, MAVLINK_MESSAGE_INFO_UAVCAN_NODE_STATUS, MAVLINK_MESSAGE_INFO_UAVCAN_NODE_INFO, MAVLINK_MESSAGE_INFO_PARAM_EXT_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_EXT_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_EXT_VALUE, MAVLINK_MESSAGE_INFO_PARAM_EXT_SET, MAVLINK_MESSAGE_INFO_PARAM_EXT_ACK, MAVLINK_MESSAGE_INFO_OBSTACLE_DISTANCE, MAVLINK_MESSAGE_INFO_ODOMETRY, MAVLINK_MESSAGE_INFO_TRAJECTORY_REPRESENTATION_WAYPOINTS, MAVLINK_MESSAGE_INFO_TRAJECTORY_REPRESENTATION_BEZIER, MAVLINK_MESSAGE_INFO_CELLULAR_STATUS, MAVLINK_MESSAGE_INFO_ISBD_LINK_STATUS, MAVLINK_MESSAGE_INFO_CELLULAR_CONFIG, MAVLINK_MESSAGE_INFO_RAW_RPM, MAVLINK_MESSAGE_INFO_UTM_GLOBAL_POSITION, MAVLINK_MESSAGE_INFO_PARAM_ERROR, MAVLINK_MESSAGE_INFO_DEBUG_FLOAT_ARRAY, MAVLINK_MESSAGE_INFO_ORBIT_EXECUTION_STATUS, MAVLINK_MESSAGE_INFO_FIGURE_EIGHT_EXECUTION_STATUS, MAVLINK_MESSAGE_INFO_SMART_BATTERY_INFO, MAVLINK_MESSAGE_INFO_FUEL_STATUS, MAVLINK_MESSAGE_INFO_BATTERY_INFO, MAVLINK_MESSAGE_INFO_GENERATOR_STATUS, MAVLINK_MESSAGE_INFO_ACTUATOR_OUTPUT_STATUS, MAVLINK_MESSAGE_INFO_RELAY_STATUS, MAVLINK_MESSAGE_INFO_TIME_ESTIMATE_TO_TARGET, MAVLINK_MESSAGE_INFO_TUNNEL, MAVLINK_MESSAGE_INFO_CAN_FRAME, MAVLINK_MESSAGE_INFO_CANFD_FRAME, MAVLINK_MESSAGE_INFO_CAN_FILTER_MODIFY, MAVLINK_MESSAGE_INFO_ONBOARD_COMPUTER_STATUS, MAVLINK_MESSAGE_INFO_COMPONENT_INFORMATION, MAVLINK_MESSAGE_INFO_COMPONENT_INFORMATION_BASIC, MAVLINK_MESSAGE_INFO_COMPONENT_METADATA, MAVLINK_MESSAGE_INFO_PLAY_TUNE_V2, MAVLINK_MESSAGE_INFO_SUPPORTED_TUNES, MAVLINK_MESSAGE_INFO_EVENT, MAVLINK_MESSAGE_INFO_CURRENT_EVENT_SEQUENCE, MAVLINK_MESSAGE_INFO_REQUEST_EVENT, MAVLINK_MESSAGE_INFO_RESPONSE_EVENT_ERROR, MAVLINK_MESSAGE_INFO_AVAILABLE_MODES, MAVLINK_MESSAGE_INFO_CURRENT_MODE, MAVLINK_MESSAGE_INFO_AVAILABLE_MODES_MONITOR, MAVLINK_MESSAGE_INFO_ILLUMINATOR_STATUS, MAVLINK_MESSAGE_INFO_WHEEL_DISTANCE, MAVLINK_MESSAGE_INFO_WINCH_STATUS, MAVLINK_MESSAGE_INFO_UAVIONIX_ADSB_OUT_CFG, MAVLINK_MESSAGE_INFO_UAVIONIX_ADSB_OUT_DYNAMIC, MAVLINK_MESSAGE_INFO_UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT, MAVLINK_MESSAGE_INFO_UAVIONIX_ADSB_OUT_CFG_REGISTRATION, MAVLINK_MESSAGE_INFO_UAVIONIX_ADSB_OUT_CFG_FLIGHTID, MAVLINK_MESSAGE_INFO_UAVIONIX_ADSB_GET, MAVLINK_MESSAGE_INFO_UAVIONIX_ADSB_OUT_CONTROL, MAVLINK_MESSAGE_INFO_UAVIONIX_ADSB_OUT_STATUS, MAVLINK_MESSAGE_INFO_LOWEHEISER_GOV_EFI, MAVLINK_MESSAGE_INFO_DEVICE_OP_READ, MAVLINK_MESSAGE_INFO_DEVICE_OP_READ_REPLY, MAVLINK_MESSAGE_INFO_DEVICE_OP_WRITE, MAVLINK_MESSAGE_INFO_DEVICE_OP_WRITE_REPLY, MAVLINK_MESSAGE_INFO_SECURE_COMMAND, MAVLINK_MESSAGE_INFO_SECURE_COMMAND_REPLY, MAVLINK_MESSAGE_INFO_ADAP_TUNING, MAVLINK_MESSAGE_INFO_VISION_POSITION_DELTA, MAVLINK_MESSAGE_INFO_AOA_SSA, MAVLINK_MESSAGE_INFO_ESC_TELEMETRY_1_TO_4, MAVLINK_MESSAGE_INFO_ESC_TELEMETRY_5_TO_8, MAVLINK_MESSAGE_INFO_ESC_TELEMETRY_9_TO_12, MAVLINK_MESSAGE_INFO_OSD_PARAM_CONFIG, MAVLINK_MESSAGE_INFO_OSD_PARAM_CONFIG_REPLY, MAVLINK_MESSAGE_INFO_OSD_PARAM_SHOW_CONFIG, MAVLINK_MESSAGE_INFO_OSD_PARAM_SHOW_CONFIG_REPLY, MAVLINK_MESSAGE_INFO_OBSTACLE_DISTANCE_3D, MAVLINK_MESSAGE_INFO_WATER_DEPTH, MAVLINK_MESSAGE_INFO_MCU_STATUS, MAVLINK_MESSAGE_INFO_ESC_TELEMETRY_13_TO_16, MAVLINK_MESSAGE_INFO_ESC_TELEMETRY_17_TO_20, MAVLINK_MESSAGE_INFO_ESC_TELEMETRY_21_TO_24, MAVLINK_MESSAGE_INFO_ESC_TELEMETRY_25_TO_28, MAVLINK_MESSAGE_INFO_ESC_TELEMETRY_29_TO_32, MAVLINK_MESSAGE_INFO_NAMED_VALUE_STRING, MAVLINK_MESSAGE_INFO_OPEN_DRONE_ID_BASIC_ID, MAVLINK_MESSAGE_INFO_OPEN_DRONE_ID_LOCATION, MAVLINK_MESSAGE_INFO_OPEN_DRONE_ID_AUTHENTICATION, MAVLINK_MESSAGE_INFO_OPEN_DRONE_ID_SELF_ID, MAVLINK_MESSAGE_INFO_OPEN_DRONE_ID_SYSTEM, MAVLINK_MESSAGE_INFO_OPEN_DRONE_ID_OPERATOR_ID, MAVLINK_MESSAGE_INFO_OPEN_DRONE_ID_MESSAGE_PACK, MAVLINK_MESSAGE_INFO_OPEN_DRONE_ID_ARM_STATUS, MAVLINK_MESSAGE_INFO_OPEN_DRONE_ID_SYSTEM_UPDATE, MAVLINK_MESSAGE_INFO_HYGROMETER_SENSOR, MAVLINK_MESSAGE_INFO_ICAROUS_HEARTBEAT, MAVLINK_MESSAGE_INFO_ICAROUS_KINEMATIC_BANDS, MAVLINK_MESSAGE_INFO_CUBEPILOT_RAW_RC, MAVLINK_MESSAGE_INFO_HERELINK_VIDEO_STREAM_INFORMATION, MAVLINK_MESSAGE_INFO_HERELINK_TELEM, MAVLINK_MESSAGE_INFO_CUBEPILOT_FIRMWARE_UPDATE_START, MAVLINK_MESSAGE_INFO_CUBEPILOT_FIRMWARE_UPDATE_RESP, MAVLINK_MESSAGE_INFO_AIRLINK_AUTH, MAVLINK_MESSAGE_INFO_AIRLINK_AUTH_RESPONSE}
+# define MAVLINK_MESSAGE_NAMES {{ "ACTUATOR_CONTROL_TARGET", 140 }, { "ACTUATOR_OUTPUT_STATUS", 375 }, { "ADAP_TUNING", 11010 }, { "ADSB_VEHICLE", 246 }, { "AHRS", 163 }, { "AHRS2", 178 }, { "AHRS3", 182 }, { "AIRLINK_AUTH", 52000 }, { "AIRLINK_AUTH_RESPONSE", 52001 }, { "AIRSPEED", 295 }, { "AIRSPEED_AUTOCAL", 174 }, { "AIS_VESSEL", 301 }, { "ALTITUDE", 141 }, { "AOA_SSA", 11020 }, { "AP_ADC", 153 }, { "ATTITUDE", 30 }, { "ATTITUDE_QUATERNION", 31 }, { "ATTITUDE_QUATERNION_COV", 61 }, { "ATTITUDE_TARGET", 83 }, { "ATT_POS_MOCAP", 138 }, { "AUTH_KEY", 7 }, { "AUTOPILOT_STATE_FOR_GIMBAL_DEVICE", 286 }, { "AUTOPILOT_VERSION", 148 }, { "AUTOPILOT_VERSION_REQUEST", 183 }, { "AVAILABLE_MODES", 435 }, { "AVAILABLE_MODES_MONITOR", 437 }, { "BATTERY2", 181 }, { "BATTERY_INFO", 372 }, { "BATTERY_STATUS", 147 }, { "BUTTON_CHANGE", 257 }, { "CAMERA_CAPTURE_STATUS", 262 }, { "CAMERA_FEEDBACK", 180 }, { "CAMERA_FOV_STATUS", 271 }, { "CAMERA_IMAGE_CAPTURED", 263 }, { "CAMERA_INFORMATION", 259 }, { "CAMERA_SETTINGS", 260 }, { "CAMERA_STATUS", 179 }, { "CAMERA_THERMAL_RANGE", 277 }, { "CAMERA_TRACKING_GEO_STATUS", 276 }, { "CAMERA_TRACKING_IMAGE_STATUS", 275 }, { "CAMERA_TRIGGER", 112 }, { "CANFD_FRAME", 387 }, { "CAN_FILTER_MODIFY", 388 }, { "CAN_FRAME", 386 }, { "CELLULAR_CONFIG", 336 }, { "CELLULAR_STATUS", 334 }, { "CHANGE_OPERATOR_CONTROL", 5 }, { "CHANGE_OPERATOR_CONTROL_ACK", 6 }, { "COLLISION", 247 }, { "COMMAND_ACK", 77 }, { "COMMAND_CANCEL", 80 }, { "COMMAND_INT", 75 }, { "COMMAND_LONG", 76 }, { "COMPASSMOT_STATUS", 177 }, { "COMPONENT_INFORMATION", 395 }, { "COMPONENT_INFORMATION_BASIC", 396 }, { "COMPONENT_METADATA", 397 }, { "CONTROL_SYSTEM_STATE", 146 }, { "CUBEPILOT_FIRMWARE_UPDATE_RESP", 50005 }, { "CUBEPILOT_FIRMWARE_UPDATE_START", 50004 }, { "CUBEPILOT_RAW_RC", 50001 }, { "CURRENT_EVENT_SEQUENCE", 411 }, { "CURRENT_MODE", 436 }, { "DATA16", 169 }, { "DATA32", 170 }, { "DATA64", 171 }, { "DATA96", 172 }, { "DATA_STREAM", 67 }, { "DATA_TRANSMISSION_HANDSHAKE", 130 }, { "DEBUG", 254 }, { "DEBUG_FLOAT_ARRAY", 350 }, { "DEBUG_VECT", 250 }, { "DEEPSTALL", 195 }, { "DEVICE_OP_READ", 11000 }, { "DEVICE_OP_READ_REPLY", 11001 }, { "DEVICE_OP_WRITE", 11002 }, { "DEVICE_OP_WRITE_REPLY", 11003 }, { "DIGICAM_CONFIGURE", 154 }, { "DIGICAM_CONTROL", 155 }, { "DISTANCE_SENSOR", 132 }, { "EFI_STATUS", 225 }, { "EKF_STATUS_REPORT", 193 }, { "ENCAPSULATED_DATA", 131 }, { "ESC_INFO", 290 }, { "ESC_STATUS", 291 }, { "ESC_TELEMETRY_13_TO_16", 11040 }, { "ESC_TELEMETRY_17_TO_20", 11041 }, { "ESC_TELEMETRY_1_TO_4", 11030 }, { "ESC_TELEMETRY_21_TO_24", 11042 }, { "ESC_TELEMETRY_25_TO_28", 11043 }, { "ESC_TELEMETRY_29_TO_32", 11044 }, { "ESC_TELEMETRY_5_TO_8", 11031 }, { "ESC_TELEMETRY_9_TO_12", 11032 }, { "ESTIMATOR_STATUS", 230 }, { "EVENT", 410 }, { "EXTENDED_SYS_STATE", 245 }, { "FENCE_FETCH_POINT", 161 }, { "FENCE_POINT", 160 }, { "FENCE_STATUS", 162 }, { "FIGURE_EIGHT_EXECUTION_STATUS", 361 }, { "FILE_TRANSFER_PROTOCOL", 110 }, { "FLIGHT_INFORMATION", 264 }, { "FOLLOW_TARGET", 144 }, { "FUEL_STATUS", 371 }, { "GENERATOR_STATUS", 373 }, { "GIMBAL_CONTROL", 201 }, { "GIMBAL_DEVICE_ATTITUDE_STATUS", 285 }, { "GIMBAL_DEVICE_INFORMATION", 283 }, { "GIMBAL_DEVICE_SET_ATTITUDE", 284 }, { "GIMBAL_MANAGER_INFORMATION", 280 }, { "GIMBAL_MANAGER_SET_ATTITUDE", 282 }, { "GIMBAL_MANAGER_SET_MANUAL_CONTROL", 288 }, { "GIMBAL_MANAGER_SET_PITCHYAW", 287 }, { "GIMBAL_MANAGER_STATUS", 281 }, { "GIMBAL_REPORT", 200 }, { "GIMBAL_TORQUE_CMD_REPORT", 214 }, { "GLOBAL_POSITION_INT", 33 }, { "GLOBAL_POSITION_INT_COV", 63 }, { "GLOBAL_POSITION_SENSOR", 296 }, { "GLOBAL_VISION_POSITION_ESTIMATE", 101 }, { "GOPRO_GET_REQUEST", 216 }, { "GOPRO_GET_RESPONSE", 217 }, { "GOPRO_HEARTBEAT", 215 }, { "GOPRO_SET_REQUEST", 218 }, { "GOPRO_SET_RESPONSE", 219 }, { "GPS2_RAW", 124 }, { "GPS2_RTK", 128 }, { "GPS_GLOBAL_ORIGIN", 49 }, { "GPS_INJECT_DATA", 123 }, { "GPS_INPUT", 232 }, { "GPS_RAW_INT", 24 }, { "GPS_RTCM_DATA", 233 }, { "GPS_RTK", 127 }, { "GPS_STATUS", 25 }, { "HEARTBEAT", 0 }, { "HERELINK_TELEM", 50003 }, { "HERELINK_VIDEO_STREAM_INFORMATION", 50002 }, { "HIGHRES_IMU", 105 }, { "HIGH_LATENCY", 234 }, { "HIGH_LATENCY2", 235 }, { "HIL_ACTUATOR_CONTROLS", 93 }, { "HIL_CONTROLS", 91 }, { "HIL_GPS", 113 }, { "HIL_OPTICAL_FLOW", 114 }, { "HIL_RC_INPUTS_RAW", 92 }, { "HIL_SENSOR", 107 }, { "HIL_STATE", 90 }, { "HIL_STATE_QUATERNION", 115 }, { "HOME_POSITION", 242 }, { "HWSTATUS", 165 }, { "HYGROMETER_SENSOR", 12920 }, { "ICAROUS_HEARTBEAT", 42000 }, { "ICAROUS_KINEMATIC_BANDS", 42001 }, { "ILLUMINATOR_STATUS", 440 }, { "ISBD_LINK_STATUS", 335 }, { "LANDING_TARGET", 149 }, { "LED_CONTROL", 186 }, { "LIMITS_STATUS", 167 }, { "LINK_NODE_STATUS", 8 }, { "LOCAL_POSITION_NED", 32 }, { "LOCAL_POSITION_NED_COV", 64 }, { "LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET", 89 }, { "LOGGING_ACK", 268 }, { "LOGGING_DATA", 266 }, { "LOGGING_DATA_ACKED", 267 }, { "LOG_DATA", 120 }, { "LOG_ENTRY", 118 }, { "LOG_ERASE", 121 }, { "LOG_REQUEST_DATA", 119 }, { "LOG_REQUEST_END", 122 }, { "LOG_REQUEST_LIST", 117 }, { "LOWEHEISER_GOV_EFI", 10151 }, { "MAG_CAL_PROGRESS", 191 }, { "MAG_CAL_REPORT", 192 }, { "MANUAL_CONTROL", 69 }, { "MANUAL_SETPOINT", 81 }, { "MCU_STATUS", 11039 }, { "MEMINFO", 152 }, { "MEMORY_VECT", 249 }, { "MESSAGE_INTERVAL", 244 }, { "MISSION_ACK", 47 }, { "MISSION_CLEAR_ALL", 45 }, { "MISSION_COUNT", 44 }, { "MISSION_CURRENT", 42 }, { "MISSION_ITEM", 39 }, { "MISSION_ITEM_INT", 73 }, { "MISSION_ITEM_REACHED", 46 }, { "MISSION_REQUEST", 40 }, { "MISSION_REQUEST_INT", 51 }, { "MISSION_REQUEST_LIST", 43 }, { "MISSION_REQUEST_PARTIAL_LIST", 37 }, { "MISSION_SET_CURRENT", 41 }, { "MISSION_WRITE_PARTIAL_LIST", 38 }, { "MOUNT_CONFIGURE", 156 }, { "MOUNT_CONTROL", 157 }, { "MOUNT_ORIENTATION", 265 }, { "MOUNT_STATUS", 158 }, { "NAMED_VALUE_FLOAT", 251 }, { "NAMED_VALUE_INT", 252 }, { "NAMED_VALUE_STRING", 11060 }, { "NAV_CONTROLLER_OUTPUT", 62 }, { "OBSTACLE_DISTANCE", 330 }, { "OBSTACLE_DISTANCE_3D", 11037 }, { "ODOMETRY", 331 }, { "ONBOARD_COMPUTER_STATUS", 390 }, { "OPEN_DRONE_ID_ARM_STATUS", 12918 }, { "OPEN_DRONE_ID_AUTHENTICATION", 12902 }, { "OPEN_DRONE_ID_BASIC_ID", 12900 }, { "OPEN_DRONE_ID_LOCATION", 12901 }, { "OPEN_DRONE_ID_MESSAGE_PACK", 12915 }, { "OPEN_DRONE_ID_OPERATOR_ID", 12905 }, { "OPEN_DRONE_ID_SELF_ID", 12903 }, { "OPEN_DRONE_ID_SYSTEM", 12904 }, { "OPEN_DRONE_ID_SYSTEM_UPDATE", 12919 }, { "OPTICAL_FLOW", 100 }, { "OPTICAL_FLOW_RAD", 106 }, { "ORBIT_EXECUTION_STATUS", 360 }, { "OSD_PARAM_CONFIG", 11033 }, { "OSD_PARAM_CONFIG_REPLY", 11034 }, { "OSD_PARAM_SHOW_CONFIG", 11035 }, { "OSD_PARAM_SHOW_CONFIG_REPLY", 11036 }, { "PARAM_ERROR", 345 }, { "PARAM_EXT_ACK", 324 }, { "PARAM_EXT_REQUEST_LIST", 321 }, { "PARAM_EXT_REQUEST_READ", 320 }, { "PARAM_EXT_SET", 323 }, { "PARAM_EXT_VALUE", 322 }, { "PARAM_MAP_RC", 50 }, { "PARAM_REQUEST_LIST", 21 }, { "PARAM_REQUEST_READ", 20 }, { "PARAM_SET", 23 }, { "PARAM_VALUE", 22 }, { "PID_TUNING", 194 }, { "PING", 4 }, { "PLAY_TUNE", 258 }, { "PLAY_TUNE_V2", 400 }, { "POSITION_TARGET_GLOBAL_INT", 87 }, { "POSITION_TARGET_LOCAL_NED", 85 }, { "POWER_STATUS", 125 }, { "PROTOCOL_VERSION", 300 }, { "RADIO", 166 }, { "RADIO_STATUS", 109 }, { "RALLY_FETCH_POINT", 176 }, { "RALLY_POINT", 175 }, { "RANGEFINDER", 173 }, { "RAW_IMU", 27 }, { "RAW_PRESSURE", 28 }, { "RAW_RPM", 339 }, { "RC_CHANNELS", 65 }, { "RC_CHANNELS_OVERRIDE", 70 }, { "RC_CHANNELS_RAW", 35 }, { "RC_CHANNELS_SCALED", 34 }, { "RELAY_STATUS", 376 }, { "REMOTE_LOG_BLOCK_STATUS", 185 }, { "REMOTE_LOG_DATA_BLOCK", 184 }, { "REQUEST_DATA_STREAM", 66 }, { "REQUEST_EVENT", 412 }, { "RESOURCE_REQUEST", 142 }, { "RESPONSE_EVENT_ERROR", 413 }, { "RPM", 226 }, { "SAFETY_ALLOWED_AREA", 55 }, { "SAFETY_SET_ALLOWED_AREA", 54 }, { "SCALED_IMU", 26 }, { "SCALED_IMU2", 116 }, { "SCALED_IMU3", 129 }, { "SCALED_PRESSURE", 29 }, { "SCALED_PRESSURE2", 137 }, { "SCALED_PRESSURE3", 143 }, { "SECURE_COMMAND", 11004 }, { "SECURE_COMMAND_REPLY", 11005 }, { "SENSOR_OFFSETS", 150 }, { "SERIAL_CONTROL", 126 }, { "SERVO_OUTPUT_RAW", 36 }, { "SETUP_SIGNING", 256 }, { "SET_ACTUATOR_CONTROL_TARGET", 139 }, { "SET_ATTITUDE_TARGET", 82 }, { "SET_GPS_GLOBAL_ORIGIN", 48 }, { "SET_HOME_POSITION", 243 }, { "SET_MAG_OFFSETS", 151 }, { "SET_MODE", 11 }, { "SET_POSITION_TARGET_GLOBAL_INT", 86 }, { "SET_POSITION_TARGET_LOCAL_NED", 84 }, { "SIMSTATE", 164 }, { "SIM_STATE", 108 }, { "SMART_BATTERY_INFO", 370 }, { "STATUSTEXT", 253 }, { "STORAGE_INFORMATION", 261 }, { "SUPPORTED_TUNES", 401 }, { "SYSTEM_TIME", 2 }, { "SYS_STATUS", 1 }, { "TERRAIN_CHECK", 135 }, { "TERRAIN_DATA", 134 }, { "TERRAIN_REPORT", 136 }, { "TERRAIN_REQUEST", 133 }, { "TIMESYNC", 111 }, { "TIME_ESTIMATE_TO_TARGET", 380 }, { "TRAJECTORY_REPRESENTATION_BEZIER", 333 }, { "TRAJECTORY_REPRESENTATION_WAYPOINTS", 332 }, { "TUNNEL", 385 }, { "UAVCAN_NODE_INFO", 311 }, { "UAVCAN_NODE_STATUS", 310 }, { "UAVIONIX_ADSB_GET", 10006 }, { "UAVIONIX_ADSB_OUT_CFG", 10001 }, { "UAVIONIX_ADSB_OUT_CFG_FLIGHTID", 10005 }, { "UAVIONIX_ADSB_OUT_CFG_REGISTRATION", 10004 }, { "UAVIONIX_ADSB_OUT_CONTROL", 10007 }, { "UAVIONIX_ADSB_OUT_DYNAMIC", 10002 }, { "UAVIONIX_ADSB_OUT_STATUS", 10008 }, { "UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT", 10003 }, { "UTM_GLOBAL_POSITION", 340 }, { "V2_EXTENSION", 248 }, { "VFR_HUD", 74 }, { "VIBRATION", 241 }, { "VICON_POSITION_ESTIMATE", 104 }, { "VIDEO_STREAM_INFORMATION", 269 }, { "VIDEO_STREAM_STATUS", 270 }, { "VISION_POSITION_DELTA", 11011 }, { "VISION_POSITION_ESTIMATE", 102 }, { "VISION_SPEED_ESTIMATE", 103 }, { "WATER_DEPTH", 11038 }, { "WHEEL_DISTANCE", 9000 }, { "WIFI_CONFIG_AP", 299 }, { "WINCH_STATUS", 9005 }, { "WIND", 168 }, { "WIND_COV", 231 }}
+# if MAVLINK_COMMAND_24BIT
+# include "../mavlink_get_info.h"
+# endif
+#endif
+
+#ifdef __cplusplus
+}
+#endif // __cplusplus
+#endif // MAVLINK_ARDUPILOTMEGA_H
diff --git a/lib/main/MAVLink/ardupilotmega/mavlink.h b/lib/main/MAVLink/ardupilotmega/mavlink.h
new file mode 100644
index 00000000000..3a04c625591
--- /dev/null
+++ b/lib/main/MAVLink/ardupilotmega/mavlink.h
@@ -0,0 +1,34 @@
+/** @file
+ * @brief MAVLink comm protocol built from ardupilotmega.xml
+ * @see http://mavlink.org
+ */
+#pragma once
+#ifndef MAVLINK_H
+#define MAVLINK_H
+
+#define MAVLINK_PRIMARY_XML_HASH -8353338523788949766
+
+#ifndef MAVLINK_STX
+#define MAVLINK_STX 253
+#endif
+
+#ifndef MAVLINK_ENDIAN
+#define MAVLINK_ENDIAN MAVLINK_LITTLE_ENDIAN
+#endif
+
+#ifndef MAVLINK_ALIGNED_FIELDS
+#define MAVLINK_ALIGNED_FIELDS 1
+#endif
+
+#ifndef MAVLINK_CRC_EXTRA
+#define MAVLINK_CRC_EXTRA 1
+#endif
+
+#ifndef MAVLINK_COMMAND_24BIT
+#define MAVLINK_COMMAND_24BIT 1
+#endif
+
+#include "version.h"
+#include "ardupilotmega.h"
+
+#endif // MAVLINK_H
diff --git a/lib/main/MAVLink/ardupilotmega/mavlink_msg_adap_tuning.h b/lib/main/MAVLink/ardupilotmega/mavlink_msg_adap_tuning.h
new file mode 100644
index 00000000000..2424ee96b48
--- /dev/null
+++ b/lib/main/MAVLink/ardupilotmega/mavlink_msg_adap_tuning.h
@@ -0,0 +1,596 @@
+#pragma once
+// MESSAGE ADAP_TUNING PACKING
+
+#define MAVLINK_MSG_ID_ADAP_TUNING 11010
+
+
+typedef struct __mavlink_adap_tuning_t {
+ float desired; /*< [deg/s] Desired rate.*/
+ float achieved; /*< [deg/s] Achieved rate.*/
+ float error; /*< Error between model and vehicle.*/
+ float theta; /*< Theta estimated state predictor.*/
+ float omega; /*< Omega estimated state predictor.*/
+ float sigma; /*< Sigma estimated state predictor.*/
+ float theta_dot; /*< Theta derivative.*/
+ float omega_dot; /*< Omega derivative.*/
+ float sigma_dot; /*< Sigma derivative.*/
+ float f; /*< Projection operator value.*/
+ float f_dot; /*< Projection operator derivative.*/
+ float u; /*< u adaptive controlled output command.*/
+ uint8_t axis; /*< Axis.*/
+} mavlink_adap_tuning_t;
+
+#define MAVLINK_MSG_ID_ADAP_TUNING_LEN 49
+#define MAVLINK_MSG_ID_ADAP_TUNING_MIN_LEN 49
+#define MAVLINK_MSG_ID_11010_LEN 49
+#define MAVLINK_MSG_ID_11010_MIN_LEN 49
+
+#define MAVLINK_MSG_ID_ADAP_TUNING_CRC 46
+#define MAVLINK_MSG_ID_11010_CRC 46
+
+
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_ADAP_TUNING { \
+ 11010, \
+ "ADAP_TUNING", \
+ 13, \
+ { { "axis", NULL, MAVLINK_TYPE_UINT8_T, 0, 48, offsetof(mavlink_adap_tuning_t, axis) }, \
+ { "desired", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_adap_tuning_t, desired) }, \
+ { "achieved", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_adap_tuning_t, achieved) }, \
+ { "error", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_adap_tuning_t, error) }, \
+ { "theta", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_adap_tuning_t, theta) }, \
+ { "omega", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_adap_tuning_t, omega) }, \
+ { "sigma", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_adap_tuning_t, sigma) }, \
+ { "theta_dot", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_adap_tuning_t, theta_dot) }, \
+ { "omega_dot", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_adap_tuning_t, omega_dot) }, \
+ { "sigma_dot", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_adap_tuning_t, sigma_dot) }, \
+ { "f", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_adap_tuning_t, f) }, \
+ { "f_dot", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_adap_tuning_t, f_dot) }, \
+ { "u", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_adap_tuning_t, u) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_ADAP_TUNING { \
+ "ADAP_TUNING", \
+ 13, \
+ { { "axis", NULL, MAVLINK_TYPE_UINT8_T, 0, 48, offsetof(mavlink_adap_tuning_t, axis) }, \
+ { "desired", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_adap_tuning_t, desired) }, \
+ { "achieved", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_adap_tuning_t, achieved) }, \
+ { "error", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_adap_tuning_t, error) }, \
+ { "theta", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_adap_tuning_t, theta) }, \
+ { "omega", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_adap_tuning_t, omega) }, \
+ { "sigma", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_adap_tuning_t, sigma) }, \
+ { "theta_dot", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_adap_tuning_t, theta_dot) }, \
+ { "omega_dot", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_adap_tuning_t, omega_dot) }, \
+ { "sigma_dot", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_adap_tuning_t, sigma_dot) }, \
+ { "f", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_adap_tuning_t, f) }, \
+ { "f_dot", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_adap_tuning_t, f_dot) }, \
+ { "u", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_adap_tuning_t, u) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a adap_tuning 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 axis Axis.
+ * @param desired [deg/s] Desired rate.
+ * @param achieved [deg/s] Achieved rate.
+ * @param error Error between model and vehicle.
+ * @param theta Theta estimated state predictor.
+ * @param omega Omega estimated state predictor.
+ * @param sigma Sigma estimated state predictor.
+ * @param theta_dot Theta derivative.
+ * @param omega_dot Omega derivative.
+ * @param sigma_dot Sigma derivative.
+ * @param f Projection operator value.
+ * @param f_dot Projection operator derivative.
+ * @param u u adaptive controlled output command.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_adap_tuning_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint8_t axis, float desired, float achieved, float error, float theta, float omega, float sigma, float theta_dot, float omega_dot, float sigma_dot, float f, float f_dot, float u)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_ADAP_TUNING_LEN];
+ _mav_put_float(buf, 0, desired);
+ _mav_put_float(buf, 4, achieved);
+ _mav_put_float(buf, 8, error);
+ _mav_put_float(buf, 12, theta);
+ _mav_put_float(buf, 16, omega);
+ _mav_put_float(buf, 20, sigma);
+ _mav_put_float(buf, 24, theta_dot);
+ _mav_put_float(buf, 28, omega_dot);
+ _mav_put_float(buf, 32, sigma_dot);
+ _mav_put_float(buf, 36, f);
+ _mav_put_float(buf, 40, f_dot);
+ _mav_put_float(buf, 44, u);
+ _mav_put_uint8_t(buf, 48, axis);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ADAP_TUNING_LEN);
+#else
+ mavlink_adap_tuning_t packet;
+ packet.desired = desired;
+ packet.achieved = achieved;
+ packet.error = error;
+ packet.theta = theta;
+ packet.omega = omega;
+ packet.sigma = sigma;
+ packet.theta_dot = theta_dot;
+ packet.omega_dot = omega_dot;
+ packet.sigma_dot = sigma_dot;
+ packet.f = f;
+ packet.f_dot = f_dot;
+ packet.u = u;
+ packet.axis = axis;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ADAP_TUNING_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_ADAP_TUNING;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ADAP_TUNING_MIN_LEN, MAVLINK_MSG_ID_ADAP_TUNING_LEN, MAVLINK_MSG_ID_ADAP_TUNING_CRC);
+}
+
+/**
+ * @brief Pack a adap_tuning 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 axis Axis.
+ * @param desired [deg/s] Desired rate.
+ * @param achieved [deg/s] Achieved rate.
+ * @param error Error between model and vehicle.
+ * @param theta Theta estimated state predictor.
+ * @param omega Omega estimated state predictor.
+ * @param sigma Sigma estimated state predictor.
+ * @param theta_dot Theta derivative.
+ * @param omega_dot Omega derivative.
+ * @param sigma_dot Sigma derivative.
+ * @param f Projection operator value.
+ * @param f_dot Projection operator derivative.
+ * @param u u adaptive controlled output command.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_adap_tuning_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ uint8_t axis, float desired, float achieved, float error, float theta, float omega, float sigma, float theta_dot, float omega_dot, float sigma_dot, float f, float f_dot, float u)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_ADAP_TUNING_LEN];
+ _mav_put_float(buf, 0, desired);
+ _mav_put_float(buf, 4, achieved);
+ _mav_put_float(buf, 8, error);
+ _mav_put_float(buf, 12, theta);
+ _mav_put_float(buf, 16, omega);
+ _mav_put_float(buf, 20, sigma);
+ _mav_put_float(buf, 24, theta_dot);
+ _mav_put_float(buf, 28, omega_dot);
+ _mav_put_float(buf, 32, sigma_dot);
+ _mav_put_float(buf, 36, f);
+ _mav_put_float(buf, 40, f_dot);
+ _mav_put_float(buf, 44, u);
+ _mav_put_uint8_t(buf, 48, axis);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ADAP_TUNING_LEN);
+#else
+ mavlink_adap_tuning_t packet;
+ packet.desired = desired;
+ packet.achieved = achieved;
+ packet.error = error;
+ packet.theta = theta;
+ packet.omega = omega;
+ packet.sigma = sigma;
+ packet.theta_dot = theta_dot;
+ packet.omega_dot = omega_dot;
+ packet.sigma_dot = sigma_dot;
+ packet.f = f;
+ packet.f_dot = f_dot;
+ packet.u = u;
+ packet.axis = axis;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ADAP_TUNING_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_ADAP_TUNING;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_ADAP_TUNING_MIN_LEN, MAVLINK_MSG_ID_ADAP_TUNING_LEN, MAVLINK_MSG_ID_ADAP_TUNING_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_ADAP_TUNING_MIN_LEN, MAVLINK_MSG_ID_ADAP_TUNING_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a adap_tuning 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 axis Axis.
+ * @param desired [deg/s] Desired rate.
+ * @param achieved [deg/s] Achieved rate.
+ * @param error Error between model and vehicle.
+ * @param theta Theta estimated state predictor.
+ * @param omega Omega estimated state predictor.
+ * @param sigma Sigma estimated state predictor.
+ * @param theta_dot Theta derivative.
+ * @param omega_dot Omega derivative.
+ * @param sigma_dot Sigma derivative.
+ * @param f Projection operator value.
+ * @param f_dot Projection operator derivative.
+ * @param u u adaptive controlled output command.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_adap_tuning_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint8_t axis,float desired,float achieved,float error,float theta,float omega,float sigma,float theta_dot,float omega_dot,float sigma_dot,float f,float f_dot,float u)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_ADAP_TUNING_LEN];
+ _mav_put_float(buf, 0, desired);
+ _mav_put_float(buf, 4, achieved);
+ _mav_put_float(buf, 8, error);
+ _mav_put_float(buf, 12, theta);
+ _mav_put_float(buf, 16, omega);
+ _mav_put_float(buf, 20, sigma);
+ _mav_put_float(buf, 24, theta_dot);
+ _mav_put_float(buf, 28, omega_dot);
+ _mav_put_float(buf, 32, sigma_dot);
+ _mav_put_float(buf, 36, f);
+ _mav_put_float(buf, 40, f_dot);
+ _mav_put_float(buf, 44, u);
+ _mav_put_uint8_t(buf, 48, axis);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ADAP_TUNING_LEN);
+#else
+ mavlink_adap_tuning_t packet;
+ packet.desired = desired;
+ packet.achieved = achieved;
+ packet.error = error;
+ packet.theta = theta;
+ packet.omega = omega;
+ packet.sigma = sigma;
+ packet.theta_dot = theta_dot;
+ packet.omega_dot = omega_dot;
+ packet.sigma_dot = sigma_dot;
+ packet.f = f;
+ packet.f_dot = f_dot;
+ packet.u = u;
+ packet.axis = axis;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ADAP_TUNING_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_ADAP_TUNING;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ADAP_TUNING_MIN_LEN, MAVLINK_MSG_ID_ADAP_TUNING_LEN, MAVLINK_MSG_ID_ADAP_TUNING_CRC);
+}
+
+/**
+ * @brief Encode a adap_tuning 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 adap_tuning C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_adap_tuning_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_adap_tuning_t* adap_tuning)
+{
+ return mavlink_msg_adap_tuning_pack(system_id, component_id, msg, adap_tuning->axis, adap_tuning->desired, adap_tuning->achieved, adap_tuning->error, adap_tuning->theta, adap_tuning->omega, adap_tuning->sigma, adap_tuning->theta_dot, adap_tuning->omega_dot, adap_tuning->sigma_dot, adap_tuning->f, adap_tuning->f_dot, adap_tuning->u);
+}
+
+/**
+ * @brief Encode a adap_tuning 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 adap_tuning C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_adap_tuning_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_adap_tuning_t* adap_tuning)
+{
+ return mavlink_msg_adap_tuning_pack_chan(system_id, component_id, chan, msg, adap_tuning->axis, adap_tuning->desired, adap_tuning->achieved, adap_tuning->error, adap_tuning->theta, adap_tuning->omega, adap_tuning->sigma, adap_tuning->theta_dot, adap_tuning->omega_dot, adap_tuning->sigma_dot, adap_tuning->f, adap_tuning->f_dot, adap_tuning->u);
+}
+
+/**
+ * @brief Encode a adap_tuning 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 adap_tuning C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_adap_tuning_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_adap_tuning_t* adap_tuning)
+{
+ return mavlink_msg_adap_tuning_pack_status(system_id, component_id, _status, msg, adap_tuning->axis, adap_tuning->desired, adap_tuning->achieved, adap_tuning->error, adap_tuning->theta, adap_tuning->omega, adap_tuning->sigma, adap_tuning->theta_dot, adap_tuning->omega_dot, adap_tuning->sigma_dot, adap_tuning->f, adap_tuning->f_dot, adap_tuning->u);
+}
+
+/**
+ * @brief Send a adap_tuning message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param axis Axis.
+ * @param desired [deg/s] Desired rate.
+ * @param achieved [deg/s] Achieved rate.
+ * @param error Error between model and vehicle.
+ * @param theta Theta estimated state predictor.
+ * @param omega Omega estimated state predictor.
+ * @param sigma Sigma estimated state predictor.
+ * @param theta_dot Theta derivative.
+ * @param omega_dot Omega derivative.
+ * @param sigma_dot Sigma derivative.
+ * @param f Projection operator value.
+ * @param f_dot Projection operator derivative.
+ * @param u u adaptive controlled output command.
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_adap_tuning_send(mavlink_channel_t chan, uint8_t axis, float desired, float achieved, float error, float theta, float omega, float sigma, float theta_dot, float omega_dot, float sigma_dot, float f, float f_dot, float u)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_ADAP_TUNING_LEN];
+ _mav_put_float(buf, 0, desired);
+ _mav_put_float(buf, 4, achieved);
+ _mav_put_float(buf, 8, error);
+ _mav_put_float(buf, 12, theta);
+ _mav_put_float(buf, 16, omega);
+ _mav_put_float(buf, 20, sigma);
+ _mav_put_float(buf, 24, theta_dot);
+ _mav_put_float(buf, 28, omega_dot);
+ _mav_put_float(buf, 32, sigma_dot);
+ _mav_put_float(buf, 36, f);
+ _mav_put_float(buf, 40, f_dot);
+ _mav_put_float(buf, 44, u);
+ _mav_put_uint8_t(buf, 48, axis);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADAP_TUNING, buf, MAVLINK_MSG_ID_ADAP_TUNING_MIN_LEN, MAVLINK_MSG_ID_ADAP_TUNING_LEN, MAVLINK_MSG_ID_ADAP_TUNING_CRC);
+#else
+ mavlink_adap_tuning_t packet;
+ packet.desired = desired;
+ packet.achieved = achieved;
+ packet.error = error;
+ packet.theta = theta;
+ packet.omega = omega;
+ packet.sigma = sigma;
+ packet.theta_dot = theta_dot;
+ packet.omega_dot = omega_dot;
+ packet.sigma_dot = sigma_dot;
+ packet.f = f;
+ packet.f_dot = f_dot;
+ packet.u = u;
+ packet.axis = axis;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADAP_TUNING, (const char *)&packet, MAVLINK_MSG_ID_ADAP_TUNING_MIN_LEN, MAVLINK_MSG_ID_ADAP_TUNING_LEN, MAVLINK_MSG_ID_ADAP_TUNING_CRC);
+#endif
+}
+
+/**
+ * @brief Send a adap_tuning message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_adap_tuning_send_struct(mavlink_channel_t chan, const mavlink_adap_tuning_t* adap_tuning)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_adap_tuning_send(chan, adap_tuning->axis, adap_tuning->desired, adap_tuning->achieved, adap_tuning->error, adap_tuning->theta, adap_tuning->omega, adap_tuning->sigma, adap_tuning->theta_dot, adap_tuning->omega_dot, adap_tuning->sigma_dot, adap_tuning->f, adap_tuning->f_dot, adap_tuning->u);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADAP_TUNING, (const char *)adap_tuning, MAVLINK_MSG_ID_ADAP_TUNING_MIN_LEN, MAVLINK_MSG_ID_ADAP_TUNING_LEN, MAVLINK_MSG_ID_ADAP_TUNING_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_ADAP_TUNING_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_adap_tuning_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t axis, float desired, float achieved, float error, float theta, float omega, float sigma, float theta_dot, float omega_dot, float sigma_dot, float f, float f_dot, float u)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_float(buf, 0, desired);
+ _mav_put_float(buf, 4, achieved);
+ _mav_put_float(buf, 8, error);
+ _mav_put_float(buf, 12, theta);
+ _mav_put_float(buf, 16, omega);
+ _mav_put_float(buf, 20, sigma);
+ _mav_put_float(buf, 24, theta_dot);
+ _mav_put_float(buf, 28, omega_dot);
+ _mav_put_float(buf, 32, sigma_dot);
+ _mav_put_float(buf, 36, f);
+ _mav_put_float(buf, 40, f_dot);
+ _mav_put_float(buf, 44, u);
+ _mav_put_uint8_t(buf, 48, axis);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADAP_TUNING, buf, MAVLINK_MSG_ID_ADAP_TUNING_MIN_LEN, MAVLINK_MSG_ID_ADAP_TUNING_LEN, MAVLINK_MSG_ID_ADAP_TUNING_CRC);
+#else
+ mavlink_adap_tuning_t *packet = (mavlink_adap_tuning_t *)msgbuf;
+ packet->desired = desired;
+ packet->achieved = achieved;
+ packet->error = error;
+ packet->theta = theta;
+ packet->omega = omega;
+ packet->sigma = sigma;
+ packet->theta_dot = theta_dot;
+ packet->omega_dot = omega_dot;
+ packet->sigma_dot = sigma_dot;
+ packet->f = f;
+ packet->f_dot = f_dot;
+ packet->u = u;
+ packet->axis = axis;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADAP_TUNING, (const char *)packet, MAVLINK_MSG_ID_ADAP_TUNING_MIN_LEN, MAVLINK_MSG_ID_ADAP_TUNING_LEN, MAVLINK_MSG_ID_ADAP_TUNING_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE ADAP_TUNING UNPACKING
+
+
+/**
+ * @brief Get field axis from adap_tuning message
+ *
+ * @return Axis.
+ */
+static inline uint8_t mavlink_msg_adap_tuning_get_axis(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 48);
+}
+
+/**
+ * @brief Get field desired from adap_tuning message
+ *
+ * @return [deg/s] Desired rate.
+ */
+static inline float mavlink_msg_adap_tuning_get_desired(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 0);
+}
+
+/**
+ * @brief Get field achieved from adap_tuning message
+ *
+ * @return [deg/s] Achieved rate.
+ */
+static inline float mavlink_msg_adap_tuning_get_achieved(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 4);
+}
+
+/**
+ * @brief Get field error from adap_tuning message
+ *
+ * @return Error between model and vehicle.
+ */
+static inline float mavlink_msg_adap_tuning_get_error(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 8);
+}
+
+/**
+ * @brief Get field theta from adap_tuning message
+ *
+ * @return Theta estimated state predictor.
+ */
+static inline float mavlink_msg_adap_tuning_get_theta(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 12);
+}
+
+/**
+ * @brief Get field omega from adap_tuning message
+ *
+ * @return Omega estimated state predictor.
+ */
+static inline float mavlink_msg_adap_tuning_get_omega(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 16);
+}
+
+/**
+ * @brief Get field sigma from adap_tuning message
+ *
+ * @return Sigma estimated state predictor.
+ */
+static inline float mavlink_msg_adap_tuning_get_sigma(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 20);
+}
+
+/**
+ * @brief Get field theta_dot from adap_tuning message
+ *
+ * @return Theta derivative.
+ */
+static inline float mavlink_msg_adap_tuning_get_theta_dot(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 24);
+}
+
+/**
+ * @brief Get field omega_dot from adap_tuning message
+ *
+ * @return Omega derivative.
+ */
+static inline float mavlink_msg_adap_tuning_get_omega_dot(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 28);
+}
+
+/**
+ * @brief Get field sigma_dot from adap_tuning message
+ *
+ * @return Sigma derivative.
+ */
+static inline float mavlink_msg_adap_tuning_get_sigma_dot(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 32);
+}
+
+/**
+ * @brief Get field f from adap_tuning message
+ *
+ * @return Projection operator value.
+ */
+static inline float mavlink_msg_adap_tuning_get_f(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 36);
+}
+
+/**
+ * @brief Get field f_dot from adap_tuning message
+ *
+ * @return Projection operator derivative.
+ */
+static inline float mavlink_msg_adap_tuning_get_f_dot(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 40);
+}
+
+/**
+ * @brief Get field u from adap_tuning message
+ *
+ * @return u adaptive controlled output command.
+ */
+static inline float mavlink_msg_adap_tuning_get_u(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 44);
+}
+
+/**
+ * @brief Decode a adap_tuning message into a struct
+ *
+ * @param msg The message to decode
+ * @param adap_tuning C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_adap_tuning_decode(const mavlink_message_t* msg, mavlink_adap_tuning_t* adap_tuning)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ adap_tuning->desired = mavlink_msg_adap_tuning_get_desired(msg);
+ adap_tuning->achieved = mavlink_msg_adap_tuning_get_achieved(msg);
+ adap_tuning->error = mavlink_msg_adap_tuning_get_error(msg);
+ adap_tuning->theta = mavlink_msg_adap_tuning_get_theta(msg);
+ adap_tuning->omega = mavlink_msg_adap_tuning_get_omega(msg);
+ adap_tuning->sigma = mavlink_msg_adap_tuning_get_sigma(msg);
+ adap_tuning->theta_dot = mavlink_msg_adap_tuning_get_theta_dot(msg);
+ adap_tuning->omega_dot = mavlink_msg_adap_tuning_get_omega_dot(msg);
+ adap_tuning->sigma_dot = mavlink_msg_adap_tuning_get_sigma_dot(msg);
+ adap_tuning->f = mavlink_msg_adap_tuning_get_f(msg);
+ adap_tuning->f_dot = mavlink_msg_adap_tuning_get_f_dot(msg);
+ adap_tuning->u = mavlink_msg_adap_tuning_get_u(msg);
+ adap_tuning->axis = mavlink_msg_adap_tuning_get_axis(msg);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_ADAP_TUNING_LEN? msg->len : MAVLINK_MSG_ID_ADAP_TUNING_LEN;
+ memset(adap_tuning, 0, MAVLINK_MSG_ID_ADAP_TUNING_LEN);
+ memcpy(adap_tuning, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/ardupilotmega/mavlink_msg_ahrs.h b/lib/main/MAVLink/ardupilotmega/mavlink_msg_ahrs.h
new file mode 100644
index 00000000000..66df7064a4e
--- /dev/null
+++ b/lib/main/MAVLink/ardupilotmega/mavlink_msg_ahrs.h
@@ -0,0 +1,428 @@
+#pragma once
+// MESSAGE AHRS PACKING
+
+#define MAVLINK_MSG_ID_AHRS 163
+
+
+typedef struct __mavlink_ahrs_t {
+ float omegaIx; /*< [rad/s] X gyro drift estimate.*/
+ float omegaIy; /*< [rad/s] Y gyro drift estimate.*/
+ float omegaIz; /*< [rad/s] Z gyro drift estimate.*/
+ float accel_weight; /*< Average accel_weight.*/
+ float renorm_val; /*< Average renormalisation value.*/
+ float error_rp; /*< Average error_roll_pitch value.*/
+ float error_yaw; /*< Average error_yaw value.*/
+} mavlink_ahrs_t;
+
+#define MAVLINK_MSG_ID_AHRS_LEN 28
+#define MAVLINK_MSG_ID_AHRS_MIN_LEN 28
+#define MAVLINK_MSG_ID_163_LEN 28
+#define MAVLINK_MSG_ID_163_MIN_LEN 28
+
+#define MAVLINK_MSG_ID_AHRS_CRC 127
+#define MAVLINK_MSG_ID_163_CRC 127
+
+
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_AHRS { \
+ 163, \
+ "AHRS", \
+ 7, \
+ { { "omegaIx", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_ahrs_t, omegaIx) }, \
+ { "omegaIy", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_ahrs_t, omegaIy) }, \
+ { "omegaIz", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_ahrs_t, omegaIz) }, \
+ { "accel_weight", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_ahrs_t, accel_weight) }, \
+ { "renorm_val", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_ahrs_t, renorm_val) }, \
+ { "error_rp", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_ahrs_t, error_rp) }, \
+ { "error_yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_ahrs_t, error_yaw) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_AHRS { \
+ "AHRS", \
+ 7, \
+ { { "omegaIx", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_ahrs_t, omegaIx) }, \
+ { "omegaIy", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_ahrs_t, omegaIy) }, \
+ { "omegaIz", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_ahrs_t, omegaIz) }, \
+ { "accel_weight", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_ahrs_t, accel_weight) }, \
+ { "renorm_val", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_ahrs_t, renorm_val) }, \
+ { "error_rp", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_ahrs_t, error_rp) }, \
+ { "error_yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_ahrs_t, error_yaw) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a ahrs 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 omegaIx [rad/s] X gyro drift estimate.
+ * @param omegaIy [rad/s] Y gyro drift estimate.
+ * @param omegaIz [rad/s] Z gyro drift estimate.
+ * @param accel_weight Average accel_weight.
+ * @param renorm_val Average renormalisation value.
+ * @param error_rp Average error_roll_pitch value.
+ * @param error_yaw Average error_yaw value.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_ahrs_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ float omegaIx, float omegaIy, float omegaIz, float accel_weight, float renorm_val, float error_rp, float error_yaw)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_AHRS_LEN];
+ _mav_put_float(buf, 0, omegaIx);
+ _mav_put_float(buf, 4, omegaIy);
+ _mav_put_float(buf, 8, omegaIz);
+ _mav_put_float(buf, 12, accel_weight);
+ _mav_put_float(buf, 16, renorm_val);
+ _mav_put_float(buf, 20, error_rp);
+ _mav_put_float(buf, 24, error_yaw);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AHRS_LEN);
+#else
+ mavlink_ahrs_t packet;
+ packet.omegaIx = omegaIx;
+ packet.omegaIy = omegaIy;
+ packet.omegaIz = omegaIz;
+ packet.accel_weight = accel_weight;
+ packet.renorm_val = renorm_val;
+ packet.error_rp = error_rp;
+ packet.error_yaw = error_yaw;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AHRS_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_AHRS;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_AHRS_MIN_LEN, MAVLINK_MSG_ID_AHRS_LEN, MAVLINK_MSG_ID_AHRS_CRC);
+}
+
+/**
+ * @brief Pack a ahrs 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 omegaIx [rad/s] X gyro drift estimate.
+ * @param omegaIy [rad/s] Y gyro drift estimate.
+ * @param omegaIz [rad/s] Z gyro drift estimate.
+ * @param accel_weight Average accel_weight.
+ * @param renorm_val Average renormalisation value.
+ * @param error_rp Average error_roll_pitch value.
+ * @param error_yaw Average error_yaw value.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_ahrs_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ float omegaIx, float omegaIy, float omegaIz, float accel_weight, float renorm_val, float error_rp, float error_yaw)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_AHRS_LEN];
+ _mav_put_float(buf, 0, omegaIx);
+ _mav_put_float(buf, 4, omegaIy);
+ _mav_put_float(buf, 8, omegaIz);
+ _mav_put_float(buf, 12, accel_weight);
+ _mav_put_float(buf, 16, renorm_val);
+ _mav_put_float(buf, 20, error_rp);
+ _mav_put_float(buf, 24, error_yaw);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AHRS_LEN);
+#else
+ mavlink_ahrs_t packet;
+ packet.omegaIx = omegaIx;
+ packet.omegaIy = omegaIy;
+ packet.omegaIz = omegaIz;
+ packet.accel_weight = accel_weight;
+ packet.renorm_val = renorm_val;
+ packet.error_rp = error_rp;
+ packet.error_yaw = error_yaw;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AHRS_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_AHRS;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_AHRS_MIN_LEN, MAVLINK_MSG_ID_AHRS_LEN, MAVLINK_MSG_ID_AHRS_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_AHRS_MIN_LEN, MAVLINK_MSG_ID_AHRS_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a ahrs 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 omegaIx [rad/s] X gyro drift estimate.
+ * @param omegaIy [rad/s] Y gyro drift estimate.
+ * @param omegaIz [rad/s] Z gyro drift estimate.
+ * @param accel_weight Average accel_weight.
+ * @param renorm_val Average renormalisation value.
+ * @param error_rp Average error_roll_pitch value.
+ * @param error_yaw Average error_yaw value.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_ahrs_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ float omegaIx,float omegaIy,float omegaIz,float accel_weight,float renorm_val,float error_rp,float error_yaw)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_AHRS_LEN];
+ _mav_put_float(buf, 0, omegaIx);
+ _mav_put_float(buf, 4, omegaIy);
+ _mav_put_float(buf, 8, omegaIz);
+ _mav_put_float(buf, 12, accel_weight);
+ _mav_put_float(buf, 16, renorm_val);
+ _mav_put_float(buf, 20, error_rp);
+ _mav_put_float(buf, 24, error_yaw);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AHRS_LEN);
+#else
+ mavlink_ahrs_t packet;
+ packet.omegaIx = omegaIx;
+ packet.omegaIy = omegaIy;
+ packet.omegaIz = omegaIz;
+ packet.accel_weight = accel_weight;
+ packet.renorm_val = renorm_val;
+ packet.error_rp = error_rp;
+ packet.error_yaw = error_yaw;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AHRS_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_AHRS;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_AHRS_MIN_LEN, MAVLINK_MSG_ID_AHRS_LEN, MAVLINK_MSG_ID_AHRS_CRC);
+}
+
+/**
+ * @brief Encode a ahrs 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 ahrs C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_ahrs_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_ahrs_t* ahrs)
+{
+ return mavlink_msg_ahrs_pack(system_id, component_id, msg, ahrs->omegaIx, ahrs->omegaIy, ahrs->omegaIz, ahrs->accel_weight, ahrs->renorm_val, ahrs->error_rp, ahrs->error_yaw);
+}
+
+/**
+ * @brief Encode a ahrs 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 ahrs C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_ahrs_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_ahrs_t* ahrs)
+{
+ return mavlink_msg_ahrs_pack_chan(system_id, component_id, chan, msg, ahrs->omegaIx, ahrs->omegaIy, ahrs->omegaIz, ahrs->accel_weight, ahrs->renorm_val, ahrs->error_rp, ahrs->error_yaw);
+}
+
+/**
+ * @brief Encode a ahrs 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 ahrs C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_ahrs_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_ahrs_t* ahrs)
+{
+ return mavlink_msg_ahrs_pack_status(system_id, component_id, _status, msg, ahrs->omegaIx, ahrs->omegaIy, ahrs->omegaIz, ahrs->accel_weight, ahrs->renorm_val, ahrs->error_rp, ahrs->error_yaw);
+}
+
+/**
+ * @brief Send a ahrs message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param omegaIx [rad/s] X gyro drift estimate.
+ * @param omegaIy [rad/s] Y gyro drift estimate.
+ * @param omegaIz [rad/s] Z gyro drift estimate.
+ * @param accel_weight Average accel_weight.
+ * @param renorm_val Average renormalisation value.
+ * @param error_rp Average error_roll_pitch value.
+ * @param error_yaw Average error_yaw value.
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_ahrs_send(mavlink_channel_t chan, float omegaIx, float omegaIy, float omegaIz, float accel_weight, float renorm_val, float error_rp, float error_yaw)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_AHRS_LEN];
+ _mav_put_float(buf, 0, omegaIx);
+ _mav_put_float(buf, 4, omegaIy);
+ _mav_put_float(buf, 8, omegaIz);
+ _mav_put_float(buf, 12, accel_weight);
+ _mav_put_float(buf, 16, renorm_val);
+ _mav_put_float(buf, 20, error_rp);
+ _mav_put_float(buf, 24, error_yaw);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AHRS, buf, MAVLINK_MSG_ID_AHRS_MIN_LEN, MAVLINK_MSG_ID_AHRS_LEN, MAVLINK_MSG_ID_AHRS_CRC);
+#else
+ mavlink_ahrs_t packet;
+ packet.omegaIx = omegaIx;
+ packet.omegaIy = omegaIy;
+ packet.omegaIz = omegaIz;
+ packet.accel_weight = accel_weight;
+ packet.renorm_val = renorm_val;
+ packet.error_rp = error_rp;
+ packet.error_yaw = error_yaw;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AHRS, (const char *)&packet, MAVLINK_MSG_ID_AHRS_MIN_LEN, MAVLINK_MSG_ID_AHRS_LEN, MAVLINK_MSG_ID_AHRS_CRC);
+#endif
+}
+
+/**
+ * @brief Send a ahrs message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_ahrs_send_struct(mavlink_channel_t chan, const mavlink_ahrs_t* ahrs)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_ahrs_send(chan, ahrs->omegaIx, ahrs->omegaIy, ahrs->omegaIz, ahrs->accel_weight, ahrs->renorm_val, ahrs->error_rp, ahrs->error_yaw);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AHRS, (const char *)ahrs, MAVLINK_MSG_ID_AHRS_MIN_LEN, MAVLINK_MSG_ID_AHRS_LEN, MAVLINK_MSG_ID_AHRS_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_AHRS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_ahrs_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float omegaIx, float omegaIy, float omegaIz, float accel_weight, float renorm_val, float error_rp, float error_yaw)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_float(buf, 0, omegaIx);
+ _mav_put_float(buf, 4, omegaIy);
+ _mav_put_float(buf, 8, omegaIz);
+ _mav_put_float(buf, 12, accel_weight);
+ _mav_put_float(buf, 16, renorm_val);
+ _mav_put_float(buf, 20, error_rp);
+ _mav_put_float(buf, 24, error_yaw);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AHRS, buf, MAVLINK_MSG_ID_AHRS_MIN_LEN, MAVLINK_MSG_ID_AHRS_LEN, MAVLINK_MSG_ID_AHRS_CRC);
+#else
+ mavlink_ahrs_t *packet = (mavlink_ahrs_t *)msgbuf;
+ packet->omegaIx = omegaIx;
+ packet->omegaIy = omegaIy;
+ packet->omegaIz = omegaIz;
+ packet->accel_weight = accel_weight;
+ packet->renorm_val = renorm_val;
+ packet->error_rp = error_rp;
+ packet->error_yaw = error_yaw;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AHRS, (const char *)packet, MAVLINK_MSG_ID_AHRS_MIN_LEN, MAVLINK_MSG_ID_AHRS_LEN, MAVLINK_MSG_ID_AHRS_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE AHRS UNPACKING
+
+
+/**
+ * @brief Get field omegaIx from ahrs message
+ *
+ * @return [rad/s] X gyro drift estimate.
+ */
+static inline float mavlink_msg_ahrs_get_omegaIx(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 0);
+}
+
+/**
+ * @brief Get field omegaIy from ahrs message
+ *
+ * @return [rad/s] Y gyro drift estimate.
+ */
+static inline float mavlink_msg_ahrs_get_omegaIy(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 4);
+}
+
+/**
+ * @brief Get field omegaIz from ahrs message
+ *
+ * @return [rad/s] Z gyro drift estimate.
+ */
+static inline float mavlink_msg_ahrs_get_omegaIz(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 8);
+}
+
+/**
+ * @brief Get field accel_weight from ahrs message
+ *
+ * @return Average accel_weight.
+ */
+static inline float mavlink_msg_ahrs_get_accel_weight(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 12);
+}
+
+/**
+ * @brief Get field renorm_val from ahrs message
+ *
+ * @return Average renormalisation value.
+ */
+static inline float mavlink_msg_ahrs_get_renorm_val(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 16);
+}
+
+/**
+ * @brief Get field error_rp from ahrs message
+ *
+ * @return Average error_roll_pitch value.
+ */
+static inline float mavlink_msg_ahrs_get_error_rp(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 20);
+}
+
+/**
+ * @brief Get field error_yaw from ahrs message
+ *
+ * @return Average error_yaw value.
+ */
+static inline float mavlink_msg_ahrs_get_error_yaw(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 24);
+}
+
+/**
+ * @brief Decode a ahrs message into a struct
+ *
+ * @param msg The message to decode
+ * @param ahrs C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_ahrs_decode(const mavlink_message_t* msg, mavlink_ahrs_t* ahrs)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ ahrs->omegaIx = mavlink_msg_ahrs_get_omegaIx(msg);
+ ahrs->omegaIy = mavlink_msg_ahrs_get_omegaIy(msg);
+ ahrs->omegaIz = mavlink_msg_ahrs_get_omegaIz(msg);
+ ahrs->accel_weight = mavlink_msg_ahrs_get_accel_weight(msg);
+ ahrs->renorm_val = mavlink_msg_ahrs_get_renorm_val(msg);
+ ahrs->error_rp = mavlink_msg_ahrs_get_error_rp(msg);
+ ahrs->error_yaw = mavlink_msg_ahrs_get_error_yaw(msg);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_AHRS_LEN? msg->len : MAVLINK_MSG_ID_AHRS_LEN;
+ memset(ahrs, 0, MAVLINK_MSG_ID_AHRS_LEN);
+ memcpy(ahrs, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/ardupilotmega/mavlink_msg_ahrs2.h b/lib/main/MAVLink/ardupilotmega/mavlink_msg_ahrs2.h
new file mode 100644
index 00000000000..699cee633b9
--- /dev/null
+++ b/lib/main/MAVLink/ardupilotmega/mavlink_msg_ahrs2.h
@@ -0,0 +1,400 @@
+#pragma once
+// MESSAGE AHRS2 PACKING
+
+#define MAVLINK_MSG_ID_AHRS2 178
+
+
+typedef struct __mavlink_ahrs2_t {
+ float roll; /*< [rad] Roll angle.*/
+ float pitch; /*< [rad] Pitch angle.*/
+ float yaw; /*< [rad] Yaw angle.*/
+ float altitude; /*< [m] Altitude (MSL).*/
+ int32_t lat; /*< [degE7] Latitude.*/
+ int32_t lng; /*< [degE7] Longitude.*/
+} mavlink_ahrs2_t;
+
+#define MAVLINK_MSG_ID_AHRS2_LEN 24
+#define MAVLINK_MSG_ID_AHRS2_MIN_LEN 24
+#define MAVLINK_MSG_ID_178_LEN 24
+#define MAVLINK_MSG_ID_178_MIN_LEN 24
+
+#define MAVLINK_MSG_ID_AHRS2_CRC 47
+#define MAVLINK_MSG_ID_178_CRC 47
+
+
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_AHRS2 { \
+ 178, \
+ "AHRS2", \
+ 6, \
+ { { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_ahrs2_t, roll) }, \
+ { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_ahrs2_t, pitch) }, \
+ { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_ahrs2_t, yaw) }, \
+ { "altitude", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_ahrs2_t, altitude) }, \
+ { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_ahrs2_t, lat) }, \
+ { "lng", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_ahrs2_t, lng) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_AHRS2 { \
+ "AHRS2", \
+ 6, \
+ { { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_ahrs2_t, roll) }, \
+ { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_ahrs2_t, pitch) }, \
+ { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_ahrs2_t, yaw) }, \
+ { "altitude", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_ahrs2_t, altitude) }, \
+ { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_ahrs2_t, lat) }, \
+ { "lng", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_ahrs2_t, lng) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a ahrs2 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 roll [rad] Roll angle.
+ * @param pitch [rad] Pitch angle.
+ * @param yaw [rad] Yaw angle.
+ * @param altitude [m] Altitude (MSL).
+ * @param lat [degE7] Latitude.
+ * @param lng [degE7] Longitude.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_ahrs2_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ float roll, float pitch, float yaw, float altitude, int32_t lat, int32_t lng)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_AHRS2_LEN];
+ _mav_put_float(buf, 0, roll);
+ _mav_put_float(buf, 4, pitch);
+ _mav_put_float(buf, 8, yaw);
+ _mav_put_float(buf, 12, altitude);
+ _mav_put_int32_t(buf, 16, lat);
+ _mav_put_int32_t(buf, 20, lng);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AHRS2_LEN);
+#else
+ mavlink_ahrs2_t packet;
+ packet.roll = roll;
+ packet.pitch = pitch;
+ packet.yaw = yaw;
+ packet.altitude = altitude;
+ packet.lat = lat;
+ packet.lng = lng;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AHRS2_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_AHRS2;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_AHRS2_MIN_LEN, MAVLINK_MSG_ID_AHRS2_LEN, MAVLINK_MSG_ID_AHRS2_CRC);
+}
+
+/**
+ * @brief Pack a ahrs2 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 roll [rad] Roll angle.
+ * @param pitch [rad] Pitch angle.
+ * @param yaw [rad] Yaw angle.
+ * @param altitude [m] Altitude (MSL).
+ * @param lat [degE7] Latitude.
+ * @param lng [degE7] Longitude.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_ahrs2_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ float roll, float pitch, float yaw, float altitude, int32_t lat, int32_t lng)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_AHRS2_LEN];
+ _mav_put_float(buf, 0, roll);
+ _mav_put_float(buf, 4, pitch);
+ _mav_put_float(buf, 8, yaw);
+ _mav_put_float(buf, 12, altitude);
+ _mav_put_int32_t(buf, 16, lat);
+ _mav_put_int32_t(buf, 20, lng);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AHRS2_LEN);
+#else
+ mavlink_ahrs2_t packet;
+ packet.roll = roll;
+ packet.pitch = pitch;
+ packet.yaw = yaw;
+ packet.altitude = altitude;
+ packet.lat = lat;
+ packet.lng = lng;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AHRS2_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_AHRS2;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_AHRS2_MIN_LEN, MAVLINK_MSG_ID_AHRS2_LEN, MAVLINK_MSG_ID_AHRS2_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_AHRS2_MIN_LEN, MAVLINK_MSG_ID_AHRS2_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a ahrs2 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 roll [rad] Roll angle.
+ * @param pitch [rad] Pitch angle.
+ * @param yaw [rad] Yaw angle.
+ * @param altitude [m] Altitude (MSL).
+ * @param lat [degE7] Latitude.
+ * @param lng [degE7] Longitude.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_ahrs2_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ float roll,float pitch,float yaw,float altitude,int32_t lat,int32_t lng)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_AHRS2_LEN];
+ _mav_put_float(buf, 0, roll);
+ _mav_put_float(buf, 4, pitch);
+ _mav_put_float(buf, 8, yaw);
+ _mav_put_float(buf, 12, altitude);
+ _mav_put_int32_t(buf, 16, lat);
+ _mav_put_int32_t(buf, 20, lng);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AHRS2_LEN);
+#else
+ mavlink_ahrs2_t packet;
+ packet.roll = roll;
+ packet.pitch = pitch;
+ packet.yaw = yaw;
+ packet.altitude = altitude;
+ packet.lat = lat;
+ packet.lng = lng;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AHRS2_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_AHRS2;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_AHRS2_MIN_LEN, MAVLINK_MSG_ID_AHRS2_LEN, MAVLINK_MSG_ID_AHRS2_CRC);
+}
+
+/**
+ * @brief Encode a ahrs2 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 ahrs2 C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_ahrs2_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_ahrs2_t* ahrs2)
+{
+ return mavlink_msg_ahrs2_pack(system_id, component_id, msg, ahrs2->roll, ahrs2->pitch, ahrs2->yaw, ahrs2->altitude, ahrs2->lat, ahrs2->lng);
+}
+
+/**
+ * @brief Encode a ahrs2 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 ahrs2 C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_ahrs2_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_ahrs2_t* ahrs2)
+{
+ return mavlink_msg_ahrs2_pack_chan(system_id, component_id, chan, msg, ahrs2->roll, ahrs2->pitch, ahrs2->yaw, ahrs2->altitude, ahrs2->lat, ahrs2->lng);
+}
+
+/**
+ * @brief Encode a ahrs2 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 ahrs2 C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_ahrs2_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_ahrs2_t* ahrs2)
+{
+ return mavlink_msg_ahrs2_pack_status(system_id, component_id, _status, msg, ahrs2->roll, ahrs2->pitch, ahrs2->yaw, ahrs2->altitude, ahrs2->lat, ahrs2->lng);
+}
+
+/**
+ * @brief Send a ahrs2 message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param roll [rad] Roll angle.
+ * @param pitch [rad] Pitch angle.
+ * @param yaw [rad] Yaw angle.
+ * @param altitude [m] Altitude (MSL).
+ * @param lat [degE7] Latitude.
+ * @param lng [degE7] Longitude.
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_ahrs2_send(mavlink_channel_t chan, float roll, float pitch, float yaw, float altitude, int32_t lat, int32_t lng)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_AHRS2_LEN];
+ _mav_put_float(buf, 0, roll);
+ _mav_put_float(buf, 4, pitch);
+ _mav_put_float(buf, 8, yaw);
+ _mav_put_float(buf, 12, altitude);
+ _mav_put_int32_t(buf, 16, lat);
+ _mav_put_int32_t(buf, 20, lng);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AHRS2, buf, MAVLINK_MSG_ID_AHRS2_MIN_LEN, MAVLINK_MSG_ID_AHRS2_LEN, MAVLINK_MSG_ID_AHRS2_CRC);
+#else
+ mavlink_ahrs2_t packet;
+ packet.roll = roll;
+ packet.pitch = pitch;
+ packet.yaw = yaw;
+ packet.altitude = altitude;
+ packet.lat = lat;
+ packet.lng = lng;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AHRS2, (const char *)&packet, MAVLINK_MSG_ID_AHRS2_MIN_LEN, MAVLINK_MSG_ID_AHRS2_LEN, MAVLINK_MSG_ID_AHRS2_CRC);
+#endif
+}
+
+/**
+ * @brief Send a ahrs2 message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_ahrs2_send_struct(mavlink_channel_t chan, const mavlink_ahrs2_t* ahrs2)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_ahrs2_send(chan, ahrs2->roll, ahrs2->pitch, ahrs2->yaw, ahrs2->altitude, ahrs2->lat, ahrs2->lng);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AHRS2, (const char *)ahrs2, MAVLINK_MSG_ID_AHRS2_MIN_LEN, MAVLINK_MSG_ID_AHRS2_LEN, MAVLINK_MSG_ID_AHRS2_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_AHRS2_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_ahrs2_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float roll, float pitch, float yaw, float altitude, int32_t lat, int32_t lng)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_float(buf, 0, roll);
+ _mav_put_float(buf, 4, pitch);
+ _mav_put_float(buf, 8, yaw);
+ _mav_put_float(buf, 12, altitude);
+ _mav_put_int32_t(buf, 16, lat);
+ _mav_put_int32_t(buf, 20, lng);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AHRS2, buf, MAVLINK_MSG_ID_AHRS2_MIN_LEN, MAVLINK_MSG_ID_AHRS2_LEN, MAVLINK_MSG_ID_AHRS2_CRC);
+#else
+ mavlink_ahrs2_t *packet = (mavlink_ahrs2_t *)msgbuf;
+ packet->roll = roll;
+ packet->pitch = pitch;
+ packet->yaw = yaw;
+ packet->altitude = altitude;
+ packet->lat = lat;
+ packet->lng = lng;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AHRS2, (const char *)packet, MAVLINK_MSG_ID_AHRS2_MIN_LEN, MAVLINK_MSG_ID_AHRS2_LEN, MAVLINK_MSG_ID_AHRS2_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE AHRS2 UNPACKING
+
+
+/**
+ * @brief Get field roll from ahrs2 message
+ *
+ * @return [rad] Roll angle.
+ */
+static inline float mavlink_msg_ahrs2_get_roll(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 0);
+}
+
+/**
+ * @brief Get field pitch from ahrs2 message
+ *
+ * @return [rad] Pitch angle.
+ */
+static inline float mavlink_msg_ahrs2_get_pitch(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 4);
+}
+
+/**
+ * @brief Get field yaw from ahrs2 message
+ *
+ * @return [rad] Yaw angle.
+ */
+static inline float mavlink_msg_ahrs2_get_yaw(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 8);
+}
+
+/**
+ * @brief Get field altitude from ahrs2 message
+ *
+ * @return [m] Altitude (MSL).
+ */
+static inline float mavlink_msg_ahrs2_get_altitude(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 12);
+}
+
+/**
+ * @brief Get field lat from ahrs2 message
+ *
+ * @return [degE7] Latitude.
+ */
+static inline int32_t mavlink_msg_ahrs2_get_lat(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_int32_t(msg, 16);
+}
+
+/**
+ * @brief Get field lng from ahrs2 message
+ *
+ * @return [degE7] Longitude.
+ */
+static inline int32_t mavlink_msg_ahrs2_get_lng(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_int32_t(msg, 20);
+}
+
+/**
+ * @brief Decode a ahrs2 message into a struct
+ *
+ * @param msg The message to decode
+ * @param ahrs2 C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_ahrs2_decode(const mavlink_message_t* msg, mavlink_ahrs2_t* ahrs2)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ ahrs2->roll = mavlink_msg_ahrs2_get_roll(msg);
+ ahrs2->pitch = mavlink_msg_ahrs2_get_pitch(msg);
+ ahrs2->yaw = mavlink_msg_ahrs2_get_yaw(msg);
+ ahrs2->altitude = mavlink_msg_ahrs2_get_altitude(msg);
+ ahrs2->lat = mavlink_msg_ahrs2_get_lat(msg);
+ ahrs2->lng = mavlink_msg_ahrs2_get_lng(msg);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_AHRS2_LEN? msg->len : MAVLINK_MSG_ID_AHRS2_LEN;
+ memset(ahrs2, 0, MAVLINK_MSG_ID_AHRS2_LEN);
+ memcpy(ahrs2, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/ardupilotmega/mavlink_msg_ahrs3.h b/lib/main/MAVLink/ardupilotmega/mavlink_msg_ahrs3.h
new file mode 100644
index 00000000000..bbbcee92a3c
--- /dev/null
+++ b/lib/main/MAVLink/ardupilotmega/mavlink_msg_ahrs3.h
@@ -0,0 +1,512 @@
+#pragma once
+// MESSAGE AHRS3 PACKING
+
+#define MAVLINK_MSG_ID_AHRS3 182
+
+
+typedef struct __mavlink_ahrs3_t {
+ float roll; /*< [rad] Roll angle.*/
+ float pitch; /*< [rad] Pitch angle.*/
+ float yaw; /*< [rad] Yaw angle.*/
+ float altitude; /*< [m] Altitude (MSL).*/
+ int32_t lat; /*< [degE7] Latitude.*/
+ int32_t lng; /*< [degE7] Longitude.*/
+ float v1; /*< Test variable1.*/
+ float v2; /*< Test variable2.*/
+ float v3; /*< Test variable3.*/
+ float v4; /*< Test variable4.*/
+} mavlink_ahrs3_t;
+
+#define MAVLINK_MSG_ID_AHRS3_LEN 40
+#define MAVLINK_MSG_ID_AHRS3_MIN_LEN 40
+#define MAVLINK_MSG_ID_182_LEN 40
+#define MAVLINK_MSG_ID_182_MIN_LEN 40
+
+#define MAVLINK_MSG_ID_AHRS3_CRC 229
+#define MAVLINK_MSG_ID_182_CRC 229
+
+
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_AHRS3 { \
+ 182, \
+ "AHRS3", \
+ 10, \
+ { { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_ahrs3_t, roll) }, \
+ { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_ahrs3_t, pitch) }, \
+ { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_ahrs3_t, yaw) }, \
+ { "altitude", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_ahrs3_t, altitude) }, \
+ { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_ahrs3_t, lat) }, \
+ { "lng", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_ahrs3_t, lng) }, \
+ { "v1", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_ahrs3_t, v1) }, \
+ { "v2", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_ahrs3_t, v2) }, \
+ { "v3", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_ahrs3_t, v3) }, \
+ { "v4", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_ahrs3_t, v4) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_AHRS3 { \
+ "AHRS3", \
+ 10, \
+ { { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_ahrs3_t, roll) }, \
+ { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_ahrs3_t, pitch) }, \
+ { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_ahrs3_t, yaw) }, \
+ { "altitude", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_ahrs3_t, altitude) }, \
+ { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_ahrs3_t, lat) }, \
+ { "lng", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_ahrs3_t, lng) }, \
+ { "v1", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_ahrs3_t, v1) }, \
+ { "v2", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_ahrs3_t, v2) }, \
+ { "v3", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_ahrs3_t, v3) }, \
+ { "v4", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_ahrs3_t, v4) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a ahrs3 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 roll [rad] Roll angle.
+ * @param pitch [rad] Pitch angle.
+ * @param yaw [rad] Yaw angle.
+ * @param altitude [m] Altitude (MSL).
+ * @param lat [degE7] Latitude.
+ * @param lng [degE7] Longitude.
+ * @param v1 Test variable1.
+ * @param v2 Test variable2.
+ * @param v3 Test variable3.
+ * @param v4 Test variable4.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_ahrs3_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ float roll, float pitch, float yaw, float altitude, int32_t lat, int32_t lng, float v1, float v2, float v3, float v4)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_AHRS3_LEN];
+ _mav_put_float(buf, 0, roll);
+ _mav_put_float(buf, 4, pitch);
+ _mav_put_float(buf, 8, yaw);
+ _mav_put_float(buf, 12, altitude);
+ _mav_put_int32_t(buf, 16, lat);
+ _mav_put_int32_t(buf, 20, lng);
+ _mav_put_float(buf, 24, v1);
+ _mav_put_float(buf, 28, v2);
+ _mav_put_float(buf, 32, v3);
+ _mav_put_float(buf, 36, v4);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AHRS3_LEN);
+#else
+ mavlink_ahrs3_t packet;
+ packet.roll = roll;
+ packet.pitch = pitch;
+ packet.yaw = yaw;
+ packet.altitude = altitude;
+ packet.lat = lat;
+ packet.lng = lng;
+ packet.v1 = v1;
+ packet.v2 = v2;
+ packet.v3 = v3;
+ packet.v4 = v4;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AHRS3_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_AHRS3;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_AHRS3_MIN_LEN, MAVLINK_MSG_ID_AHRS3_LEN, MAVLINK_MSG_ID_AHRS3_CRC);
+}
+
+/**
+ * @brief Pack a ahrs3 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 roll [rad] Roll angle.
+ * @param pitch [rad] Pitch angle.
+ * @param yaw [rad] Yaw angle.
+ * @param altitude [m] Altitude (MSL).
+ * @param lat [degE7] Latitude.
+ * @param lng [degE7] Longitude.
+ * @param v1 Test variable1.
+ * @param v2 Test variable2.
+ * @param v3 Test variable3.
+ * @param v4 Test variable4.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_ahrs3_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ float roll, float pitch, float yaw, float altitude, int32_t lat, int32_t lng, float v1, float v2, float v3, float v4)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_AHRS3_LEN];
+ _mav_put_float(buf, 0, roll);
+ _mav_put_float(buf, 4, pitch);
+ _mav_put_float(buf, 8, yaw);
+ _mav_put_float(buf, 12, altitude);
+ _mav_put_int32_t(buf, 16, lat);
+ _mav_put_int32_t(buf, 20, lng);
+ _mav_put_float(buf, 24, v1);
+ _mav_put_float(buf, 28, v2);
+ _mav_put_float(buf, 32, v3);
+ _mav_put_float(buf, 36, v4);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AHRS3_LEN);
+#else
+ mavlink_ahrs3_t packet;
+ packet.roll = roll;
+ packet.pitch = pitch;
+ packet.yaw = yaw;
+ packet.altitude = altitude;
+ packet.lat = lat;
+ packet.lng = lng;
+ packet.v1 = v1;
+ packet.v2 = v2;
+ packet.v3 = v3;
+ packet.v4 = v4;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AHRS3_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_AHRS3;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_AHRS3_MIN_LEN, MAVLINK_MSG_ID_AHRS3_LEN, MAVLINK_MSG_ID_AHRS3_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_AHRS3_MIN_LEN, MAVLINK_MSG_ID_AHRS3_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a ahrs3 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 roll [rad] Roll angle.
+ * @param pitch [rad] Pitch angle.
+ * @param yaw [rad] Yaw angle.
+ * @param altitude [m] Altitude (MSL).
+ * @param lat [degE7] Latitude.
+ * @param lng [degE7] Longitude.
+ * @param v1 Test variable1.
+ * @param v2 Test variable2.
+ * @param v3 Test variable3.
+ * @param v4 Test variable4.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_ahrs3_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ float roll,float pitch,float yaw,float altitude,int32_t lat,int32_t lng,float v1,float v2,float v3,float v4)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_AHRS3_LEN];
+ _mav_put_float(buf, 0, roll);
+ _mav_put_float(buf, 4, pitch);
+ _mav_put_float(buf, 8, yaw);
+ _mav_put_float(buf, 12, altitude);
+ _mav_put_int32_t(buf, 16, lat);
+ _mav_put_int32_t(buf, 20, lng);
+ _mav_put_float(buf, 24, v1);
+ _mav_put_float(buf, 28, v2);
+ _mav_put_float(buf, 32, v3);
+ _mav_put_float(buf, 36, v4);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AHRS3_LEN);
+#else
+ mavlink_ahrs3_t packet;
+ packet.roll = roll;
+ packet.pitch = pitch;
+ packet.yaw = yaw;
+ packet.altitude = altitude;
+ packet.lat = lat;
+ packet.lng = lng;
+ packet.v1 = v1;
+ packet.v2 = v2;
+ packet.v3 = v3;
+ packet.v4 = v4;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AHRS3_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_AHRS3;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_AHRS3_MIN_LEN, MAVLINK_MSG_ID_AHRS3_LEN, MAVLINK_MSG_ID_AHRS3_CRC);
+}
+
+/**
+ * @brief Encode a ahrs3 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 ahrs3 C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_ahrs3_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_ahrs3_t* ahrs3)
+{
+ return mavlink_msg_ahrs3_pack(system_id, component_id, msg, ahrs3->roll, ahrs3->pitch, ahrs3->yaw, ahrs3->altitude, ahrs3->lat, ahrs3->lng, ahrs3->v1, ahrs3->v2, ahrs3->v3, ahrs3->v4);
+}
+
+/**
+ * @brief Encode a ahrs3 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 ahrs3 C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_ahrs3_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_ahrs3_t* ahrs3)
+{
+ return mavlink_msg_ahrs3_pack_chan(system_id, component_id, chan, msg, ahrs3->roll, ahrs3->pitch, ahrs3->yaw, ahrs3->altitude, ahrs3->lat, ahrs3->lng, ahrs3->v1, ahrs3->v2, ahrs3->v3, ahrs3->v4);
+}
+
+/**
+ * @brief Encode a ahrs3 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 ahrs3 C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_ahrs3_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_ahrs3_t* ahrs3)
+{
+ return mavlink_msg_ahrs3_pack_status(system_id, component_id, _status, msg, ahrs3->roll, ahrs3->pitch, ahrs3->yaw, ahrs3->altitude, ahrs3->lat, ahrs3->lng, ahrs3->v1, ahrs3->v2, ahrs3->v3, ahrs3->v4);
+}
+
+/**
+ * @brief Send a ahrs3 message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param roll [rad] Roll angle.
+ * @param pitch [rad] Pitch angle.
+ * @param yaw [rad] Yaw angle.
+ * @param altitude [m] Altitude (MSL).
+ * @param lat [degE7] Latitude.
+ * @param lng [degE7] Longitude.
+ * @param v1 Test variable1.
+ * @param v2 Test variable2.
+ * @param v3 Test variable3.
+ * @param v4 Test variable4.
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_ahrs3_send(mavlink_channel_t chan, float roll, float pitch, float yaw, float altitude, int32_t lat, int32_t lng, float v1, float v2, float v3, float v4)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_AHRS3_LEN];
+ _mav_put_float(buf, 0, roll);
+ _mav_put_float(buf, 4, pitch);
+ _mav_put_float(buf, 8, yaw);
+ _mav_put_float(buf, 12, altitude);
+ _mav_put_int32_t(buf, 16, lat);
+ _mav_put_int32_t(buf, 20, lng);
+ _mav_put_float(buf, 24, v1);
+ _mav_put_float(buf, 28, v2);
+ _mav_put_float(buf, 32, v3);
+ _mav_put_float(buf, 36, v4);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AHRS3, buf, MAVLINK_MSG_ID_AHRS3_MIN_LEN, MAVLINK_MSG_ID_AHRS3_LEN, MAVLINK_MSG_ID_AHRS3_CRC);
+#else
+ mavlink_ahrs3_t packet;
+ packet.roll = roll;
+ packet.pitch = pitch;
+ packet.yaw = yaw;
+ packet.altitude = altitude;
+ packet.lat = lat;
+ packet.lng = lng;
+ packet.v1 = v1;
+ packet.v2 = v2;
+ packet.v3 = v3;
+ packet.v4 = v4;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AHRS3, (const char *)&packet, MAVLINK_MSG_ID_AHRS3_MIN_LEN, MAVLINK_MSG_ID_AHRS3_LEN, MAVLINK_MSG_ID_AHRS3_CRC);
+#endif
+}
+
+/**
+ * @brief Send a ahrs3 message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_ahrs3_send_struct(mavlink_channel_t chan, const mavlink_ahrs3_t* ahrs3)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_ahrs3_send(chan, ahrs3->roll, ahrs3->pitch, ahrs3->yaw, ahrs3->altitude, ahrs3->lat, ahrs3->lng, ahrs3->v1, ahrs3->v2, ahrs3->v3, ahrs3->v4);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AHRS3, (const char *)ahrs3, MAVLINK_MSG_ID_AHRS3_MIN_LEN, MAVLINK_MSG_ID_AHRS3_LEN, MAVLINK_MSG_ID_AHRS3_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_AHRS3_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_ahrs3_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float roll, float pitch, float yaw, float altitude, int32_t lat, int32_t lng, float v1, float v2, float v3, float v4)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_float(buf, 0, roll);
+ _mav_put_float(buf, 4, pitch);
+ _mav_put_float(buf, 8, yaw);
+ _mav_put_float(buf, 12, altitude);
+ _mav_put_int32_t(buf, 16, lat);
+ _mav_put_int32_t(buf, 20, lng);
+ _mav_put_float(buf, 24, v1);
+ _mav_put_float(buf, 28, v2);
+ _mav_put_float(buf, 32, v3);
+ _mav_put_float(buf, 36, v4);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AHRS3, buf, MAVLINK_MSG_ID_AHRS3_MIN_LEN, MAVLINK_MSG_ID_AHRS3_LEN, MAVLINK_MSG_ID_AHRS3_CRC);
+#else
+ mavlink_ahrs3_t *packet = (mavlink_ahrs3_t *)msgbuf;
+ packet->roll = roll;
+ packet->pitch = pitch;
+ packet->yaw = yaw;
+ packet->altitude = altitude;
+ packet->lat = lat;
+ packet->lng = lng;
+ packet->v1 = v1;
+ packet->v2 = v2;
+ packet->v3 = v3;
+ packet->v4 = v4;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AHRS3, (const char *)packet, MAVLINK_MSG_ID_AHRS3_MIN_LEN, MAVLINK_MSG_ID_AHRS3_LEN, MAVLINK_MSG_ID_AHRS3_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE AHRS3 UNPACKING
+
+
+/**
+ * @brief Get field roll from ahrs3 message
+ *
+ * @return [rad] Roll angle.
+ */
+static inline float mavlink_msg_ahrs3_get_roll(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 0);
+}
+
+/**
+ * @brief Get field pitch from ahrs3 message
+ *
+ * @return [rad] Pitch angle.
+ */
+static inline float mavlink_msg_ahrs3_get_pitch(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 4);
+}
+
+/**
+ * @brief Get field yaw from ahrs3 message
+ *
+ * @return [rad] Yaw angle.
+ */
+static inline float mavlink_msg_ahrs3_get_yaw(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 8);
+}
+
+/**
+ * @brief Get field altitude from ahrs3 message
+ *
+ * @return [m] Altitude (MSL).
+ */
+static inline float mavlink_msg_ahrs3_get_altitude(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 12);
+}
+
+/**
+ * @brief Get field lat from ahrs3 message
+ *
+ * @return [degE7] Latitude.
+ */
+static inline int32_t mavlink_msg_ahrs3_get_lat(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_int32_t(msg, 16);
+}
+
+/**
+ * @brief Get field lng from ahrs3 message
+ *
+ * @return [degE7] Longitude.
+ */
+static inline int32_t mavlink_msg_ahrs3_get_lng(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_int32_t(msg, 20);
+}
+
+/**
+ * @brief Get field v1 from ahrs3 message
+ *
+ * @return Test variable1.
+ */
+static inline float mavlink_msg_ahrs3_get_v1(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 24);
+}
+
+/**
+ * @brief Get field v2 from ahrs3 message
+ *
+ * @return Test variable2.
+ */
+static inline float mavlink_msg_ahrs3_get_v2(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 28);
+}
+
+/**
+ * @brief Get field v3 from ahrs3 message
+ *
+ * @return Test variable3.
+ */
+static inline float mavlink_msg_ahrs3_get_v3(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 32);
+}
+
+/**
+ * @brief Get field v4 from ahrs3 message
+ *
+ * @return Test variable4.
+ */
+static inline float mavlink_msg_ahrs3_get_v4(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 36);
+}
+
+/**
+ * @brief Decode a ahrs3 message into a struct
+ *
+ * @param msg The message to decode
+ * @param ahrs3 C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_ahrs3_decode(const mavlink_message_t* msg, mavlink_ahrs3_t* ahrs3)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ ahrs3->roll = mavlink_msg_ahrs3_get_roll(msg);
+ ahrs3->pitch = mavlink_msg_ahrs3_get_pitch(msg);
+ ahrs3->yaw = mavlink_msg_ahrs3_get_yaw(msg);
+ ahrs3->altitude = mavlink_msg_ahrs3_get_altitude(msg);
+ ahrs3->lat = mavlink_msg_ahrs3_get_lat(msg);
+ ahrs3->lng = mavlink_msg_ahrs3_get_lng(msg);
+ ahrs3->v1 = mavlink_msg_ahrs3_get_v1(msg);
+ ahrs3->v2 = mavlink_msg_ahrs3_get_v2(msg);
+ ahrs3->v3 = mavlink_msg_ahrs3_get_v3(msg);
+ ahrs3->v4 = mavlink_msg_ahrs3_get_v4(msg);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_AHRS3_LEN? msg->len : MAVLINK_MSG_ID_AHRS3_LEN;
+ memset(ahrs3, 0, MAVLINK_MSG_ID_AHRS3_LEN);
+ memcpy(ahrs3, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/ardupilotmega/mavlink_msg_airspeed_autocal.h b/lib/main/MAVLink/ardupilotmega/mavlink_msg_airspeed_autocal.h
new file mode 100644
index 00000000000..9ffdda1de63
--- /dev/null
+++ b/lib/main/MAVLink/ardupilotmega/mavlink_msg_airspeed_autocal.h
@@ -0,0 +1,568 @@
+#pragma once
+// MESSAGE AIRSPEED_AUTOCAL PACKING
+
+#define MAVLINK_MSG_ID_AIRSPEED_AUTOCAL 174
+
+
+typedef struct __mavlink_airspeed_autocal_t {
+ float vx; /*< [m/s] GPS velocity north.*/
+ float vy; /*< [m/s] GPS velocity east.*/
+ float vz; /*< [m/s] GPS velocity down.*/
+ float diff_pressure; /*< [Pa] Differential pressure.*/
+ float EAS2TAS; /*< Estimated to true airspeed ratio.*/
+ float ratio; /*< Airspeed ratio.*/
+ float state_x; /*< EKF state x.*/
+ float state_y; /*< EKF state y.*/
+ float state_z; /*< EKF state z.*/
+ float Pax; /*< EKF Pax.*/
+ float Pby; /*< EKF Pby.*/
+ float Pcz; /*< EKF Pcz.*/
+} mavlink_airspeed_autocal_t;
+
+#define MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN 48
+#define MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_MIN_LEN 48
+#define MAVLINK_MSG_ID_174_LEN 48
+#define MAVLINK_MSG_ID_174_MIN_LEN 48
+
+#define MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_CRC 167
+#define MAVLINK_MSG_ID_174_CRC 167
+
+
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_AIRSPEED_AUTOCAL { \
+ 174, \
+ "AIRSPEED_AUTOCAL", \
+ 12, \
+ { { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_airspeed_autocal_t, vx) }, \
+ { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_airspeed_autocal_t, vy) }, \
+ { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_airspeed_autocal_t, vz) }, \
+ { "diff_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_airspeed_autocal_t, diff_pressure) }, \
+ { "EAS2TAS", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_airspeed_autocal_t, EAS2TAS) }, \
+ { "ratio", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_airspeed_autocal_t, ratio) }, \
+ { "state_x", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_airspeed_autocal_t, state_x) }, \
+ { "state_y", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_airspeed_autocal_t, state_y) }, \
+ { "state_z", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_airspeed_autocal_t, state_z) }, \
+ { "Pax", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_airspeed_autocal_t, Pax) }, \
+ { "Pby", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_airspeed_autocal_t, Pby) }, \
+ { "Pcz", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_airspeed_autocal_t, Pcz) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_AIRSPEED_AUTOCAL { \
+ "AIRSPEED_AUTOCAL", \
+ 12, \
+ { { "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_airspeed_autocal_t, vx) }, \
+ { "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_airspeed_autocal_t, vy) }, \
+ { "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_airspeed_autocal_t, vz) }, \
+ { "diff_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_airspeed_autocal_t, diff_pressure) }, \
+ { "EAS2TAS", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_airspeed_autocal_t, EAS2TAS) }, \
+ { "ratio", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_airspeed_autocal_t, ratio) }, \
+ { "state_x", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_airspeed_autocal_t, state_x) }, \
+ { "state_y", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_airspeed_autocal_t, state_y) }, \
+ { "state_z", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_airspeed_autocal_t, state_z) }, \
+ { "Pax", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_airspeed_autocal_t, Pax) }, \
+ { "Pby", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_airspeed_autocal_t, Pby) }, \
+ { "Pcz", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_airspeed_autocal_t, Pcz) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a airspeed_autocal 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 vx [m/s] GPS velocity north.
+ * @param vy [m/s] GPS velocity east.
+ * @param vz [m/s] GPS velocity down.
+ * @param diff_pressure [Pa] Differential pressure.
+ * @param EAS2TAS Estimated to true airspeed ratio.
+ * @param ratio Airspeed ratio.
+ * @param state_x EKF state x.
+ * @param state_y EKF state y.
+ * @param state_z EKF state z.
+ * @param Pax EKF Pax.
+ * @param Pby EKF Pby.
+ * @param Pcz EKF Pcz.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_airspeed_autocal_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ float vx, float vy, float vz, float diff_pressure, float EAS2TAS, float ratio, float state_x, float state_y, float state_z, float Pax, float Pby, float Pcz)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN];
+ _mav_put_float(buf, 0, vx);
+ _mav_put_float(buf, 4, vy);
+ _mav_put_float(buf, 8, vz);
+ _mav_put_float(buf, 12, diff_pressure);
+ _mav_put_float(buf, 16, EAS2TAS);
+ _mav_put_float(buf, 20, ratio);
+ _mav_put_float(buf, 24, state_x);
+ _mav_put_float(buf, 28, state_y);
+ _mav_put_float(buf, 32, state_z);
+ _mav_put_float(buf, 36, Pax);
+ _mav_put_float(buf, 40, Pby);
+ _mav_put_float(buf, 44, Pcz);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN);
+#else
+ mavlink_airspeed_autocal_t packet;
+ packet.vx = vx;
+ packet.vy = vy;
+ packet.vz = vz;
+ packet.diff_pressure = diff_pressure;
+ packet.EAS2TAS = EAS2TAS;
+ packet.ratio = ratio;
+ packet.state_x = state_x;
+ packet.state_y = state_y;
+ packet.state_z = state_z;
+ packet.Pax = Pax;
+ packet.Pby = Pby;
+ packet.Pcz = Pcz;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_AIRSPEED_AUTOCAL;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_MIN_LEN, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_CRC);
+}
+
+/**
+ * @brief Pack a airspeed_autocal 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 vx [m/s] GPS velocity north.
+ * @param vy [m/s] GPS velocity east.
+ * @param vz [m/s] GPS velocity down.
+ * @param diff_pressure [Pa] Differential pressure.
+ * @param EAS2TAS Estimated to true airspeed ratio.
+ * @param ratio Airspeed ratio.
+ * @param state_x EKF state x.
+ * @param state_y EKF state y.
+ * @param state_z EKF state z.
+ * @param Pax EKF Pax.
+ * @param Pby EKF Pby.
+ * @param Pcz EKF Pcz.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_airspeed_autocal_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ float vx, float vy, float vz, float diff_pressure, float EAS2TAS, float ratio, float state_x, float state_y, float state_z, float Pax, float Pby, float Pcz)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN];
+ _mav_put_float(buf, 0, vx);
+ _mav_put_float(buf, 4, vy);
+ _mav_put_float(buf, 8, vz);
+ _mav_put_float(buf, 12, diff_pressure);
+ _mav_put_float(buf, 16, EAS2TAS);
+ _mav_put_float(buf, 20, ratio);
+ _mav_put_float(buf, 24, state_x);
+ _mav_put_float(buf, 28, state_y);
+ _mav_put_float(buf, 32, state_z);
+ _mav_put_float(buf, 36, Pax);
+ _mav_put_float(buf, 40, Pby);
+ _mav_put_float(buf, 44, Pcz);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN);
+#else
+ mavlink_airspeed_autocal_t packet;
+ packet.vx = vx;
+ packet.vy = vy;
+ packet.vz = vz;
+ packet.diff_pressure = diff_pressure;
+ packet.EAS2TAS = EAS2TAS;
+ packet.ratio = ratio;
+ packet.state_x = state_x;
+ packet.state_y = state_y;
+ packet.state_z = state_z;
+ packet.Pax = Pax;
+ packet.Pby = Pby;
+ packet.Pcz = Pcz;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_AIRSPEED_AUTOCAL;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_MIN_LEN, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_MIN_LEN, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a airspeed_autocal 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 vx [m/s] GPS velocity north.
+ * @param vy [m/s] GPS velocity east.
+ * @param vz [m/s] GPS velocity down.
+ * @param diff_pressure [Pa] Differential pressure.
+ * @param EAS2TAS Estimated to true airspeed ratio.
+ * @param ratio Airspeed ratio.
+ * @param state_x EKF state x.
+ * @param state_y EKF state y.
+ * @param state_z EKF state z.
+ * @param Pax EKF Pax.
+ * @param Pby EKF Pby.
+ * @param Pcz EKF Pcz.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_airspeed_autocal_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ float vx,float vy,float vz,float diff_pressure,float EAS2TAS,float ratio,float state_x,float state_y,float state_z,float Pax,float Pby,float Pcz)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN];
+ _mav_put_float(buf, 0, vx);
+ _mav_put_float(buf, 4, vy);
+ _mav_put_float(buf, 8, vz);
+ _mav_put_float(buf, 12, diff_pressure);
+ _mav_put_float(buf, 16, EAS2TAS);
+ _mav_put_float(buf, 20, ratio);
+ _mav_put_float(buf, 24, state_x);
+ _mav_put_float(buf, 28, state_y);
+ _mav_put_float(buf, 32, state_z);
+ _mav_put_float(buf, 36, Pax);
+ _mav_put_float(buf, 40, Pby);
+ _mav_put_float(buf, 44, Pcz);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN);
+#else
+ mavlink_airspeed_autocal_t packet;
+ packet.vx = vx;
+ packet.vy = vy;
+ packet.vz = vz;
+ packet.diff_pressure = diff_pressure;
+ packet.EAS2TAS = EAS2TAS;
+ packet.ratio = ratio;
+ packet.state_x = state_x;
+ packet.state_y = state_y;
+ packet.state_z = state_z;
+ packet.Pax = Pax;
+ packet.Pby = Pby;
+ packet.Pcz = Pcz;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_AIRSPEED_AUTOCAL;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_MIN_LEN, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_CRC);
+}
+
+/**
+ * @brief Encode a airspeed_autocal 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 airspeed_autocal C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_airspeed_autocal_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_airspeed_autocal_t* airspeed_autocal)
+{
+ return mavlink_msg_airspeed_autocal_pack(system_id, component_id, msg, airspeed_autocal->vx, airspeed_autocal->vy, airspeed_autocal->vz, airspeed_autocal->diff_pressure, airspeed_autocal->EAS2TAS, airspeed_autocal->ratio, airspeed_autocal->state_x, airspeed_autocal->state_y, airspeed_autocal->state_z, airspeed_autocal->Pax, airspeed_autocal->Pby, airspeed_autocal->Pcz);
+}
+
+/**
+ * @brief Encode a airspeed_autocal 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 airspeed_autocal C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_airspeed_autocal_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_airspeed_autocal_t* airspeed_autocal)
+{
+ return mavlink_msg_airspeed_autocal_pack_chan(system_id, component_id, chan, msg, airspeed_autocal->vx, airspeed_autocal->vy, airspeed_autocal->vz, airspeed_autocal->diff_pressure, airspeed_autocal->EAS2TAS, airspeed_autocal->ratio, airspeed_autocal->state_x, airspeed_autocal->state_y, airspeed_autocal->state_z, airspeed_autocal->Pax, airspeed_autocal->Pby, airspeed_autocal->Pcz);
+}
+
+/**
+ * @brief Encode a airspeed_autocal 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 airspeed_autocal C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_airspeed_autocal_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_airspeed_autocal_t* airspeed_autocal)
+{
+ return mavlink_msg_airspeed_autocal_pack_status(system_id, component_id, _status, msg, airspeed_autocal->vx, airspeed_autocal->vy, airspeed_autocal->vz, airspeed_autocal->diff_pressure, airspeed_autocal->EAS2TAS, airspeed_autocal->ratio, airspeed_autocal->state_x, airspeed_autocal->state_y, airspeed_autocal->state_z, airspeed_autocal->Pax, airspeed_autocal->Pby, airspeed_autocal->Pcz);
+}
+
+/**
+ * @brief Send a airspeed_autocal message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param vx [m/s] GPS velocity north.
+ * @param vy [m/s] GPS velocity east.
+ * @param vz [m/s] GPS velocity down.
+ * @param diff_pressure [Pa] Differential pressure.
+ * @param EAS2TAS Estimated to true airspeed ratio.
+ * @param ratio Airspeed ratio.
+ * @param state_x EKF state x.
+ * @param state_y EKF state y.
+ * @param state_z EKF state z.
+ * @param Pax EKF Pax.
+ * @param Pby EKF Pby.
+ * @param Pcz EKF Pcz.
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_airspeed_autocal_send(mavlink_channel_t chan, float vx, float vy, float vz, float diff_pressure, float EAS2TAS, float ratio, float state_x, float state_y, float state_z, float Pax, float Pby, float Pcz)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN];
+ _mav_put_float(buf, 0, vx);
+ _mav_put_float(buf, 4, vy);
+ _mav_put_float(buf, 8, vz);
+ _mav_put_float(buf, 12, diff_pressure);
+ _mav_put_float(buf, 16, EAS2TAS);
+ _mav_put_float(buf, 20, ratio);
+ _mav_put_float(buf, 24, state_x);
+ _mav_put_float(buf, 28, state_y);
+ _mav_put_float(buf, 32, state_z);
+ _mav_put_float(buf, 36, Pax);
+ _mav_put_float(buf, 40, Pby);
+ _mav_put_float(buf, 44, Pcz);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL, buf, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_MIN_LEN, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_CRC);
+#else
+ mavlink_airspeed_autocal_t packet;
+ packet.vx = vx;
+ packet.vy = vy;
+ packet.vz = vz;
+ packet.diff_pressure = diff_pressure;
+ packet.EAS2TAS = EAS2TAS;
+ packet.ratio = ratio;
+ packet.state_x = state_x;
+ packet.state_y = state_y;
+ packet.state_z = state_z;
+ packet.Pax = Pax;
+ packet.Pby = Pby;
+ packet.Pcz = Pcz;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL, (const char *)&packet, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_MIN_LEN, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_CRC);
+#endif
+}
+
+/**
+ * @brief Send a airspeed_autocal message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_airspeed_autocal_send_struct(mavlink_channel_t chan, const mavlink_airspeed_autocal_t* airspeed_autocal)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_airspeed_autocal_send(chan, airspeed_autocal->vx, airspeed_autocal->vy, airspeed_autocal->vz, airspeed_autocal->diff_pressure, airspeed_autocal->EAS2TAS, airspeed_autocal->ratio, airspeed_autocal->state_x, airspeed_autocal->state_y, airspeed_autocal->state_z, airspeed_autocal->Pax, airspeed_autocal->Pby, airspeed_autocal->Pcz);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL, (const char *)airspeed_autocal, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_MIN_LEN, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_airspeed_autocal_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float vx, float vy, float vz, float diff_pressure, float EAS2TAS, float ratio, float state_x, float state_y, float state_z, float Pax, float Pby, float Pcz)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_float(buf, 0, vx);
+ _mav_put_float(buf, 4, vy);
+ _mav_put_float(buf, 8, vz);
+ _mav_put_float(buf, 12, diff_pressure);
+ _mav_put_float(buf, 16, EAS2TAS);
+ _mav_put_float(buf, 20, ratio);
+ _mav_put_float(buf, 24, state_x);
+ _mav_put_float(buf, 28, state_y);
+ _mav_put_float(buf, 32, state_z);
+ _mav_put_float(buf, 36, Pax);
+ _mav_put_float(buf, 40, Pby);
+ _mav_put_float(buf, 44, Pcz);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL, buf, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_MIN_LEN, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_CRC);
+#else
+ mavlink_airspeed_autocal_t *packet = (mavlink_airspeed_autocal_t *)msgbuf;
+ packet->vx = vx;
+ packet->vy = vy;
+ packet->vz = vz;
+ packet->diff_pressure = diff_pressure;
+ packet->EAS2TAS = EAS2TAS;
+ packet->ratio = ratio;
+ packet->state_x = state_x;
+ packet->state_y = state_y;
+ packet->state_z = state_z;
+ packet->Pax = Pax;
+ packet->Pby = Pby;
+ packet->Pcz = Pcz;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL, (const char *)packet, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_MIN_LEN, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE AIRSPEED_AUTOCAL UNPACKING
+
+
+/**
+ * @brief Get field vx from airspeed_autocal message
+ *
+ * @return [m/s] GPS velocity north.
+ */
+static inline float mavlink_msg_airspeed_autocal_get_vx(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 0);
+}
+
+/**
+ * @brief Get field vy from airspeed_autocal message
+ *
+ * @return [m/s] GPS velocity east.
+ */
+static inline float mavlink_msg_airspeed_autocal_get_vy(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 4);
+}
+
+/**
+ * @brief Get field vz from airspeed_autocal message
+ *
+ * @return [m/s] GPS velocity down.
+ */
+static inline float mavlink_msg_airspeed_autocal_get_vz(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 8);
+}
+
+/**
+ * @brief Get field diff_pressure from airspeed_autocal message
+ *
+ * @return [Pa] Differential pressure.
+ */
+static inline float mavlink_msg_airspeed_autocal_get_diff_pressure(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 12);
+}
+
+/**
+ * @brief Get field EAS2TAS from airspeed_autocal message
+ *
+ * @return Estimated to true airspeed ratio.
+ */
+static inline float mavlink_msg_airspeed_autocal_get_EAS2TAS(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 16);
+}
+
+/**
+ * @brief Get field ratio from airspeed_autocal message
+ *
+ * @return Airspeed ratio.
+ */
+static inline float mavlink_msg_airspeed_autocal_get_ratio(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 20);
+}
+
+/**
+ * @brief Get field state_x from airspeed_autocal message
+ *
+ * @return EKF state x.
+ */
+static inline float mavlink_msg_airspeed_autocal_get_state_x(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 24);
+}
+
+/**
+ * @brief Get field state_y from airspeed_autocal message
+ *
+ * @return EKF state y.
+ */
+static inline float mavlink_msg_airspeed_autocal_get_state_y(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 28);
+}
+
+/**
+ * @brief Get field state_z from airspeed_autocal message
+ *
+ * @return EKF state z.
+ */
+static inline float mavlink_msg_airspeed_autocal_get_state_z(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 32);
+}
+
+/**
+ * @brief Get field Pax from airspeed_autocal message
+ *
+ * @return EKF Pax.
+ */
+static inline float mavlink_msg_airspeed_autocal_get_Pax(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 36);
+}
+
+/**
+ * @brief Get field Pby from airspeed_autocal message
+ *
+ * @return EKF Pby.
+ */
+static inline float mavlink_msg_airspeed_autocal_get_Pby(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 40);
+}
+
+/**
+ * @brief Get field Pcz from airspeed_autocal message
+ *
+ * @return EKF Pcz.
+ */
+static inline float mavlink_msg_airspeed_autocal_get_Pcz(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 44);
+}
+
+/**
+ * @brief Decode a airspeed_autocal message into a struct
+ *
+ * @param msg The message to decode
+ * @param airspeed_autocal C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_airspeed_autocal_decode(const mavlink_message_t* msg, mavlink_airspeed_autocal_t* airspeed_autocal)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ airspeed_autocal->vx = mavlink_msg_airspeed_autocal_get_vx(msg);
+ airspeed_autocal->vy = mavlink_msg_airspeed_autocal_get_vy(msg);
+ airspeed_autocal->vz = mavlink_msg_airspeed_autocal_get_vz(msg);
+ airspeed_autocal->diff_pressure = mavlink_msg_airspeed_autocal_get_diff_pressure(msg);
+ airspeed_autocal->EAS2TAS = mavlink_msg_airspeed_autocal_get_EAS2TAS(msg);
+ airspeed_autocal->ratio = mavlink_msg_airspeed_autocal_get_ratio(msg);
+ airspeed_autocal->state_x = mavlink_msg_airspeed_autocal_get_state_x(msg);
+ airspeed_autocal->state_y = mavlink_msg_airspeed_autocal_get_state_y(msg);
+ airspeed_autocal->state_z = mavlink_msg_airspeed_autocal_get_state_z(msg);
+ airspeed_autocal->Pax = mavlink_msg_airspeed_autocal_get_Pax(msg);
+ airspeed_autocal->Pby = mavlink_msg_airspeed_autocal_get_Pby(msg);
+ airspeed_autocal->Pcz = mavlink_msg_airspeed_autocal_get_Pcz(msg);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN? msg->len : MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN;
+ memset(airspeed_autocal, 0, MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_LEN);
+ memcpy(airspeed_autocal, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/ardupilotmega/mavlink_msg_aoa_ssa.h b/lib/main/MAVLink/ardupilotmega/mavlink_msg_aoa_ssa.h
new file mode 100644
index 00000000000..0c8148124ca
--- /dev/null
+++ b/lib/main/MAVLink/ardupilotmega/mavlink_msg_aoa_ssa.h
@@ -0,0 +1,316 @@
+#pragma once
+// MESSAGE AOA_SSA PACKING
+
+#define MAVLINK_MSG_ID_AOA_SSA 11020
+
+
+typedef struct __mavlink_aoa_ssa_t {
+ uint64_t time_usec; /*< [us] Timestamp (since boot or Unix epoch).*/
+ float AOA; /*< [deg] Angle of Attack.*/
+ float SSA; /*< [deg] Side Slip Angle.*/
+} mavlink_aoa_ssa_t;
+
+#define MAVLINK_MSG_ID_AOA_SSA_LEN 16
+#define MAVLINK_MSG_ID_AOA_SSA_MIN_LEN 16
+#define MAVLINK_MSG_ID_11020_LEN 16
+#define MAVLINK_MSG_ID_11020_MIN_LEN 16
+
+#define MAVLINK_MSG_ID_AOA_SSA_CRC 205
+#define MAVLINK_MSG_ID_11020_CRC 205
+
+
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_AOA_SSA { \
+ 11020, \
+ "AOA_SSA", \
+ 3, \
+ { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_aoa_ssa_t, time_usec) }, \
+ { "AOA", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_aoa_ssa_t, AOA) }, \
+ { "SSA", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_aoa_ssa_t, SSA) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_AOA_SSA { \
+ "AOA_SSA", \
+ 3, \
+ { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_aoa_ssa_t, time_usec) }, \
+ { "AOA", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_aoa_ssa_t, AOA) }, \
+ { "SSA", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_aoa_ssa_t, SSA) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a aoa_ssa 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 time_usec [us] Timestamp (since boot or Unix epoch).
+ * @param AOA [deg] Angle of Attack.
+ * @param SSA [deg] Side Slip Angle.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_aoa_ssa_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint64_t time_usec, float AOA, float SSA)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_AOA_SSA_LEN];
+ _mav_put_uint64_t(buf, 0, time_usec);
+ _mav_put_float(buf, 8, AOA);
+ _mav_put_float(buf, 12, SSA);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AOA_SSA_LEN);
+#else
+ mavlink_aoa_ssa_t packet;
+ packet.time_usec = time_usec;
+ packet.AOA = AOA;
+ packet.SSA = SSA;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AOA_SSA_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_AOA_SSA;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_AOA_SSA_MIN_LEN, MAVLINK_MSG_ID_AOA_SSA_LEN, MAVLINK_MSG_ID_AOA_SSA_CRC);
+}
+
+/**
+ * @brief Pack a aoa_ssa 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 time_usec [us] Timestamp (since boot or Unix epoch).
+ * @param AOA [deg] Angle of Attack.
+ * @param SSA [deg] Side Slip Angle.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_aoa_ssa_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ uint64_t time_usec, float AOA, float SSA)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_AOA_SSA_LEN];
+ _mav_put_uint64_t(buf, 0, time_usec);
+ _mav_put_float(buf, 8, AOA);
+ _mav_put_float(buf, 12, SSA);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AOA_SSA_LEN);
+#else
+ mavlink_aoa_ssa_t packet;
+ packet.time_usec = time_usec;
+ packet.AOA = AOA;
+ packet.SSA = SSA;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AOA_SSA_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_AOA_SSA;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_AOA_SSA_MIN_LEN, MAVLINK_MSG_ID_AOA_SSA_LEN, MAVLINK_MSG_ID_AOA_SSA_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_AOA_SSA_MIN_LEN, MAVLINK_MSG_ID_AOA_SSA_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a aoa_ssa 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 time_usec [us] Timestamp (since boot or Unix epoch).
+ * @param AOA [deg] Angle of Attack.
+ * @param SSA [deg] Side Slip Angle.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_aoa_ssa_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint64_t time_usec,float AOA,float SSA)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_AOA_SSA_LEN];
+ _mav_put_uint64_t(buf, 0, time_usec);
+ _mav_put_float(buf, 8, AOA);
+ _mav_put_float(buf, 12, SSA);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AOA_SSA_LEN);
+#else
+ mavlink_aoa_ssa_t packet;
+ packet.time_usec = time_usec;
+ packet.AOA = AOA;
+ packet.SSA = SSA;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AOA_SSA_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_AOA_SSA;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_AOA_SSA_MIN_LEN, MAVLINK_MSG_ID_AOA_SSA_LEN, MAVLINK_MSG_ID_AOA_SSA_CRC);
+}
+
+/**
+ * @brief Encode a aoa_ssa 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 aoa_ssa C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_aoa_ssa_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_aoa_ssa_t* aoa_ssa)
+{
+ return mavlink_msg_aoa_ssa_pack(system_id, component_id, msg, aoa_ssa->time_usec, aoa_ssa->AOA, aoa_ssa->SSA);
+}
+
+/**
+ * @brief Encode a aoa_ssa 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 aoa_ssa C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_aoa_ssa_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_aoa_ssa_t* aoa_ssa)
+{
+ return mavlink_msg_aoa_ssa_pack_chan(system_id, component_id, chan, msg, aoa_ssa->time_usec, aoa_ssa->AOA, aoa_ssa->SSA);
+}
+
+/**
+ * @brief Encode a aoa_ssa 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 aoa_ssa C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_aoa_ssa_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_aoa_ssa_t* aoa_ssa)
+{
+ return mavlink_msg_aoa_ssa_pack_status(system_id, component_id, _status, msg, aoa_ssa->time_usec, aoa_ssa->AOA, aoa_ssa->SSA);
+}
+
+/**
+ * @brief Send a aoa_ssa message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param time_usec [us] Timestamp (since boot or Unix epoch).
+ * @param AOA [deg] Angle of Attack.
+ * @param SSA [deg] Side Slip Angle.
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_aoa_ssa_send(mavlink_channel_t chan, uint64_t time_usec, float AOA, float SSA)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_AOA_SSA_LEN];
+ _mav_put_uint64_t(buf, 0, time_usec);
+ _mav_put_float(buf, 8, AOA);
+ _mav_put_float(buf, 12, SSA);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AOA_SSA, buf, MAVLINK_MSG_ID_AOA_SSA_MIN_LEN, MAVLINK_MSG_ID_AOA_SSA_LEN, MAVLINK_MSG_ID_AOA_SSA_CRC);
+#else
+ mavlink_aoa_ssa_t packet;
+ packet.time_usec = time_usec;
+ packet.AOA = AOA;
+ packet.SSA = SSA;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AOA_SSA, (const char *)&packet, MAVLINK_MSG_ID_AOA_SSA_MIN_LEN, MAVLINK_MSG_ID_AOA_SSA_LEN, MAVLINK_MSG_ID_AOA_SSA_CRC);
+#endif
+}
+
+/**
+ * @brief Send a aoa_ssa message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_aoa_ssa_send_struct(mavlink_channel_t chan, const mavlink_aoa_ssa_t* aoa_ssa)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_aoa_ssa_send(chan, aoa_ssa->time_usec, aoa_ssa->AOA, aoa_ssa->SSA);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AOA_SSA, (const char *)aoa_ssa, MAVLINK_MSG_ID_AOA_SSA_MIN_LEN, MAVLINK_MSG_ID_AOA_SSA_LEN, MAVLINK_MSG_ID_AOA_SSA_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_AOA_SSA_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_aoa_ssa_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, float AOA, float SSA)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint64_t(buf, 0, time_usec);
+ _mav_put_float(buf, 8, AOA);
+ _mav_put_float(buf, 12, SSA);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AOA_SSA, buf, MAVLINK_MSG_ID_AOA_SSA_MIN_LEN, MAVLINK_MSG_ID_AOA_SSA_LEN, MAVLINK_MSG_ID_AOA_SSA_CRC);
+#else
+ mavlink_aoa_ssa_t *packet = (mavlink_aoa_ssa_t *)msgbuf;
+ packet->time_usec = time_usec;
+ packet->AOA = AOA;
+ packet->SSA = SSA;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AOA_SSA, (const char *)packet, MAVLINK_MSG_ID_AOA_SSA_MIN_LEN, MAVLINK_MSG_ID_AOA_SSA_LEN, MAVLINK_MSG_ID_AOA_SSA_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE AOA_SSA UNPACKING
+
+
+/**
+ * @brief Get field time_usec from aoa_ssa message
+ *
+ * @return [us] Timestamp (since boot or Unix epoch).
+ */
+static inline uint64_t mavlink_msg_aoa_ssa_get_time_usec(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint64_t(msg, 0);
+}
+
+/**
+ * @brief Get field AOA from aoa_ssa message
+ *
+ * @return [deg] Angle of Attack.
+ */
+static inline float mavlink_msg_aoa_ssa_get_AOA(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 8);
+}
+
+/**
+ * @brief Get field SSA from aoa_ssa message
+ *
+ * @return [deg] Side Slip Angle.
+ */
+static inline float mavlink_msg_aoa_ssa_get_SSA(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 12);
+}
+
+/**
+ * @brief Decode a aoa_ssa message into a struct
+ *
+ * @param msg The message to decode
+ * @param aoa_ssa C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_aoa_ssa_decode(const mavlink_message_t* msg, mavlink_aoa_ssa_t* aoa_ssa)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ aoa_ssa->time_usec = mavlink_msg_aoa_ssa_get_time_usec(msg);
+ aoa_ssa->AOA = mavlink_msg_aoa_ssa_get_AOA(msg);
+ aoa_ssa->SSA = mavlink_msg_aoa_ssa_get_SSA(msg);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_AOA_SSA_LEN? msg->len : MAVLINK_MSG_ID_AOA_SSA_LEN;
+ memset(aoa_ssa, 0, MAVLINK_MSG_ID_AOA_SSA_LEN);
+ memcpy(aoa_ssa, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/ardupilotmega/mavlink_msg_ap_adc.h b/lib/main/MAVLink/ardupilotmega/mavlink_msg_ap_adc.h
new file mode 100644
index 00000000000..bfbfc593ea8
--- /dev/null
+++ b/lib/main/MAVLink/ardupilotmega/mavlink_msg_ap_adc.h
@@ -0,0 +1,400 @@
+#pragma once
+// MESSAGE AP_ADC PACKING
+
+#define MAVLINK_MSG_ID_AP_ADC 153
+
+
+typedef struct __mavlink_ap_adc_t {
+ uint16_t adc1; /*< ADC output 1.*/
+ uint16_t adc2; /*< ADC output 2.*/
+ uint16_t adc3; /*< ADC output 3.*/
+ uint16_t adc4; /*< ADC output 4.*/
+ uint16_t adc5; /*< ADC output 5.*/
+ uint16_t adc6; /*< ADC output 6.*/
+} mavlink_ap_adc_t;
+
+#define MAVLINK_MSG_ID_AP_ADC_LEN 12
+#define MAVLINK_MSG_ID_AP_ADC_MIN_LEN 12
+#define MAVLINK_MSG_ID_153_LEN 12
+#define MAVLINK_MSG_ID_153_MIN_LEN 12
+
+#define MAVLINK_MSG_ID_AP_ADC_CRC 188
+#define MAVLINK_MSG_ID_153_CRC 188
+
+
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_AP_ADC { \
+ 153, \
+ "AP_ADC", \
+ 6, \
+ { { "adc1", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_ap_adc_t, adc1) }, \
+ { "adc2", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_ap_adc_t, adc2) }, \
+ { "adc3", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_ap_adc_t, adc3) }, \
+ { "adc4", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_ap_adc_t, adc4) }, \
+ { "adc5", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_ap_adc_t, adc5) }, \
+ { "adc6", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_ap_adc_t, adc6) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_AP_ADC { \
+ "AP_ADC", \
+ 6, \
+ { { "adc1", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_ap_adc_t, adc1) }, \
+ { "adc2", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_ap_adc_t, adc2) }, \
+ { "adc3", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_ap_adc_t, adc3) }, \
+ { "adc4", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_ap_adc_t, adc4) }, \
+ { "adc5", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_ap_adc_t, adc5) }, \
+ { "adc6", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_ap_adc_t, adc6) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a ap_adc 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 adc1 ADC output 1.
+ * @param adc2 ADC output 2.
+ * @param adc3 ADC output 3.
+ * @param adc4 ADC output 4.
+ * @param adc5 ADC output 5.
+ * @param adc6 ADC output 6.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_ap_adc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint16_t adc1, uint16_t adc2, uint16_t adc3, uint16_t adc4, uint16_t adc5, uint16_t adc6)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_AP_ADC_LEN];
+ _mav_put_uint16_t(buf, 0, adc1);
+ _mav_put_uint16_t(buf, 2, adc2);
+ _mav_put_uint16_t(buf, 4, adc3);
+ _mav_put_uint16_t(buf, 6, adc4);
+ _mav_put_uint16_t(buf, 8, adc5);
+ _mav_put_uint16_t(buf, 10, adc6);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AP_ADC_LEN);
+#else
+ mavlink_ap_adc_t packet;
+ packet.adc1 = adc1;
+ packet.adc2 = adc2;
+ packet.adc3 = adc3;
+ packet.adc4 = adc4;
+ packet.adc5 = adc5;
+ packet.adc6 = adc6;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AP_ADC_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_AP_ADC;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_AP_ADC_MIN_LEN, MAVLINK_MSG_ID_AP_ADC_LEN, MAVLINK_MSG_ID_AP_ADC_CRC);
+}
+
+/**
+ * @brief Pack a ap_adc 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 adc1 ADC output 1.
+ * @param adc2 ADC output 2.
+ * @param adc3 ADC output 3.
+ * @param adc4 ADC output 4.
+ * @param adc5 ADC output 5.
+ * @param adc6 ADC output 6.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_ap_adc_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ uint16_t adc1, uint16_t adc2, uint16_t adc3, uint16_t adc4, uint16_t adc5, uint16_t adc6)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_AP_ADC_LEN];
+ _mav_put_uint16_t(buf, 0, adc1);
+ _mav_put_uint16_t(buf, 2, adc2);
+ _mav_put_uint16_t(buf, 4, adc3);
+ _mav_put_uint16_t(buf, 6, adc4);
+ _mav_put_uint16_t(buf, 8, adc5);
+ _mav_put_uint16_t(buf, 10, adc6);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AP_ADC_LEN);
+#else
+ mavlink_ap_adc_t packet;
+ packet.adc1 = adc1;
+ packet.adc2 = adc2;
+ packet.adc3 = adc3;
+ packet.adc4 = adc4;
+ packet.adc5 = adc5;
+ packet.adc6 = adc6;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AP_ADC_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_AP_ADC;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_AP_ADC_MIN_LEN, MAVLINK_MSG_ID_AP_ADC_LEN, MAVLINK_MSG_ID_AP_ADC_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_AP_ADC_MIN_LEN, MAVLINK_MSG_ID_AP_ADC_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a ap_adc 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 adc1 ADC output 1.
+ * @param adc2 ADC output 2.
+ * @param adc3 ADC output 3.
+ * @param adc4 ADC output 4.
+ * @param adc5 ADC output 5.
+ * @param adc6 ADC output 6.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_ap_adc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint16_t adc1,uint16_t adc2,uint16_t adc3,uint16_t adc4,uint16_t adc5,uint16_t adc6)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_AP_ADC_LEN];
+ _mav_put_uint16_t(buf, 0, adc1);
+ _mav_put_uint16_t(buf, 2, adc2);
+ _mav_put_uint16_t(buf, 4, adc3);
+ _mav_put_uint16_t(buf, 6, adc4);
+ _mav_put_uint16_t(buf, 8, adc5);
+ _mav_put_uint16_t(buf, 10, adc6);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AP_ADC_LEN);
+#else
+ mavlink_ap_adc_t packet;
+ packet.adc1 = adc1;
+ packet.adc2 = adc2;
+ packet.adc3 = adc3;
+ packet.adc4 = adc4;
+ packet.adc5 = adc5;
+ packet.adc6 = adc6;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AP_ADC_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_AP_ADC;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_AP_ADC_MIN_LEN, MAVLINK_MSG_ID_AP_ADC_LEN, MAVLINK_MSG_ID_AP_ADC_CRC);
+}
+
+/**
+ * @brief Encode a ap_adc 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 ap_adc C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_ap_adc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_ap_adc_t* ap_adc)
+{
+ return mavlink_msg_ap_adc_pack(system_id, component_id, msg, ap_adc->adc1, ap_adc->adc2, ap_adc->adc3, ap_adc->adc4, ap_adc->adc5, ap_adc->adc6);
+}
+
+/**
+ * @brief Encode a ap_adc 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 ap_adc C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_ap_adc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_ap_adc_t* ap_adc)
+{
+ return mavlink_msg_ap_adc_pack_chan(system_id, component_id, chan, msg, ap_adc->adc1, ap_adc->adc2, ap_adc->adc3, ap_adc->adc4, ap_adc->adc5, ap_adc->adc6);
+}
+
+/**
+ * @brief Encode a ap_adc 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 ap_adc C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_ap_adc_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_ap_adc_t* ap_adc)
+{
+ return mavlink_msg_ap_adc_pack_status(system_id, component_id, _status, msg, ap_adc->adc1, ap_adc->adc2, ap_adc->adc3, ap_adc->adc4, ap_adc->adc5, ap_adc->adc6);
+}
+
+/**
+ * @brief Send a ap_adc message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param adc1 ADC output 1.
+ * @param adc2 ADC output 2.
+ * @param adc3 ADC output 3.
+ * @param adc4 ADC output 4.
+ * @param adc5 ADC output 5.
+ * @param adc6 ADC output 6.
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_ap_adc_send(mavlink_channel_t chan, uint16_t adc1, uint16_t adc2, uint16_t adc3, uint16_t adc4, uint16_t adc5, uint16_t adc6)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_AP_ADC_LEN];
+ _mav_put_uint16_t(buf, 0, adc1);
+ _mav_put_uint16_t(buf, 2, adc2);
+ _mav_put_uint16_t(buf, 4, adc3);
+ _mav_put_uint16_t(buf, 6, adc4);
+ _mav_put_uint16_t(buf, 8, adc5);
+ _mav_put_uint16_t(buf, 10, adc6);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AP_ADC, buf, MAVLINK_MSG_ID_AP_ADC_MIN_LEN, MAVLINK_MSG_ID_AP_ADC_LEN, MAVLINK_MSG_ID_AP_ADC_CRC);
+#else
+ mavlink_ap_adc_t packet;
+ packet.adc1 = adc1;
+ packet.adc2 = adc2;
+ packet.adc3 = adc3;
+ packet.adc4 = adc4;
+ packet.adc5 = adc5;
+ packet.adc6 = adc6;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AP_ADC, (const char *)&packet, MAVLINK_MSG_ID_AP_ADC_MIN_LEN, MAVLINK_MSG_ID_AP_ADC_LEN, MAVLINK_MSG_ID_AP_ADC_CRC);
+#endif
+}
+
+/**
+ * @brief Send a ap_adc message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_ap_adc_send_struct(mavlink_channel_t chan, const mavlink_ap_adc_t* ap_adc)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_ap_adc_send(chan, ap_adc->adc1, ap_adc->adc2, ap_adc->adc3, ap_adc->adc4, ap_adc->adc5, ap_adc->adc6);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AP_ADC, (const char *)ap_adc, MAVLINK_MSG_ID_AP_ADC_MIN_LEN, MAVLINK_MSG_ID_AP_ADC_LEN, MAVLINK_MSG_ID_AP_ADC_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_AP_ADC_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_ap_adc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t adc1, uint16_t adc2, uint16_t adc3, uint16_t adc4, uint16_t adc5, uint16_t adc6)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint16_t(buf, 0, adc1);
+ _mav_put_uint16_t(buf, 2, adc2);
+ _mav_put_uint16_t(buf, 4, adc3);
+ _mav_put_uint16_t(buf, 6, adc4);
+ _mav_put_uint16_t(buf, 8, adc5);
+ _mav_put_uint16_t(buf, 10, adc6);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AP_ADC, buf, MAVLINK_MSG_ID_AP_ADC_MIN_LEN, MAVLINK_MSG_ID_AP_ADC_LEN, MAVLINK_MSG_ID_AP_ADC_CRC);
+#else
+ mavlink_ap_adc_t *packet = (mavlink_ap_adc_t *)msgbuf;
+ packet->adc1 = adc1;
+ packet->adc2 = adc2;
+ packet->adc3 = adc3;
+ packet->adc4 = adc4;
+ packet->adc5 = adc5;
+ packet->adc6 = adc6;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AP_ADC, (const char *)packet, MAVLINK_MSG_ID_AP_ADC_MIN_LEN, MAVLINK_MSG_ID_AP_ADC_LEN, MAVLINK_MSG_ID_AP_ADC_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE AP_ADC UNPACKING
+
+
+/**
+ * @brief Get field adc1 from ap_adc message
+ *
+ * @return ADC output 1.
+ */
+static inline uint16_t mavlink_msg_ap_adc_get_adc1(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 0);
+}
+
+/**
+ * @brief Get field adc2 from ap_adc message
+ *
+ * @return ADC output 2.
+ */
+static inline uint16_t mavlink_msg_ap_adc_get_adc2(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 2);
+}
+
+/**
+ * @brief Get field adc3 from ap_adc message
+ *
+ * @return ADC output 3.
+ */
+static inline uint16_t mavlink_msg_ap_adc_get_adc3(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 4);
+}
+
+/**
+ * @brief Get field adc4 from ap_adc message
+ *
+ * @return ADC output 4.
+ */
+static inline uint16_t mavlink_msg_ap_adc_get_adc4(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 6);
+}
+
+/**
+ * @brief Get field adc5 from ap_adc message
+ *
+ * @return ADC output 5.
+ */
+static inline uint16_t mavlink_msg_ap_adc_get_adc5(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 8);
+}
+
+/**
+ * @brief Get field adc6 from ap_adc message
+ *
+ * @return ADC output 6.
+ */
+static inline uint16_t mavlink_msg_ap_adc_get_adc6(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 10);
+}
+
+/**
+ * @brief Decode a ap_adc message into a struct
+ *
+ * @param msg The message to decode
+ * @param ap_adc C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_ap_adc_decode(const mavlink_message_t* msg, mavlink_ap_adc_t* ap_adc)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ ap_adc->adc1 = mavlink_msg_ap_adc_get_adc1(msg);
+ ap_adc->adc2 = mavlink_msg_ap_adc_get_adc2(msg);
+ ap_adc->adc3 = mavlink_msg_ap_adc_get_adc3(msg);
+ ap_adc->adc4 = mavlink_msg_ap_adc_get_adc4(msg);
+ ap_adc->adc5 = mavlink_msg_ap_adc_get_adc5(msg);
+ ap_adc->adc6 = mavlink_msg_ap_adc_get_adc6(msg);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_AP_ADC_LEN? msg->len : MAVLINK_MSG_ID_AP_ADC_LEN;
+ memset(ap_adc, 0, MAVLINK_MSG_ID_AP_ADC_LEN);
+ memcpy(ap_adc, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/ardupilotmega/mavlink_msg_autopilot_version_request.h b/lib/main/MAVLink/ardupilotmega/mavlink_msg_autopilot_version_request.h
new file mode 100644
index 00000000000..c73f7e4b8f2
--- /dev/null
+++ b/lib/main/MAVLink/ardupilotmega/mavlink_msg_autopilot_version_request.h
@@ -0,0 +1,288 @@
+#pragma once
+// MESSAGE AUTOPILOT_VERSION_REQUEST PACKING
+
+#define MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST 183
+
+
+typedef struct __mavlink_autopilot_version_request_t {
+ uint8_t target_system; /*< System ID.*/
+ uint8_t target_component; /*< Component ID.*/
+} mavlink_autopilot_version_request_t;
+
+#define MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST_LEN 2
+#define MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST_MIN_LEN 2
+#define MAVLINK_MSG_ID_183_LEN 2
+#define MAVLINK_MSG_ID_183_MIN_LEN 2
+
+#define MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST_CRC 85
+#define MAVLINK_MSG_ID_183_CRC 85
+
+
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_AUTOPILOT_VERSION_REQUEST { \
+ 183, \
+ "AUTOPILOT_VERSION_REQUEST", \
+ 2, \
+ { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_autopilot_version_request_t, target_system) }, \
+ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_autopilot_version_request_t, target_component) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_AUTOPILOT_VERSION_REQUEST { \
+ "AUTOPILOT_VERSION_REQUEST", \
+ 2, \
+ { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_autopilot_version_request_t, target_system) }, \
+ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_autopilot_version_request_t, target_component) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a autopilot_version_request 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 target_system System ID.
+ * @param target_component Component ID.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_autopilot_version_request_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint8_t target_system, uint8_t target_component)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST_LEN];
+ _mav_put_uint8_t(buf, 0, target_system);
+ _mav_put_uint8_t(buf, 1, target_component);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST_LEN);
+#else
+ mavlink_autopilot_version_request_t packet;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST_MIN_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST_CRC);
+}
+
+/**
+ * @brief Pack a autopilot_version_request 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 target_system System ID.
+ * @param target_component Component ID.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_autopilot_version_request_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ uint8_t target_system, uint8_t target_component)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST_LEN];
+ _mav_put_uint8_t(buf, 0, target_system);
+ _mav_put_uint8_t(buf, 1, target_component);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST_LEN);
+#else
+ mavlink_autopilot_version_request_t packet;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST_MIN_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST_MIN_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a autopilot_version_request 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 target_system System ID.
+ * @param target_component Component ID.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_autopilot_version_request_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint8_t target_system,uint8_t target_component)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST_LEN];
+ _mav_put_uint8_t(buf, 0, target_system);
+ _mav_put_uint8_t(buf, 1, target_component);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST_LEN);
+#else
+ mavlink_autopilot_version_request_t packet;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST_MIN_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST_CRC);
+}
+
+/**
+ * @brief Encode a autopilot_version_request 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 autopilot_version_request C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_autopilot_version_request_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_autopilot_version_request_t* autopilot_version_request)
+{
+ return mavlink_msg_autopilot_version_request_pack(system_id, component_id, msg, autopilot_version_request->target_system, autopilot_version_request->target_component);
+}
+
+/**
+ * @brief Encode a autopilot_version_request 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 autopilot_version_request C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_autopilot_version_request_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_autopilot_version_request_t* autopilot_version_request)
+{
+ return mavlink_msg_autopilot_version_request_pack_chan(system_id, component_id, chan, msg, autopilot_version_request->target_system, autopilot_version_request->target_component);
+}
+
+/**
+ * @brief Encode a autopilot_version_request 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 autopilot_version_request C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_autopilot_version_request_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_autopilot_version_request_t* autopilot_version_request)
+{
+ return mavlink_msg_autopilot_version_request_pack_status(system_id, component_id, _status, msg, autopilot_version_request->target_system, autopilot_version_request->target_component);
+}
+
+/**
+ * @brief Send a autopilot_version_request message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param target_system System ID.
+ * @param target_component Component ID.
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_autopilot_version_request_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST_LEN];
+ _mav_put_uint8_t(buf, 0, target_system);
+ _mav_put_uint8_t(buf, 1, target_component);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST, buf, MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST_MIN_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST_CRC);
+#else
+ mavlink_autopilot_version_request_t packet;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST, (const char *)&packet, MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST_MIN_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST_CRC);
+#endif
+}
+
+/**
+ * @brief Send a autopilot_version_request message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_autopilot_version_request_send_struct(mavlink_channel_t chan, const mavlink_autopilot_version_request_t* autopilot_version_request)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_autopilot_version_request_send(chan, autopilot_version_request->target_system, autopilot_version_request->target_component);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST, (const char *)autopilot_version_request, MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST_MIN_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_autopilot_version_request_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint8_t(buf, 0, target_system);
+ _mav_put_uint8_t(buf, 1, target_component);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST, buf, MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST_MIN_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST_CRC);
+#else
+ mavlink_autopilot_version_request_t *packet = (mavlink_autopilot_version_request_t *)msgbuf;
+ packet->target_system = target_system;
+ packet->target_component = target_component;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST, (const char *)packet, MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST_MIN_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE AUTOPILOT_VERSION_REQUEST UNPACKING
+
+
+/**
+ * @brief Get field target_system from autopilot_version_request message
+ *
+ * @return System ID.
+ */
+static inline uint8_t mavlink_msg_autopilot_version_request_get_target_system(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 0);
+}
+
+/**
+ * @brief Get field target_component from autopilot_version_request message
+ *
+ * @return Component ID.
+ */
+static inline uint8_t mavlink_msg_autopilot_version_request_get_target_component(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 1);
+}
+
+/**
+ * @brief Decode a autopilot_version_request message into a struct
+ *
+ * @param msg The message to decode
+ * @param autopilot_version_request C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_autopilot_version_request_decode(const mavlink_message_t* msg, mavlink_autopilot_version_request_t* autopilot_version_request)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ autopilot_version_request->target_system = mavlink_msg_autopilot_version_request_get_target_system(msg);
+ autopilot_version_request->target_component = mavlink_msg_autopilot_version_request_get_target_component(msg);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST_LEN? msg->len : MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST_LEN;
+ memset(autopilot_version_request, 0, MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST_LEN);
+ memcpy(autopilot_version_request, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/ardupilotmega/mavlink_msg_battery2.h b/lib/main/MAVLink/ardupilotmega/mavlink_msg_battery2.h
new file mode 100644
index 00000000000..598a27a2dd6
--- /dev/null
+++ b/lib/main/MAVLink/ardupilotmega/mavlink_msg_battery2.h
@@ -0,0 +1,288 @@
+#pragma once
+// MESSAGE BATTERY2 PACKING
+
+#define MAVLINK_MSG_ID_BATTERY2 181
+
+
+typedef struct __mavlink_battery2_t {
+ uint16_t voltage; /*< [mV] Voltage.*/
+ int16_t current_battery; /*< [cA] Battery current, -1: autopilot does not measure the current.*/
+} mavlink_battery2_t;
+
+#define MAVLINK_MSG_ID_BATTERY2_LEN 4
+#define MAVLINK_MSG_ID_BATTERY2_MIN_LEN 4
+#define MAVLINK_MSG_ID_181_LEN 4
+#define MAVLINK_MSG_ID_181_MIN_LEN 4
+
+#define MAVLINK_MSG_ID_BATTERY2_CRC 174
+#define MAVLINK_MSG_ID_181_CRC 174
+
+
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_BATTERY2 { \
+ 181, \
+ "BATTERY2", \
+ 2, \
+ { { "voltage", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_battery2_t, voltage) }, \
+ { "current_battery", NULL, MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_battery2_t, current_battery) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_BATTERY2 { \
+ "BATTERY2", \
+ 2, \
+ { { "voltage", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_battery2_t, voltage) }, \
+ { "current_battery", NULL, MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_battery2_t, current_battery) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a battery2 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 voltage [mV] Voltage.
+ * @param current_battery [cA] Battery current, -1: autopilot does not measure the current.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_battery2_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint16_t voltage, int16_t current_battery)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_BATTERY2_LEN];
+ _mav_put_uint16_t(buf, 0, voltage);
+ _mav_put_int16_t(buf, 2, current_battery);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_BATTERY2_LEN);
+#else
+ mavlink_battery2_t packet;
+ packet.voltage = voltage;
+ packet.current_battery = current_battery;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_BATTERY2_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_BATTERY2;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_BATTERY2_MIN_LEN, MAVLINK_MSG_ID_BATTERY2_LEN, MAVLINK_MSG_ID_BATTERY2_CRC);
+}
+
+/**
+ * @brief Pack a battery2 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 voltage [mV] Voltage.
+ * @param current_battery [cA] Battery current, -1: autopilot does not measure the current.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_battery2_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ uint16_t voltage, int16_t current_battery)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_BATTERY2_LEN];
+ _mav_put_uint16_t(buf, 0, voltage);
+ _mav_put_int16_t(buf, 2, current_battery);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_BATTERY2_LEN);
+#else
+ mavlink_battery2_t packet;
+ packet.voltage = voltage;
+ packet.current_battery = current_battery;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_BATTERY2_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_BATTERY2;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_BATTERY2_MIN_LEN, MAVLINK_MSG_ID_BATTERY2_LEN, MAVLINK_MSG_ID_BATTERY2_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_BATTERY2_MIN_LEN, MAVLINK_MSG_ID_BATTERY2_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a battery2 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 voltage [mV] Voltage.
+ * @param current_battery [cA] Battery current, -1: autopilot does not measure the current.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_battery2_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint16_t voltage,int16_t current_battery)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_BATTERY2_LEN];
+ _mav_put_uint16_t(buf, 0, voltage);
+ _mav_put_int16_t(buf, 2, current_battery);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_BATTERY2_LEN);
+#else
+ mavlink_battery2_t packet;
+ packet.voltage = voltage;
+ packet.current_battery = current_battery;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_BATTERY2_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_BATTERY2;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_BATTERY2_MIN_LEN, MAVLINK_MSG_ID_BATTERY2_LEN, MAVLINK_MSG_ID_BATTERY2_CRC);
+}
+
+/**
+ * @brief Encode a battery2 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 battery2 C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_battery2_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_battery2_t* battery2)
+{
+ return mavlink_msg_battery2_pack(system_id, component_id, msg, battery2->voltage, battery2->current_battery);
+}
+
+/**
+ * @brief Encode a battery2 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 battery2 C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_battery2_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_battery2_t* battery2)
+{
+ return mavlink_msg_battery2_pack_chan(system_id, component_id, chan, msg, battery2->voltage, battery2->current_battery);
+}
+
+/**
+ * @brief Encode a battery2 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 battery2 C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_battery2_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_battery2_t* battery2)
+{
+ return mavlink_msg_battery2_pack_status(system_id, component_id, _status, msg, battery2->voltage, battery2->current_battery);
+}
+
+/**
+ * @brief Send a battery2 message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param voltage [mV] Voltage.
+ * @param current_battery [cA] Battery current, -1: autopilot does not measure the current.
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_battery2_send(mavlink_channel_t chan, uint16_t voltage, int16_t current_battery)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_BATTERY2_LEN];
+ _mav_put_uint16_t(buf, 0, voltage);
+ _mav_put_int16_t(buf, 2, current_battery);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY2, buf, MAVLINK_MSG_ID_BATTERY2_MIN_LEN, MAVLINK_MSG_ID_BATTERY2_LEN, MAVLINK_MSG_ID_BATTERY2_CRC);
+#else
+ mavlink_battery2_t packet;
+ packet.voltage = voltage;
+ packet.current_battery = current_battery;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY2, (const char *)&packet, MAVLINK_MSG_ID_BATTERY2_MIN_LEN, MAVLINK_MSG_ID_BATTERY2_LEN, MAVLINK_MSG_ID_BATTERY2_CRC);
+#endif
+}
+
+/**
+ * @brief Send a battery2 message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_battery2_send_struct(mavlink_channel_t chan, const mavlink_battery2_t* battery2)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_battery2_send(chan, battery2->voltage, battery2->current_battery);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY2, (const char *)battery2, MAVLINK_MSG_ID_BATTERY2_MIN_LEN, MAVLINK_MSG_ID_BATTERY2_LEN, MAVLINK_MSG_ID_BATTERY2_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_BATTERY2_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_battery2_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t voltage, int16_t current_battery)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint16_t(buf, 0, voltage);
+ _mav_put_int16_t(buf, 2, current_battery);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY2, buf, MAVLINK_MSG_ID_BATTERY2_MIN_LEN, MAVLINK_MSG_ID_BATTERY2_LEN, MAVLINK_MSG_ID_BATTERY2_CRC);
+#else
+ mavlink_battery2_t *packet = (mavlink_battery2_t *)msgbuf;
+ packet->voltage = voltage;
+ packet->current_battery = current_battery;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY2, (const char *)packet, MAVLINK_MSG_ID_BATTERY2_MIN_LEN, MAVLINK_MSG_ID_BATTERY2_LEN, MAVLINK_MSG_ID_BATTERY2_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE BATTERY2 UNPACKING
+
+
+/**
+ * @brief Get field voltage from battery2 message
+ *
+ * @return [mV] Voltage.
+ */
+static inline uint16_t mavlink_msg_battery2_get_voltage(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 0);
+}
+
+/**
+ * @brief Get field current_battery from battery2 message
+ *
+ * @return [cA] Battery current, -1: autopilot does not measure the current.
+ */
+static inline int16_t mavlink_msg_battery2_get_current_battery(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_int16_t(msg, 2);
+}
+
+/**
+ * @brief Decode a battery2 message into a struct
+ *
+ * @param msg The message to decode
+ * @param battery2 C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_battery2_decode(const mavlink_message_t* msg, mavlink_battery2_t* battery2)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ battery2->voltage = mavlink_msg_battery2_get_voltage(msg);
+ battery2->current_battery = mavlink_msg_battery2_get_current_battery(msg);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_BATTERY2_LEN? msg->len : MAVLINK_MSG_ID_BATTERY2_LEN;
+ memset(battery2, 0, MAVLINK_MSG_ID_BATTERY2_LEN);
+ memcpy(battery2, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/ardupilotmega/mavlink_msg_camera_feedback.h b/lib/main/MAVLink/ardupilotmega/mavlink_msg_camera_feedback.h
new file mode 100644
index 00000000000..04711385e66
--- /dev/null
+++ b/lib/main/MAVLink/ardupilotmega/mavlink_msg_camera_feedback.h
@@ -0,0 +1,624 @@
+#pragma once
+// MESSAGE CAMERA_FEEDBACK PACKING
+
+#define MAVLINK_MSG_ID_CAMERA_FEEDBACK 180
+
+MAVPACKED(
+typedef struct __mavlink_camera_feedback_t {
+ uint64_t time_usec; /*< [us] Image timestamp (since UNIX epoch), as passed in by CAMERA_STATUS message (or autopilot if no CCB).*/
+ int32_t lat; /*< [degE7] Latitude.*/
+ int32_t lng; /*< [degE7] Longitude.*/
+ float alt_msl; /*< [m] Altitude (MSL).*/
+ float alt_rel; /*< [m] Altitude (Relative to HOME location).*/
+ float roll; /*< [deg] Camera Roll angle (earth frame, +-180).*/
+ float pitch; /*< [deg] Camera Pitch angle (earth frame, +-180).*/
+ float yaw; /*< [deg] Camera Yaw (earth frame, 0-360, true).*/
+ float foc_len; /*< [mm] Focal Length.*/
+ uint16_t img_idx; /*< Image index.*/
+ uint8_t target_system; /*< System ID.*/
+ uint8_t cam_idx; /*< Camera ID.*/
+ uint8_t flags; /*< Feedback flags.*/
+ uint16_t completed_captures; /*< Completed image captures.*/
+}) mavlink_camera_feedback_t;
+
+#define MAVLINK_MSG_ID_CAMERA_FEEDBACK_LEN 47
+#define MAVLINK_MSG_ID_CAMERA_FEEDBACK_MIN_LEN 45
+#define MAVLINK_MSG_ID_180_LEN 47
+#define MAVLINK_MSG_ID_180_MIN_LEN 45
+
+#define MAVLINK_MSG_ID_CAMERA_FEEDBACK_CRC 52
+#define MAVLINK_MSG_ID_180_CRC 52
+
+
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_CAMERA_FEEDBACK { \
+ 180, \
+ "CAMERA_FEEDBACK", \
+ 14, \
+ { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_camera_feedback_t, time_usec) }, \
+ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_camera_feedback_t, target_system) }, \
+ { "cam_idx", NULL, MAVLINK_TYPE_UINT8_T, 0, 43, offsetof(mavlink_camera_feedback_t, cam_idx) }, \
+ { "img_idx", NULL, MAVLINK_TYPE_UINT16_T, 0, 40, offsetof(mavlink_camera_feedback_t, img_idx) }, \
+ { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_camera_feedback_t, lat) }, \
+ { "lng", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_camera_feedback_t, lng) }, \
+ { "alt_msl", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_camera_feedback_t, alt_msl) }, \
+ { "alt_rel", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_camera_feedback_t, alt_rel) }, \
+ { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_camera_feedback_t, roll) }, \
+ { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_camera_feedback_t, pitch) }, \
+ { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_camera_feedback_t, yaw) }, \
+ { "foc_len", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_camera_feedback_t, foc_len) }, \
+ { "flags", NULL, MAVLINK_TYPE_UINT8_T, 0, 44, offsetof(mavlink_camera_feedback_t, flags) }, \
+ { "completed_captures", NULL, MAVLINK_TYPE_UINT16_T, 0, 45, offsetof(mavlink_camera_feedback_t, completed_captures) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_CAMERA_FEEDBACK { \
+ "CAMERA_FEEDBACK", \
+ 14, \
+ { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_camera_feedback_t, time_usec) }, \
+ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_camera_feedback_t, target_system) }, \
+ { "cam_idx", NULL, MAVLINK_TYPE_UINT8_T, 0, 43, offsetof(mavlink_camera_feedback_t, cam_idx) }, \
+ { "img_idx", NULL, MAVLINK_TYPE_UINT16_T, 0, 40, offsetof(mavlink_camera_feedback_t, img_idx) }, \
+ { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_camera_feedback_t, lat) }, \
+ { "lng", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_camera_feedback_t, lng) }, \
+ { "alt_msl", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_camera_feedback_t, alt_msl) }, \
+ { "alt_rel", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_camera_feedback_t, alt_rel) }, \
+ { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_camera_feedback_t, roll) }, \
+ { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_camera_feedback_t, pitch) }, \
+ { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_camera_feedback_t, yaw) }, \
+ { "foc_len", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_camera_feedback_t, foc_len) }, \
+ { "flags", NULL, MAVLINK_TYPE_UINT8_T, 0, 44, offsetof(mavlink_camera_feedback_t, flags) }, \
+ { "completed_captures", NULL, MAVLINK_TYPE_UINT16_T, 0, 45, offsetof(mavlink_camera_feedback_t, completed_captures) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a camera_feedback 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 time_usec [us] Image timestamp (since UNIX epoch), as passed in by CAMERA_STATUS message (or autopilot if no CCB).
+ * @param target_system System ID.
+ * @param cam_idx Camera ID.
+ * @param img_idx Image index.
+ * @param lat [degE7] Latitude.
+ * @param lng [degE7] Longitude.
+ * @param alt_msl [m] Altitude (MSL).
+ * @param alt_rel [m] Altitude (Relative to HOME location).
+ * @param roll [deg] Camera Roll angle (earth frame, +-180).
+ * @param pitch [deg] Camera Pitch angle (earth frame, +-180).
+ * @param yaw [deg] Camera Yaw (earth frame, 0-360, true).
+ * @param foc_len [mm] Focal Length.
+ * @param flags Feedback flags.
+ * @param completed_captures Completed image captures.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_camera_feedback_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint64_t time_usec, uint8_t target_system, uint8_t cam_idx, uint16_t img_idx, int32_t lat, int32_t lng, float alt_msl, float alt_rel, float roll, float pitch, float yaw, float foc_len, uint8_t flags, uint16_t completed_captures)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_CAMERA_FEEDBACK_LEN];
+ _mav_put_uint64_t(buf, 0, time_usec);
+ _mav_put_int32_t(buf, 8, lat);
+ _mav_put_int32_t(buf, 12, lng);
+ _mav_put_float(buf, 16, alt_msl);
+ _mav_put_float(buf, 20, alt_rel);
+ _mav_put_float(buf, 24, roll);
+ _mav_put_float(buf, 28, pitch);
+ _mav_put_float(buf, 32, yaw);
+ _mav_put_float(buf, 36, foc_len);
+ _mav_put_uint16_t(buf, 40, img_idx);
+ _mav_put_uint8_t(buf, 42, target_system);
+ _mav_put_uint8_t(buf, 43, cam_idx);
+ _mav_put_uint8_t(buf, 44, flags);
+ _mav_put_uint16_t(buf, 45, completed_captures);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CAMERA_FEEDBACK_LEN);
+#else
+ mavlink_camera_feedback_t packet;
+ packet.time_usec = time_usec;
+ packet.lat = lat;
+ packet.lng = lng;
+ packet.alt_msl = alt_msl;
+ packet.alt_rel = alt_rel;
+ packet.roll = roll;
+ packet.pitch = pitch;
+ packet.yaw = yaw;
+ packet.foc_len = foc_len;
+ packet.img_idx = img_idx;
+ packet.target_system = target_system;
+ packet.cam_idx = cam_idx;
+ packet.flags = flags;
+ packet.completed_captures = completed_captures;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CAMERA_FEEDBACK_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_CAMERA_FEEDBACK;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CAMERA_FEEDBACK_MIN_LEN, MAVLINK_MSG_ID_CAMERA_FEEDBACK_LEN, MAVLINK_MSG_ID_CAMERA_FEEDBACK_CRC);
+}
+
+/**
+ * @brief Pack a camera_feedback 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 time_usec [us] Image timestamp (since UNIX epoch), as passed in by CAMERA_STATUS message (or autopilot if no CCB).
+ * @param target_system System ID.
+ * @param cam_idx Camera ID.
+ * @param img_idx Image index.
+ * @param lat [degE7] Latitude.
+ * @param lng [degE7] Longitude.
+ * @param alt_msl [m] Altitude (MSL).
+ * @param alt_rel [m] Altitude (Relative to HOME location).
+ * @param roll [deg] Camera Roll angle (earth frame, +-180).
+ * @param pitch [deg] Camera Pitch angle (earth frame, +-180).
+ * @param yaw [deg] Camera Yaw (earth frame, 0-360, true).
+ * @param foc_len [mm] Focal Length.
+ * @param flags Feedback flags.
+ * @param completed_captures Completed image captures.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_camera_feedback_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ uint64_t time_usec, uint8_t target_system, uint8_t cam_idx, uint16_t img_idx, int32_t lat, int32_t lng, float alt_msl, float alt_rel, float roll, float pitch, float yaw, float foc_len, uint8_t flags, uint16_t completed_captures)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_CAMERA_FEEDBACK_LEN];
+ _mav_put_uint64_t(buf, 0, time_usec);
+ _mav_put_int32_t(buf, 8, lat);
+ _mav_put_int32_t(buf, 12, lng);
+ _mav_put_float(buf, 16, alt_msl);
+ _mav_put_float(buf, 20, alt_rel);
+ _mav_put_float(buf, 24, roll);
+ _mav_put_float(buf, 28, pitch);
+ _mav_put_float(buf, 32, yaw);
+ _mav_put_float(buf, 36, foc_len);
+ _mav_put_uint16_t(buf, 40, img_idx);
+ _mav_put_uint8_t(buf, 42, target_system);
+ _mav_put_uint8_t(buf, 43, cam_idx);
+ _mav_put_uint8_t(buf, 44, flags);
+ _mav_put_uint16_t(buf, 45, completed_captures);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CAMERA_FEEDBACK_LEN);
+#else
+ mavlink_camera_feedback_t packet;
+ packet.time_usec = time_usec;
+ packet.lat = lat;
+ packet.lng = lng;
+ packet.alt_msl = alt_msl;
+ packet.alt_rel = alt_rel;
+ packet.roll = roll;
+ packet.pitch = pitch;
+ packet.yaw = yaw;
+ packet.foc_len = foc_len;
+ packet.img_idx = img_idx;
+ packet.target_system = target_system;
+ packet.cam_idx = cam_idx;
+ packet.flags = flags;
+ packet.completed_captures = completed_captures;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CAMERA_FEEDBACK_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_CAMERA_FEEDBACK;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_CAMERA_FEEDBACK_MIN_LEN, MAVLINK_MSG_ID_CAMERA_FEEDBACK_LEN, MAVLINK_MSG_ID_CAMERA_FEEDBACK_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_CAMERA_FEEDBACK_MIN_LEN, MAVLINK_MSG_ID_CAMERA_FEEDBACK_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a camera_feedback 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 time_usec [us] Image timestamp (since UNIX epoch), as passed in by CAMERA_STATUS message (or autopilot if no CCB).
+ * @param target_system System ID.
+ * @param cam_idx Camera ID.
+ * @param img_idx Image index.
+ * @param lat [degE7] Latitude.
+ * @param lng [degE7] Longitude.
+ * @param alt_msl [m] Altitude (MSL).
+ * @param alt_rel [m] Altitude (Relative to HOME location).
+ * @param roll [deg] Camera Roll angle (earth frame, +-180).
+ * @param pitch [deg] Camera Pitch angle (earth frame, +-180).
+ * @param yaw [deg] Camera Yaw (earth frame, 0-360, true).
+ * @param foc_len [mm] Focal Length.
+ * @param flags Feedback flags.
+ * @param completed_captures Completed image captures.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_camera_feedback_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint64_t time_usec,uint8_t target_system,uint8_t cam_idx,uint16_t img_idx,int32_t lat,int32_t lng,float alt_msl,float alt_rel,float roll,float pitch,float yaw,float foc_len,uint8_t flags,uint16_t completed_captures)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_CAMERA_FEEDBACK_LEN];
+ _mav_put_uint64_t(buf, 0, time_usec);
+ _mav_put_int32_t(buf, 8, lat);
+ _mav_put_int32_t(buf, 12, lng);
+ _mav_put_float(buf, 16, alt_msl);
+ _mav_put_float(buf, 20, alt_rel);
+ _mav_put_float(buf, 24, roll);
+ _mav_put_float(buf, 28, pitch);
+ _mav_put_float(buf, 32, yaw);
+ _mav_put_float(buf, 36, foc_len);
+ _mav_put_uint16_t(buf, 40, img_idx);
+ _mav_put_uint8_t(buf, 42, target_system);
+ _mav_put_uint8_t(buf, 43, cam_idx);
+ _mav_put_uint8_t(buf, 44, flags);
+ _mav_put_uint16_t(buf, 45, completed_captures);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CAMERA_FEEDBACK_LEN);
+#else
+ mavlink_camera_feedback_t packet;
+ packet.time_usec = time_usec;
+ packet.lat = lat;
+ packet.lng = lng;
+ packet.alt_msl = alt_msl;
+ packet.alt_rel = alt_rel;
+ packet.roll = roll;
+ packet.pitch = pitch;
+ packet.yaw = yaw;
+ packet.foc_len = foc_len;
+ packet.img_idx = img_idx;
+ packet.target_system = target_system;
+ packet.cam_idx = cam_idx;
+ packet.flags = flags;
+ packet.completed_captures = completed_captures;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CAMERA_FEEDBACK_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_CAMERA_FEEDBACK;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CAMERA_FEEDBACK_MIN_LEN, MAVLINK_MSG_ID_CAMERA_FEEDBACK_LEN, MAVLINK_MSG_ID_CAMERA_FEEDBACK_CRC);
+}
+
+/**
+ * @brief Encode a camera_feedback 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 camera_feedback C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_camera_feedback_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_camera_feedback_t* camera_feedback)
+{
+ return mavlink_msg_camera_feedback_pack(system_id, component_id, msg, camera_feedback->time_usec, camera_feedback->target_system, camera_feedback->cam_idx, camera_feedback->img_idx, camera_feedback->lat, camera_feedback->lng, camera_feedback->alt_msl, camera_feedback->alt_rel, camera_feedback->roll, camera_feedback->pitch, camera_feedback->yaw, camera_feedback->foc_len, camera_feedback->flags, camera_feedback->completed_captures);
+}
+
+/**
+ * @brief Encode a camera_feedback 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 camera_feedback C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_camera_feedback_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_camera_feedback_t* camera_feedback)
+{
+ return mavlink_msg_camera_feedback_pack_chan(system_id, component_id, chan, msg, camera_feedback->time_usec, camera_feedback->target_system, camera_feedback->cam_idx, camera_feedback->img_idx, camera_feedback->lat, camera_feedback->lng, camera_feedback->alt_msl, camera_feedback->alt_rel, camera_feedback->roll, camera_feedback->pitch, camera_feedback->yaw, camera_feedback->foc_len, camera_feedback->flags, camera_feedback->completed_captures);
+}
+
+/**
+ * @brief Encode a camera_feedback 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 camera_feedback C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_camera_feedback_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_camera_feedback_t* camera_feedback)
+{
+ return mavlink_msg_camera_feedback_pack_status(system_id, component_id, _status, msg, camera_feedback->time_usec, camera_feedback->target_system, camera_feedback->cam_idx, camera_feedback->img_idx, camera_feedback->lat, camera_feedback->lng, camera_feedback->alt_msl, camera_feedback->alt_rel, camera_feedback->roll, camera_feedback->pitch, camera_feedback->yaw, camera_feedback->foc_len, camera_feedback->flags, camera_feedback->completed_captures);
+}
+
+/**
+ * @brief Send a camera_feedback message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param time_usec [us] Image timestamp (since UNIX epoch), as passed in by CAMERA_STATUS message (or autopilot if no CCB).
+ * @param target_system System ID.
+ * @param cam_idx Camera ID.
+ * @param img_idx Image index.
+ * @param lat [degE7] Latitude.
+ * @param lng [degE7] Longitude.
+ * @param alt_msl [m] Altitude (MSL).
+ * @param alt_rel [m] Altitude (Relative to HOME location).
+ * @param roll [deg] Camera Roll angle (earth frame, +-180).
+ * @param pitch [deg] Camera Pitch angle (earth frame, +-180).
+ * @param yaw [deg] Camera Yaw (earth frame, 0-360, true).
+ * @param foc_len [mm] Focal Length.
+ * @param flags Feedback flags.
+ * @param completed_captures Completed image captures.
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_camera_feedback_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t target_system, uint8_t cam_idx, uint16_t img_idx, int32_t lat, int32_t lng, float alt_msl, float alt_rel, float roll, float pitch, float yaw, float foc_len, uint8_t flags, uint16_t completed_captures)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_CAMERA_FEEDBACK_LEN];
+ _mav_put_uint64_t(buf, 0, time_usec);
+ _mav_put_int32_t(buf, 8, lat);
+ _mav_put_int32_t(buf, 12, lng);
+ _mav_put_float(buf, 16, alt_msl);
+ _mav_put_float(buf, 20, alt_rel);
+ _mav_put_float(buf, 24, roll);
+ _mav_put_float(buf, 28, pitch);
+ _mav_put_float(buf, 32, yaw);
+ _mav_put_float(buf, 36, foc_len);
+ _mav_put_uint16_t(buf, 40, img_idx);
+ _mav_put_uint8_t(buf, 42, target_system);
+ _mav_put_uint8_t(buf, 43, cam_idx);
+ _mav_put_uint8_t(buf, 44, flags);
+ _mav_put_uint16_t(buf, 45, completed_captures);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_FEEDBACK, buf, MAVLINK_MSG_ID_CAMERA_FEEDBACK_MIN_LEN, MAVLINK_MSG_ID_CAMERA_FEEDBACK_LEN, MAVLINK_MSG_ID_CAMERA_FEEDBACK_CRC);
+#else
+ mavlink_camera_feedback_t packet;
+ packet.time_usec = time_usec;
+ packet.lat = lat;
+ packet.lng = lng;
+ packet.alt_msl = alt_msl;
+ packet.alt_rel = alt_rel;
+ packet.roll = roll;
+ packet.pitch = pitch;
+ packet.yaw = yaw;
+ packet.foc_len = foc_len;
+ packet.img_idx = img_idx;
+ packet.target_system = target_system;
+ packet.cam_idx = cam_idx;
+ packet.flags = flags;
+ packet.completed_captures = completed_captures;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_FEEDBACK, (const char *)&packet, MAVLINK_MSG_ID_CAMERA_FEEDBACK_MIN_LEN, MAVLINK_MSG_ID_CAMERA_FEEDBACK_LEN, MAVLINK_MSG_ID_CAMERA_FEEDBACK_CRC);
+#endif
+}
+
+/**
+ * @brief Send a camera_feedback message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_camera_feedback_send_struct(mavlink_channel_t chan, const mavlink_camera_feedback_t* camera_feedback)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_camera_feedback_send(chan, camera_feedback->time_usec, camera_feedback->target_system, camera_feedback->cam_idx, camera_feedback->img_idx, camera_feedback->lat, camera_feedback->lng, camera_feedback->alt_msl, camera_feedback->alt_rel, camera_feedback->roll, camera_feedback->pitch, camera_feedback->yaw, camera_feedback->foc_len, camera_feedback->flags, camera_feedback->completed_captures);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_FEEDBACK, (const char *)camera_feedback, MAVLINK_MSG_ID_CAMERA_FEEDBACK_MIN_LEN, MAVLINK_MSG_ID_CAMERA_FEEDBACK_LEN, MAVLINK_MSG_ID_CAMERA_FEEDBACK_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_CAMERA_FEEDBACK_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_camera_feedback_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t target_system, uint8_t cam_idx, uint16_t img_idx, int32_t lat, int32_t lng, float alt_msl, float alt_rel, float roll, float pitch, float yaw, float foc_len, uint8_t flags, uint16_t completed_captures)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint64_t(buf, 0, time_usec);
+ _mav_put_int32_t(buf, 8, lat);
+ _mav_put_int32_t(buf, 12, lng);
+ _mav_put_float(buf, 16, alt_msl);
+ _mav_put_float(buf, 20, alt_rel);
+ _mav_put_float(buf, 24, roll);
+ _mav_put_float(buf, 28, pitch);
+ _mav_put_float(buf, 32, yaw);
+ _mav_put_float(buf, 36, foc_len);
+ _mav_put_uint16_t(buf, 40, img_idx);
+ _mav_put_uint8_t(buf, 42, target_system);
+ _mav_put_uint8_t(buf, 43, cam_idx);
+ _mav_put_uint8_t(buf, 44, flags);
+ _mav_put_uint16_t(buf, 45, completed_captures);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_FEEDBACK, buf, MAVLINK_MSG_ID_CAMERA_FEEDBACK_MIN_LEN, MAVLINK_MSG_ID_CAMERA_FEEDBACK_LEN, MAVLINK_MSG_ID_CAMERA_FEEDBACK_CRC);
+#else
+ mavlink_camera_feedback_t *packet = (mavlink_camera_feedback_t *)msgbuf;
+ packet->time_usec = time_usec;
+ packet->lat = lat;
+ packet->lng = lng;
+ packet->alt_msl = alt_msl;
+ packet->alt_rel = alt_rel;
+ packet->roll = roll;
+ packet->pitch = pitch;
+ packet->yaw = yaw;
+ packet->foc_len = foc_len;
+ packet->img_idx = img_idx;
+ packet->target_system = target_system;
+ packet->cam_idx = cam_idx;
+ packet->flags = flags;
+ packet->completed_captures = completed_captures;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_FEEDBACK, (const char *)packet, MAVLINK_MSG_ID_CAMERA_FEEDBACK_MIN_LEN, MAVLINK_MSG_ID_CAMERA_FEEDBACK_LEN, MAVLINK_MSG_ID_CAMERA_FEEDBACK_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE CAMERA_FEEDBACK UNPACKING
+
+
+/**
+ * @brief Get field time_usec from camera_feedback message
+ *
+ * @return [us] Image timestamp (since UNIX epoch), as passed in by CAMERA_STATUS message (or autopilot if no CCB).
+ */
+static inline uint64_t mavlink_msg_camera_feedback_get_time_usec(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint64_t(msg, 0);
+}
+
+/**
+ * @brief Get field target_system from camera_feedback message
+ *
+ * @return System ID.
+ */
+static inline uint8_t mavlink_msg_camera_feedback_get_target_system(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 42);
+}
+
+/**
+ * @brief Get field cam_idx from camera_feedback message
+ *
+ * @return Camera ID.
+ */
+static inline uint8_t mavlink_msg_camera_feedback_get_cam_idx(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 43);
+}
+
+/**
+ * @brief Get field img_idx from camera_feedback message
+ *
+ * @return Image index.
+ */
+static inline uint16_t mavlink_msg_camera_feedback_get_img_idx(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 40);
+}
+
+/**
+ * @brief Get field lat from camera_feedback message
+ *
+ * @return [degE7] Latitude.
+ */
+static inline int32_t mavlink_msg_camera_feedback_get_lat(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_int32_t(msg, 8);
+}
+
+/**
+ * @brief Get field lng from camera_feedback message
+ *
+ * @return [degE7] Longitude.
+ */
+static inline int32_t mavlink_msg_camera_feedback_get_lng(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_int32_t(msg, 12);
+}
+
+/**
+ * @brief Get field alt_msl from camera_feedback message
+ *
+ * @return [m] Altitude (MSL).
+ */
+static inline float mavlink_msg_camera_feedback_get_alt_msl(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 16);
+}
+
+/**
+ * @brief Get field alt_rel from camera_feedback message
+ *
+ * @return [m] Altitude (Relative to HOME location).
+ */
+static inline float mavlink_msg_camera_feedback_get_alt_rel(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 20);
+}
+
+/**
+ * @brief Get field roll from camera_feedback message
+ *
+ * @return [deg] Camera Roll angle (earth frame, +-180).
+ */
+static inline float mavlink_msg_camera_feedback_get_roll(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 24);
+}
+
+/**
+ * @brief Get field pitch from camera_feedback message
+ *
+ * @return [deg] Camera Pitch angle (earth frame, +-180).
+ */
+static inline float mavlink_msg_camera_feedback_get_pitch(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 28);
+}
+
+/**
+ * @brief Get field yaw from camera_feedback message
+ *
+ * @return [deg] Camera Yaw (earth frame, 0-360, true).
+ */
+static inline float mavlink_msg_camera_feedback_get_yaw(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 32);
+}
+
+/**
+ * @brief Get field foc_len from camera_feedback message
+ *
+ * @return [mm] Focal Length.
+ */
+static inline float mavlink_msg_camera_feedback_get_foc_len(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 36);
+}
+
+/**
+ * @brief Get field flags from camera_feedback message
+ *
+ * @return Feedback flags.
+ */
+static inline uint8_t mavlink_msg_camera_feedback_get_flags(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 44);
+}
+
+/**
+ * @brief Get field completed_captures from camera_feedback message
+ *
+ * @return Completed image captures.
+ */
+static inline uint16_t mavlink_msg_camera_feedback_get_completed_captures(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 45);
+}
+
+/**
+ * @brief Decode a camera_feedback message into a struct
+ *
+ * @param msg The message to decode
+ * @param camera_feedback C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_camera_feedback_decode(const mavlink_message_t* msg, mavlink_camera_feedback_t* camera_feedback)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ camera_feedback->time_usec = mavlink_msg_camera_feedback_get_time_usec(msg);
+ camera_feedback->lat = mavlink_msg_camera_feedback_get_lat(msg);
+ camera_feedback->lng = mavlink_msg_camera_feedback_get_lng(msg);
+ camera_feedback->alt_msl = mavlink_msg_camera_feedback_get_alt_msl(msg);
+ camera_feedback->alt_rel = mavlink_msg_camera_feedback_get_alt_rel(msg);
+ camera_feedback->roll = mavlink_msg_camera_feedback_get_roll(msg);
+ camera_feedback->pitch = mavlink_msg_camera_feedback_get_pitch(msg);
+ camera_feedback->yaw = mavlink_msg_camera_feedback_get_yaw(msg);
+ camera_feedback->foc_len = mavlink_msg_camera_feedback_get_foc_len(msg);
+ camera_feedback->img_idx = mavlink_msg_camera_feedback_get_img_idx(msg);
+ camera_feedback->target_system = mavlink_msg_camera_feedback_get_target_system(msg);
+ camera_feedback->cam_idx = mavlink_msg_camera_feedback_get_cam_idx(msg);
+ camera_feedback->flags = mavlink_msg_camera_feedback_get_flags(msg);
+ camera_feedback->completed_captures = mavlink_msg_camera_feedback_get_completed_captures(msg);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_CAMERA_FEEDBACK_LEN? msg->len : MAVLINK_MSG_ID_CAMERA_FEEDBACK_LEN;
+ memset(camera_feedback, 0, MAVLINK_MSG_ID_CAMERA_FEEDBACK_LEN);
+ memcpy(camera_feedback, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/ardupilotmega/mavlink_msg_camera_status.h b/lib/main/MAVLink/ardupilotmega/mavlink_msg_camera_status.h
new file mode 100644
index 00000000000..e31f3af650b
--- /dev/null
+++ b/lib/main/MAVLink/ardupilotmega/mavlink_msg_camera_status.h
@@ -0,0 +1,484 @@
+#pragma once
+// MESSAGE CAMERA_STATUS PACKING
+
+#define MAVLINK_MSG_ID_CAMERA_STATUS 179
+
+
+typedef struct __mavlink_camera_status_t {
+ uint64_t time_usec; /*< [us] Image timestamp (since UNIX epoch, according to camera clock).*/
+ float p1; /*< Parameter 1 (meaning depends on event_id, see CAMERA_STATUS_TYPES enum).*/
+ float p2; /*< Parameter 2 (meaning depends on event_id, see CAMERA_STATUS_TYPES enum).*/
+ float p3; /*< Parameter 3 (meaning depends on event_id, see CAMERA_STATUS_TYPES enum).*/
+ float p4; /*< Parameter 4 (meaning depends on event_id, see CAMERA_STATUS_TYPES enum).*/
+ uint16_t img_idx; /*< Image index.*/
+ uint8_t target_system; /*< System ID.*/
+ uint8_t cam_idx; /*< Camera ID.*/
+ uint8_t event_id; /*< Event type.*/
+} mavlink_camera_status_t;
+
+#define MAVLINK_MSG_ID_CAMERA_STATUS_LEN 29
+#define MAVLINK_MSG_ID_CAMERA_STATUS_MIN_LEN 29
+#define MAVLINK_MSG_ID_179_LEN 29
+#define MAVLINK_MSG_ID_179_MIN_LEN 29
+
+#define MAVLINK_MSG_ID_CAMERA_STATUS_CRC 189
+#define MAVLINK_MSG_ID_179_CRC 189
+
+
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_CAMERA_STATUS { \
+ 179, \
+ "CAMERA_STATUS", \
+ 9, \
+ { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_camera_status_t, time_usec) }, \
+ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_camera_status_t, target_system) }, \
+ { "cam_idx", NULL, MAVLINK_TYPE_UINT8_T, 0, 27, offsetof(mavlink_camera_status_t, cam_idx) }, \
+ { "img_idx", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_camera_status_t, img_idx) }, \
+ { "event_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_camera_status_t, event_id) }, \
+ { "p1", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_camera_status_t, p1) }, \
+ { "p2", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_camera_status_t, p2) }, \
+ { "p3", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_camera_status_t, p3) }, \
+ { "p4", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_camera_status_t, p4) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_CAMERA_STATUS { \
+ "CAMERA_STATUS", \
+ 9, \
+ { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_camera_status_t, time_usec) }, \
+ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_camera_status_t, target_system) }, \
+ { "cam_idx", NULL, MAVLINK_TYPE_UINT8_T, 0, 27, offsetof(mavlink_camera_status_t, cam_idx) }, \
+ { "img_idx", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_camera_status_t, img_idx) }, \
+ { "event_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_camera_status_t, event_id) }, \
+ { "p1", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_camera_status_t, p1) }, \
+ { "p2", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_camera_status_t, p2) }, \
+ { "p3", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_camera_status_t, p3) }, \
+ { "p4", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_camera_status_t, p4) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a camera_status 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 time_usec [us] Image timestamp (since UNIX epoch, according to camera clock).
+ * @param target_system System ID.
+ * @param cam_idx Camera ID.
+ * @param img_idx Image index.
+ * @param event_id Event type.
+ * @param p1 Parameter 1 (meaning depends on event_id, see CAMERA_STATUS_TYPES enum).
+ * @param p2 Parameter 2 (meaning depends on event_id, see CAMERA_STATUS_TYPES enum).
+ * @param p3 Parameter 3 (meaning depends on event_id, see CAMERA_STATUS_TYPES enum).
+ * @param p4 Parameter 4 (meaning depends on event_id, see CAMERA_STATUS_TYPES enum).
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_camera_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint64_t time_usec, uint8_t target_system, uint8_t cam_idx, uint16_t img_idx, uint8_t event_id, float p1, float p2, float p3, float p4)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_CAMERA_STATUS_LEN];
+ _mav_put_uint64_t(buf, 0, time_usec);
+ _mav_put_float(buf, 8, p1);
+ _mav_put_float(buf, 12, p2);
+ _mav_put_float(buf, 16, p3);
+ _mav_put_float(buf, 20, p4);
+ _mav_put_uint16_t(buf, 24, img_idx);
+ _mav_put_uint8_t(buf, 26, target_system);
+ _mav_put_uint8_t(buf, 27, cam_idx);
+ _mav_put_uint8_t(buf, 28, event_id);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CAMERA_STATUS_LEN);
+#else
+ mavlink_camera_status_t packet;
+ packet.time_usec = time_usec;
+ packet.p1 = p1;
+ packet.p2 = p2;
+ packet.p3 = p3;
+ packet.p4 = p4;
+ packet.img_idx = img_idx;
+ packet.target_system = target_system;
+ packet.cam_idx = cam_idx;
+ packet.event_id = event_id;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CAMERA_STATUS_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_CAMERA_STATUS;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CAMERA_STATUS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_STATUS_LEN, MAVLINK_MSG_ID_CAMERA_STATUS_CRC);
+}
+
+/**
+ * @brief Pack a camera_status 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 time_usec [us] Image timestamp (since UNIX epoch, according to camera clock).
+ * @param target_system System ID.
+ * @param cam_idx Camera ID.
+ * @param img_idx Image index.
+ * @param event_id Event type.
+ * @param p1 Parameter 1 (meaning depends on event_id, see CAMERA_STATUS_TYPES enum).
+ * @param p2 Parameter 2 (meaning depends on event_id, see CAMERA_STATUS_TYPES enum).
+ * @param p3 Parameter 3 (meaning depends on event_id, see CAMERA_STATUS_TYPES enum).
+ * @param p4 Parameter 4 (meaning depends on event_id, see CAMERA_STATUS_TYPES enum).
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_camera_status_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ uint64_t time_usec, uint8_t target_system, uint8_t cam_idx, uint16_t img_idx, uint8_t event_id, float p1, float p2, float p3, float p4)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_CAMERA_STATUS_LEN];
+ _mav_put_uint64_t(buf, 0, time_usec);
+ _mav_put_float(buf, 8, p1);
+ _mav_put_float(buf, 12, p2);
+ _mav_put_float(buf, 16, p3);
+ _mav_put_float(buf, 20, p4);
+ _mav_put_uint16_t(buf, 24, img_idx);
+ _mav_put_uint8_t(buf, 26, target_system);
+ _mav_put_uint8_t(buf, 27, cam_idx);
+ _mav_put_uint8_t(buf, 28, event_id);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CAMERA_STATUS_LEN);
+#else
+ mavlink_camera_status_t packet;
+ packet.time_usec = time_usec;
+ packet.p1 = p1;
+ packet.p2 = p2;
+ packet.p3 = p3;
+ packet.p4 = p4;
+ packet.img_idx = img_idx;
+ packet.target_system = target_system;
+ packet.cam_idx = cam_idx;
+ packet.event_id = event_id;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CAMERA_STATUS_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_CAMERA_STATUS;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_CAMERA_STATUS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_STATUS_LEN, MAVLINK_MSG_ID_CAMERA_STATUS_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_CAMERA_STATUS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_STATUS_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a camera_status 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 time_usec [us] Image timestamp (since UNIX epoch, according to camera clock).
+ * @param target_system System ID.
+ * @param cam_idx Camera ID.
+ * @param img_idx Image index.
+ * @param event_id Event type.
+ * @param p1 Parameter 1 (meaning depends on event_id, see CAMERA_STATUS_TYPES enum).
+ * @param p2 Parameter 2 (meaning depends on event_id, see CAMERA_STATUS_TYPES enum).
+ * @param p3 Parameter 3 (meaning depends on event_id, see CAMERA_STATUS_TYPES enum).
+ * @param p4 Parameter 4 (meaning depends on event_id, see CAMERA_STATUS_TYPES enum).
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_camera_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint64_t time_usec,uint8_t target_system,uint8_t cam_idx,uint16_t img_idx,uint8_t event_id,float p1,float p2,float p3,float p4)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_CAMERA_STATUS_LEN];
+ _mav_put_uint64_t(buf, 0, time_usec);
+ _mav_put_float(buf, 8, p1);
+ _mav_put_float(buf, 12, p2);
+ _mav_put_float(buf, 16, p3);
+ _mav_put_float(buf, 20, p4);
+ _mav_put_uint16_t(buf, 24, img_idx);
+ _mav_put_uint8_t(buf, 26, target_system);
+ _mav_put_uint8_t(buf, 27, cam_idx);
+ _mav_put_uint8_t(buf, 28, event_id);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CAMERA_STATUS_LEN);
+#else
+ mavlink_camera_status_t packet;
+ packet.time_usec = time_usec;
+ packet.p1 = p1;
+ packet.p2 = p2;
+ packet.p3 = p3;
+ packet.p4 = p4;
+ packet.img_idx = img_idx;
+ packet.target_system = target_system;
+ packet.cam_idx = cam_idx;
+ packet.event_id = event_id;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CAMERA_STATUS_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_CAMERA_STATUS;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CAMERA_STATUS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_STATUS_LEN, MAVLINK_MSG_ID_CAMERA_STATUS_CRC);
+}
+
+/**
+ * @brief Encode a camera_status 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 camera_status C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_camera_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_camera_status_t* camera_status)
+{
+ return mavlink_msg_camera_status_pack(system_id, component_id, msg, camera_status->time_usec, camera_status->target_system, camera_status->cam_idx, camera_status->img_idx, camera_status->event_id, camera_status->p1, camera_status->p2, camera_status->p3, camera_status->p4);
+}
+
+/**
+ * @brief Encode a camera_status 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 camera_status C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_camera_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_camera_status_t* camera_status)
+{
+ return mavlink_msg_camera_status_pack_chan(system_id, component_id, chan, msg, camera_status->time_usec, camera_status->target_system, camera_status->cam_idx, camera_status->img_idx, camera_status->event_id, camera_status->p1, camera_status->p2, camera_status->p3, camera_status->p4);
+}
+
+/**
+ * @brief Encode a camera_status 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 camera_status C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_camera_status_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_camera_status_t* camera_status)
+{
+ return mavlink_msg_camera_status_pack_status(system_id, component_id, _status, msg, camera_status->time_usec, camera_status->target_system, camera_status->cam_idx, camera_status->img_idx, camera_status->event_id, camera_status->p1, camera_status->p2, camera_status->p3, camera_status->p4);
+}
+
+/**
+ * @brief Send a camera_status message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param time_usec [us] Image timestamp (since UNIX epoch, according to camera clock).
+ * @param target_system System ID.
+ * @param cam_idx Camera ID.
+ * @param img_idx Image index.
+ * @param event_id Event type.
+ * @param p1 Parameter 1 (meaning depends on event_id, see CAMERA_STATUS_TYPES enum).
+ * @param p2 Parameter 2 (meaning depends on event_id, see CAMERA_STATUS_TYPES enum).
+ * @param p3 Parameter 3 (meaning depends on event_id, see CAMERA_STATUS_TYPES enum).
+ * @param p4 Parameter 4 (meaning depends on event_id, see CAMERA_STATUS_TYPES enum).
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_camera_status_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t target_system, uint8_t cam_idx, uint16_t img_idx, uint8_t event_id, float p1, float p2, float p3, float p4)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_CAMERA_STATUS_LEN];
+ _mav_put_uint64_t(buf, 0, time_usec);
+ _mav_put_float(buf, 8, p1);
+ _mav_put_float(buf, 12, p2);
+ _mav_put_float(buf, 16, p3);
+ _mav_put_float(buf, 20, p4);
+ _mav_put_uint16_t(buf, 24, img_idx);
+ _mav_put_uint8_t(buf, 26, target_system);
+ _mav_put_uint8_t(buf, 27, cam_idx);
+ _mav_put_uint8_t(buf, 28, event_id);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_STATUS, buf, MAVLINK_MSG_ID_CAMERA_STATUS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_STATUS_LEN, MAVLINK_MSG_ID_CAMERA_STATUS_CRC);
+#else
+ mavlink_camera_status_t packet;
+ packet.time_usec = time_usec;
+ packet.p1 = p1;
+ packet.p2 = p2;
+ packet.p3 = p3;
+ packet.p4 = p4;
+ packet.img_idx = img_idx;
+ packet.target_system = target_system;
+ packet.cam_idx = cam_idx;
+ packet.event_id = event_id;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_STATUS, (const char *)&packet, MAVLINK_MSG_ID_CAMERA_STATUS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_STATUS_LEN, MAVLINK_MSG_ID_CAMERA_STATUS_CRC);
+#endif
+}
+
+/**
+ * @brief Send a camera_status message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_camera_status_send_struct(mavlink_channel_t chan, const mavlink_camera_status_t* camera_status)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_camera_status_send(chan, camera_status->time_usec, camera_status->target_system, camera_status->cam_idx, camera_status->img_idx, camera_status->event_id, camera_status->p1, camera_status->p2, camera_status->p3, camera_status->p4);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_STATUS, (const char *)camera_status, MAVLINK_MSG_ID_CAMERA_STATUS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_STATUS_LEN, MAVLINK_MSG_ID_CAMERA_STATUS_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_CAMERA_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_camera_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t target_system, uint8_t cam_idx, uint16_t img_idx, uint8_t event_id, float p1, float p2, float p3, float p4)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint64_t(buf, 0, time_usec);
+ _mav_put_float(buf, 8, p1);
+ _mav_put_float(buf, 12, p2);
+ _mav_put_float(buf, 16, p3);
+ _mav_put_float(buf, 20, p4);
+ _mav_put_uint16_t(buf, 24, img_idx);
+ _mav_put_uint8_t(buf, 26, target_system);
+ _mav_put_uint8_t(buf, 27, cam_idx);
+ _mav_put_uint8_t(buf, 28, event_id);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_STATUS, buf, MAVLINK_MSG_ID_CAMERA_STATUS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_STATUS_LEN, MAVLINK_MSG_ID_CAMERA_STATUS_CRC);
+#else
+ mavlink_camera_status_t *packet = (mavlink_camera_status_t *)msgbuf;
+ packet->time_usec = time_usec;
+ packet->p1 = p1;
+ packet->p2 = p2;
+ packet->p3 = p3;
+ packet->p4 = p4;
+ packet->img_idx = img_idx;
+ packet->target_system = target_system;
+ packet->cam_idx = cam_idx;
+ packet->event_id = event_id;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_STATUS, (const char *)packet, MAVLINK_MSG_ID_CAMERA_STATUS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_STATUS_LEN, MAVLINK_MSG_ID_CAMERA_STATUS_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE CAMERA_STATUS UNPACKING
+
+
+/**
+ * @brief Get field time_usec from camera_status message
+ *
+ * @return [us] Image timestamp (since UNIX epoch, according to camera clock).
+ */
+static inline uint64_t mavlink_msg_camera_status_get_time_usec(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint64_t(msg, 0);
+}
+
+/**
+ * @brief Get field target_system from camera_status message
+ *
+ * @return System ID.
+ */
+static inline uint8_t mavlink_msg_camera_status_get_target_system(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 26);
+}
+
+/**
+ * @brief Get field cam_idx from camera_status message
+ *
+ * @return Camera ID.
+ */
+static inline uint8_t mavlink_msg_camera_status_get_cam_idx(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 27);
+}
+
+/**
+ * @brief Get field img_idx from camera_status message
+ *
+ * @return Image index.
+ */
+static inline uint16_t mavlink_msg_camera_status_get_img_idx(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 24);
+}
+
+/**
+ * @brief Get field event_id from camera_status message
+ *
+ * @return Event type.
+ */
+static inline uint8_t mavlink_msg_camera_status_get_event_id(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 28);
+}
+
+/**
+ * @brief Get field p1 from camera_status message
+ *
+ * @return Parameter 1 (meaning depends on event_id, see CAMERA_STATUS_TYPES enum).
+ */
+static inline float mavlink_msg_camera_status_get_p1(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 8);
+}
+
+/**
+ * @brief Get field p2 from camera_status message
+ *
+ * @return Parameter 2 (meaning depends on event_id, see CAMERA_STATUS_TYPES enum).
+ */
+static inline float mavlink_msg_camera_status_get_p2(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 12);
+}
+
+/**
+ * @brief Get field p3 from camera_status message
+ *
+ * @return Parameter 3 (meaning depends on event_id, see CAMERA_STATUS_TYPES enum).
+ */
+static inline float mavlink_msg_camera_status_get_p3(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 16);
+}
+
+/**
+ * @brief Get field p4 from camera_status message
+ *
+ * @return Parameter 4 (meaning depends on event_id, see CAMERA_STATUS_TYPES enum).
+ */
+static inline float mavlink_msg_camera_status_get_p4(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 20);
+}
+
+/**
+ * @brief Decode a camera_status message into a struct
+ *
+ * @param msg The message to decode
+ * @param camera_status C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_camera_status_decode(const mavlink_message_t* msg, mavlink_camera_status_t* camera_status)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ camera_status->time_usec = mavlink_msg_camera_status_get_time_usec(msg);
+ camera_status->p1 = mavlink_msg_camera_status_get_p1(msg);
+ camera_status->p2 = mavlink_msg_camera_status_get_p2(msg);
+ camera_status->p3 = mavlink_msg_camera_status_get_p3(msg);
+ camera_status->p4 = mavlink_msg_camera_status_get_p4(msg);
+ camera_status->img_idx = mavlink_msg_camera_status_get_img_idx(msg);
+ camera_status->target_system = mavlink_msg_camera_status_get_target_system(msg);
+ camera_status->cam_idx = mavlink_msg_camera_status_get_cam_idx(msg);
+ camera_status->event_id = mavlink_msg_camera_status_get_event_id(msg);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_CAMERA_STATUS_LEN? msg->len : MAVLINK_MSG_ID_CAMERA_STATUS_LEN;
+ memset(camera_status, 0, MAVLINK_MSG_ID_CAMERA_STATUS_LEN);
+ memcpy(camera_status, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/ardupilotmega/mavlink_msg_compassmot_status.h b/lib/main/MAVLink/ardupilotmega/mavlink_msg_compassmot_status.h
new file mode 100644
index 00000000000..1b7bf79e637
--- /dev/null
+++ b/lib/main/MAVLink/ardupilotmega/mavlink_msg_compassmot_status.h
@@ -0,0 +1,400 @@
+#pragma once
+// MESSAGE COMPASSMOT_STATUS PACKING
+
+#define MAVLINK_MSG_ID_COMPASSMOT_STATUS 177
+
+
+typedef struct __mavlink_compassmot_status_t {
+ float current; /*< [A] Current.*/
+ float CompensationX; /*< Motor Compensation X.*/
+ float CompensationY; /*< Motor Compensation Y.*/
+ float CompensationZ; /*< Motor Compensation Z.*/
+ uint16_t throttle; /*< [d%] Throttle.*/
+ uint16_t interference; /*< [%] Interference.*/
+} mavlink_compassmot_status_t;
+
+#define MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN 20
+#define MAVLINK_MSG_ID_COMPASSMOT_STATUS_MIN_LEN 20
+#define MAVLINK_MSG_ID_177_LEN 20
+#define MAVLINK_MSG_ID_177_MIN_LEN 20
+
+#define MAVLINK_MSG_ID_COMPASSMOT_STATUS_CRC 240
+#define MAVLINK_MSG_ID_177_CRC 240
+
+
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_COMPASSMOT_STATUS { \
+ 177, \
+ "COMPASSMOT_STATUS", \
+ 6, \
+ { { "throttle", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_compassmot_status_t, throttle) }, \
+ { "current", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_compassmot_status_t, current) }, \
+ { "interference", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_compassmot_status_t, interference) }, \
+ { "CompensationX", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_compassmot_status_t, CompensationX) }, \
+ { "CompensationY", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_compassmot_status_t, CompensationY) }, \
+ { "CompensationZ", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_compassmot_status_t, CompensationZ) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_COMPASSMOT_STATUS { \
+ "COMPASSMOT_STATUS", \
+ 6, \
+ { { "throttle", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_compassmot_status_t, throttle) }, \
+ { "current", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_compassmot_status_t, current) }, \
+ { "interference", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_compassmot_status_t, interference) }, \
+ { "CompensationX", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_compassmot_status_t, CompensationX) }, \
+ { "CompensationY", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_compassmot_status_t, CompensationY) }, \
+ { "CompensationZ", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_compassmot_status_t, CompensationZ) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a compassmot_status 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 throttle [d%] Throttle.
+ * @param current [A] Current.
+ * @param interference [%] Interference.
+ * @param CompensationX Motor Compensation X.
+ * @param CompensationY Motor Compensation Y.
+ * @param CompensationZ Motor Compensation Z.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_compassmot_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint16_t throttle, float current, uint16_t interference, float CompensationX, float CompensationY, float CompensationZ)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN];
+ _mav_put_float(buf, 0, current);
+ _mav_put_float(buf, 4, CompensationX);
+ _mav_put_float(buf, 8, CompensationY);
+ _mav_put_float(buf, 12, CompensationZ);
+ _mav_put_uint16_t(buf, 16, throttle);
+ _mav_put_uint16_t(buf, 18, interference);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN);
+#else
+ mavlink_compassmot_status_t packet;
+ packet.current = current;
+ packet.CompensationX = CompensationX;
+ packet.CompensationY = CompensationY;
+ packet.CompensationZ = CompensationZ;
+ packet.throttle = throttle;
+ packet.interference = interference;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_COMPASSMOT_STATUS;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_COMPASSMOT_STATUS_MIN_LEN, MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN, MAVLINK_MSG_ID_COMPASSMOT_STATUS_CRC);
+}
+
+/**
+ * @brief Pack a compassmot_status 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 throttle [d%] Throttle.
+ * @param current [A] Current.
+ * @param interference [%] Interference.
+ * @param CompensationX Motor Compensation X.
+ * @param CompensationY Motor Compensation Y.
+ * @param CompensationZ Motor Compensation Z.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_compassmot_status_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ uint16_t throttle, float current, uint16_t interference, float CompensationX, float CompensationY, float CompensationZ)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN];
+ _mav_put_float(buf, 0, current);
+ _mav_put_float(buf, 4, CompensationX);
+ _mav_put_float(buf, 8, CompensationY);
+ _mav_put_float(buf, 12, CompensationZ);
+ _mav_put_uint16_t(buf, 16, throttle);
+ _mav_put_uint16_t(buf, 18, interference);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN);
+#else
+ mavlink_compassmot_status_t packet;
+ packet.current = current;
+ packet.CompensationX = CompensationX;
+ packet.CompensationY = CompensationY;
+ packet.CompensationZ = CompensationZ;
+ packet.throttle = throttle;
+ packet.interference = interference;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_COMPASSMOT_STATUS;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_COMPASSMOT_STATUS_MIN_LEN, MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN, MAVLINK_MSG_ID_COMPASSMOT_STATUS_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_COMPASSMOT_STATUS_MIN_LEN, MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a compassmot_status 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 throttle [d%] Throttle.
+ * @param current [A] Current.
+ * @param interference [%] Interference.
+ * @param CompensationX Motor Compensation X.
+ * @param CompensationY Motor Compensation Y.
+ * @param CompensationZ Motor Compensation Z.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_compassmot_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint16_t throttle,float current,uint16_t interference,float CompensationX,float CompensationY,float CompensationZ)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN];
+ _mav_put_float(buf, 0, current);
+ _mav_put_float(buf, 4, CompensationX);
+ _mav_put_float(buf, 8, CompensationY);
+ _mav_put_float(buf, 12, CompensationZ);
+ _mav_put_uint16_t(buf, 16, throttle);
+ _mav_put_uint16_t(buf, 18, interference);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN);
+#else
+ mavlink_compassmot_status_t packet;
+ packet.current = current;
+ packet.CompensationX = CompensationX;
+ packet.CompensationY = CompensationY;
+ packet.CompensationZ = CompensationZ;
+ packet.throttle = throttle;
+ packet.interference = interference;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_COMPASSMOT_STATUS;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_COMPASSMOT_STATUS_MIN_LEN, MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN, MAVLINK_MSG_ID_COMPASSMOT_STATUS_CRC);
+}
+
+/**
+ * @brief Encode a compassmot_status 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 compassmot_status C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_compassmot_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_compassmot_status_t* compassmot_status)
+{
+ return mavlink_msg_compassmot_status_pack(system_id, component_id, msg, compassmot_status->throttle, compassmot_status->current, compassmot_status->interference, compassmot_status->CompensationX, compassmot_status->CompensationY, compassmot_status->CompensationZ);
+}
+
+/**
+ * @brief Encode a compassmot_status 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 compassmot_status C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_compassmot_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_compassmot_status_t* compassmot_status)
+{
+ return mavlink_msg_compassmot_status_pack_chan(system_id, component_id, chan, msg, compassmot_status->throttle, compassmot_status->current, compassmot_status->interference, compassmot_status->CompensationX, compassmot_status->CompensationY, compassmot_status->CompensationZ);
+}
+
+/**
+ * @brief Encode a compassmot_status 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 compassmot_status C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_compassmot_status_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_compassmot_status_t* compassmot_status)
+{
+ return mavlink_msg_compassmot_status_pack_status(system_id, component_id, _status, msg, compassmot_status->throttle, compassmot_status->current, compassmot_status->interference, compassmot_status->CompensationX, compassmot_status->CompensationY, compassmot_status->CompensationZ);
+}
+
+/**
+ * @brief Send a compassmot_status message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param throttle [d%] Throttle.
+ * @param current [A] Current.
+ * @param interference [%] Interference.
+ * @param CompensationX Motor Compensation X.
+ * @param CompensationY Motor Compensation Y.
+ * @param CompensationZ Motor Compensation Z.
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_compassmot_status_send(mavlink_channel_t chan, uint16_t throttle, float current, uint16_t interference, float CompensationX, float CompensationY, float CompensationZ)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN];
+ _mav_put_float(buf, 0, current);
+ _mav_put_float(buf, 4, CompensationX);
+ _mav_put_float(buf, 8, CompensationY);
+ _mav_put_float(buf, 12, CompensationZ);
+ _mav_put_uint16_t(buf, 16, throttle);
+ _mav_put_uint16_t(buf, 18, interference);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMPASSMOT_STATUS, buf, MAVLINK_MSG_ID_COMPASSMOT_STATUS_MIN_LEN, MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN, MAVLINK_MSG_ID_COMPASSMOT_STATUS_CRC);
+#else
+ mavlink_compassmot_status_t packet;
+ packet.current = current;
+ packet.CompensationX = CompensationX;
+ packet.CompensationY = CompensationY;
+ packet.CompensationZ = CompensationZ;
+ packet.throttle = throttle;
+ packet.interference = interference;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMPASSMOT_STATUS, (const char *)&packet, MAVLINK_MSG_ID_COMPASSMOT_STATUS_MIN_LEN, MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN, MAVLINK_MSG_ID_COMPASSMOT_STATUS_CRC);
+#endif
+}
+
+/**
+ * @brief Send a compassmot_status message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_compassmot_status_send_struct(mavlink_channel_t chan, const mavlink_compassmot_status_t* compassmot_status)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_compassmot_status_send(chan, compassmot_status->throttle, compassmot_status->current, compassmot_status->interference, compassmot_status->CompensationX, compassmot_status->CompensationY, compassmot_status->CompensationZ);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMPASSMOT_STATUS, (const char *)compassmot_status, MAVLINK_MSG_ID_COMPASSMOT_STATUS_MIN_LEN, MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN, MAVLINK_MSG_ID_COMPASSMOT_STATUS_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_compassmot_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t throttle, float current, uint16_t interference, float CompensationX, float CompensationY, float CompensationZ)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_float(buf, 0, current);
+ _mav_put_float(buf, 4, CompensationX);
+ _mav_put_float(buf, 8, CompensationY);
+ _mav_put_float(buf, 12, CompensationZ);
+ _mav_put_uint16_t(buf, 16, throttle);
+ _mav_put_uint16_t(buf, 18, interference);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMPASSMOT_STATUS, buf, MAVLINK_MSG_ID_COMPASSMOT_STATUS_MIN_LEN, MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN, MAVLINK_MSG_ID_COMPASSMOT_STATUS_CRC);
+#else
+ mavlink_compassmot_status_t *packet = (mavlink_compassmot_status_t *)msgbuf;
+ packet->current = current;
+ packet->CompensationX = CompensationX;
+ packet->CompensationY = CompensationY;
+ packet->CompensationZ = CompensationZ;
+ packet->throttle = throttle;
+ packet->interference = interference;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMPASSMOT_STATUS, (const char *)packet, MAVLINK_MSG_ID_COMPASSMOT_STATUS_MIN_LEN, MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN, MAVLINK_MSG_ID_COMPASSMOT_STATUS_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE COMPASSMOT_STATUS UNPACKING
+
+
+/**
+ * @brief Get field throttle from compassmot_status message
+ *
+ * @return [d%] Throttle.
+ */
+static inline uint16_t mavlink_msg_compassmot_status_get_throttle(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 16);
+}
+
+/**
+ * @brief Get field current from compassmot_status message
+ *
+ * @return [A] Current.
+ */
+static inline float mavlink_msg_compassmot_status_get_current(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 0);
+}
+
+/**
+ * @brief Get field interference from compassmot_status message
+ *
+ * @return [%] Interference.
+ */
+static inline uint16_t mavlink_msg_compassmot_status_get_interference(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 18);
+}
+
+/**
+ * @brief Get field CompensationX from compassmot_status message
+ *
+ * @return Motor Compensation X.
+ */
+static inline float mavlink_msg_compassmot_status_get_CompensationX(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 4);
+}
+
+/**
+ * @brief Get field CompensationY from compassmot_status message
+ *
+ * @return Motor Compensation Y.
+ */
+static inline float mavlink_msg_compassmot_status_get_CompensationY(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 8);
+}
+
+/**
+ * @brief Get field CompensationZ from compassmot_status message
+ *
+ * @return Motor Compensation Z.
+ */
+static inline float mavlink_msg_compassmot_status_get_CompensationZ(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 12);
+}
+
+/**
+ * @brief Decode a compassmot_status message into a struct
+ *
+ * @param msg The message to decode
+ * @param compassmot_status C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_compassmot_status_decode(const mavlink_message_t* msg, mavlink_compassmot_status_t* compassmot_status)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ compassmot_status->current = mavlink_msg_compassmot_status_get_current(msg);
+ compassmot_status->CompensationX = mavlink_msg_compassmot_status_get_CompensationX(msg);
+ compassmot_status->CompensationY = mavlink_msg_compassmot_status_get_CompensationY(msg);
+ compassmot_status->CompensationZ = mavlink_msg_compassmot_status_get_CompensationZ(msg);
+ compassmot_status->throttle = mavlink_msg_compassmot_status_get_throttle(msg);
+ compassmot_status->interference = mavlink_msg_compassmot_status_get_interference(msg);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN? msg->len : MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN;
+ memset(compassmot_status, 0, MAVLINK_MSG_ID_COMPASSMOT_STATUS_LEN);
+ memcpy(compassmot_status, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/ardupilotmega/mavlink_msg_data16.h b/lib/main/MAVLink/ardupilotmega/mavlink_msg_data16.h
new file mode 100644
index 00000000000..6c43d197b3b
--- /dev/null
+++ b/lib/main/MAVLink/ardupilotmega/mavlink_msg_data16.h
@@ -0,0 +1,306 @@
+#pragma once
+// MESSAGE DATA16 PACKING
+
+#define MAVLINK_MSG_ID_DATA16 169
+
+
+typedef struct __mavlink_data16_t {
+ uint8_t type; /*< Data type.*/
+ uint8_t len; /*< [bytes] Data length.*/
+ uint8_t data[16]; /*< Raw data.*/
+} mavlink_data16_t;
+
+#define MAVLINK_MSG_ID_DATA16_LEN 18
+#define MAVLINK_MSG_ID_DATA16_MIN_LEN 18
+#define MAVLINK_MSG_ID_169_LEN 18
+#define MAVLINK_MSG_ID_169_MIN_LEN 18
+
+#define MAVLINK_MSG_ID_DATA16_CRC 234
+#define MAVLINK_MSG_ID_169_CRC 234
+
+#define MAVLINK_MSG_DATA16_FIELD_DATA_LEN 16
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_DATA16 { \
+ 169, \
+ "DATA16", \
+ 3, \
+ { { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_data16_t, type) }, \
+ { "len", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_data16_t, len) }, \
+ { "data", NULL, MAVLINK_TYPE_UINT8_T, 16, 2, offsetof(mavlink_data16_t, data) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_DATA16 { \
+ "DATA16", \
+ 3, \
+ { { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_data16_t, type) }, \
+ { "len", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_data16_t, len) }, \
+ { "data", NULL, MAVLINK_TYPE_UINT8_T, 16, 2, offsetof(mavlink_data16_t, data) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a data16 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 type Data type.
+ * @param len [bytes] Data length.
+ * @param data Raw data.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_data16_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint8_t type, uint8_t len, const uint8_t *data)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_DATA16_LEN];
+ _mav_put_uint8_t(buf, 0, type);
+ _mav_put_uint8_t(buf, 1, len);
+ _mav_put_uint8_t_array(buf, 2, data, 16);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DATA16_LEN);
+#else
+ mavlink_data16_t packet;
+ packet.type = type;
+ packet.len = len;
+ mav_array_assign_uint8_t(packet.data, data, 16);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DATA16_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_DATA16;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DATA16_MIN_LEN, MAVLINK_MSG_ID_DATA16_LEN, MAVLINK_MSG_ID_DATA16_CRC);
+}
+
+/**
+ * @brief Pack a data16 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 type Data type.
+ * @param len [bytes] Data length.
+ * @param data Raw data.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_data16_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ uint8_t type, uint8_t len, const uint8_t *data)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_DATA16_LEN];
+ _mav_put_uint8_t(buf, 0, type);
+ _mav_put_uint8_t(buf, 1, len);
+ _mav_put_uint8_t_array(buf, 2, data, 16);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DATA16_LEN);
+#else
+ mavlink_data16_t packet;
+ packet.type = type;
+ packet.len = len;
+ mav_array_memcpy(packet.data, data, sizeof(uint8_t)*16);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DATA16_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_DATA16;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_DATA16_MIN_LEN, MAVLINK_MSG_ID_DATA16_LEN, MAVLINK_MSG_ID_DATA16_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_DATA16_MIN_LEN, MAVLINK_MSG_ID_DATA16_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a data16 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 type Data type.
+ * @param len [bytes] Data length.
+ * @param data Raw data.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_data16_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint8_t type,uint8_t len,const uint8_t *data)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_DATA16_LEN];
+ _mav_put_uint8_t(buf, 0, type);
+ _mav_put_uint8_t(buf, 1, len);
+ _mav_put_uint8_t_array(buf, 2, data, 16);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DATA16_LEN);
+#else
+ mavlink_data16_t packet;
+ packet.type = type;
+ packet.len = len;
+ mav_array_assign_uint8_t(packet.data, data, 16);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DATA16_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_DATA16;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DATA16_MIN_LEN, MAVLINK_MSG_ID_DATA16_LEN, MAVLINK_MSG_ID_DATA16_CRC);
+}
+
+/**
+ * @brief Encode a data16 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 data16 C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_data16_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_data16_t* data16)
+{
+ return mavlink_msg_data16_pack(system_id, component_id, msg, data16->type, data16->len, data16->data);
+}
+
+/**
+ * @brief Encode a data16 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 data16 C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_data16_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_data16_t* data16)
+{
+ return mavlink_msg_data16_pack_chan(system_id, component_id, chan, msg, data16->type, data16->len, data16->data);
+}
+
+/**
+ * @brief Encode a data16 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 data16 C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_data16_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_data16_t* data16)
+{
+ return mavlink_msg_data16_pack_status(system_id, component_id, _status, msg, data16->type, data16->len, data16->data);
+}
+
+/**
+ * @brief Send a data16 message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param type Data type.
+ * @param len [bytes] Data length.
+ * @param data Raw data.
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_data16_send(mavlink_channel_t chan, uint8_t type, uint8_t len, const uint8_t *data)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_DATA16_LEN];
+ _mav_put_uint8_t(buf, 0, type);
+ _mav_put_uint8_t(buf, 1, len);
+ _mav_put_uint8_t_array(buf, 2, data, 16);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA16, buf, MAVLINK_MSG_ID_DATA16_MIN_LEN, MAVLINK_MSG_ID_DATA16_LEN, MAVLINK_MSG_ID_DATA16_CRC);
+#else
+ mavlink_data16_t packet;
+ packet.type = type;
+ packet.len = len;
+ mav_array_assign_uint8_t(packet.data, data, 16);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA16, (const char *)&packet, MAVLINK_MSG_ID_DATA16_MIN_LEN, MAVLINK_MSG_ID_DATA16_LEN, MAVLINK_MSG_ID_DATA16_CRC);
+#endif
+}
+
+/**
+ * @brief Send a data16 message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_data16_send_struct(mavlink_channel_t chan, const mavlink_data16_t* data16)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_data16_send(chan, data16->type, data16->len, data16->data);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA16, (const char *)data16, MAVLINK_MSG_ID_DATA16_MIN_LEN, MAVLINK_MSG_ID_DATA16_LEN, MAVLINK_MSG_ID_DATA16_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_DATA16_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_data16_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t type, uint8_t len, const uint8_t *data)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint8_t(buf, 0, type);
+ _mav_put_uint8_t(buf, 1, len);
+ _mav_put_uint8_t_array(buf, 2, data, 16);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA16, buf, MAVLINK_MSG_ID_DATA16_MIN_LEN, MAVLINK_MSG_ID_DATA16_LEN, MAVLINK_MSG_ID_DATA16_CRC);
+#else
+ mavlink_data16_t *packet = (mavlink_data16_t *)msgbuf;
+ packet->type = type;
+ packet->len = len;
+ mav_array_assign_uint8_t(packet->data, data, 16);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA16, (const char *)packet, MAVLINK_MSG_ID_DATA16_MIN_LEN, MAVLINK_MSG_ID_DATA16_LEN, MAVLINK_MSG_ID_DATA16_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE DATA16 UNPACKING
+
+
+/**
+ * @brief Get field type from data16 message
+ *
+ * @return Data type.
+ */
+static inline uint8_t mavlink_msg_data16_get_type(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 0);
+}
+
+/**
+ * @brief Get field len from data16 message
+ *
+ * @return [bytes] Data length.
+ */
+static inline uint8_t mavlink_msg_data16_get_len(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 1);
+}
+
+/**
+ * @brief Get field data from data16 message
+ *
+ * @return Raw data.
+ */
+static inline uint16_t mavlink_msg_data16_get_data(const mavlink_message_t* msg, uint8_t *data)
+{
+ return _MAV_RETURN_uint8_t_array(msg, data, 16, 2);
+}
+
+/**
+ * @brief Decode a data16 message into a struct
+ *
+ * @param msg The message to decode
+ * @param data16 C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_data16_decode(const mavlink_message_t* msg, mavlink_data16_t* data16)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ data16->type = mavlink_msg_data16_get_type(msg);
+ data16->len = mavlink_msg_data16_get_len(msg);
+ mavlink_msg_data16_get_data(msg, data16->data);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_DATA16_LEN? msg->len : MAVLINK_MSG_ID_DATA16_LEN;
+ memset(data16, 0, MAVLINK_MSG_ID_DATA16_LEN);
+ memcpy(data16, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/ardupilotmega/mavlink_msg_data32.h b/lib/main/MAVLink/ardupilotmega/mavlink_msg_data32.h
new file mode 100644
index 00000000000..61926eabe47
--- /dev/null
+++ b/lib/main/MAVLink/ardupilotmega/mavlink_msg_data32.h
@@ -0,0 +1,306 @@
+#pragma once
+// MESSAGE DATA32 PACKING
+
+#define MAVLINK_MSG_ID_DATA32 170
+
+
+typedef struct __mavlink_data32_t {
+ uint8_t type; /*< Data type.*/
+ uint8_t len; /*< [bytes] Data length.*/
+ uint8_t data[32]; /*< Raw data.*/
+} mavlink_data32_t;
+
+#define MAVLINK_MSG_ID_DATA32_LEN 34
+#define MAVLINK_MSG_ID_DATA32_MIN_LEN 34
+#define MAVLINK_MSG_ID_170_LEN 34
+#define MAVLINK_MSG_ID_170_MIN_LEN 34
+
+#define MAVLINK_MSG_ID_DATA32_CRC 73
+#define MAVLINK_MSG_ID_170_CRC 73
+
+#define MAVLINK_MSG_DATA32_FIELD_DATA_LEN 32
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_DATA32 { \
+ 170, \
+ "DATA32", \
+ 3, \
+ { { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_data32_t, type) }, \
+ { "len", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_data32_t, len) }, \
+ { "data", NULL, MAVLINK_TYPE_UINT8_T, 32, 2, offsetof(mavlink_data32_t, data) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_DATA32 { \
+ "DATA32", \
+ 3, \
+ { { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_data32_t, type) }, \
+ { "len", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_data32_t, len) }, \
+ { "data", NULL, MAVLINK_TYPE_UINT8_T, 32, 2, offsetof(mavlink_data32_t, data) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a data32 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 type Data type.
+ * @param len [bytes] Data length.
+ * @param data Raw data.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_data32_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint8_t type, uint8_t len, const uint8_t *data)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_DATA32_LEN];
+ _mav_put_uint8_t(buf, 0, type);
+ _mav_put_uint8_t(buf, 1, len);
+ _mav_put_uint8_t_array(buf, 2, data, 32);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DATA32_LEN);
+#else
+ mavlink_data32_t packet;
+ packet.type = type;
+ packet.len = len;
+ mav_array_assign_uint8_t(packet.data, data, 32);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DATA32_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_DATA32;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DATA32_MIN_LEN, MAVLINK_MSG_ID_DATA32_LEN, MAVLINK_MSG_ID_DATA32_CRC);
+}
+
+/**
+ * @brief Pack a data32 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 type Data type.
+ * @param len [bytes] Data length.
+ * @param data Raw data.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_data32_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ uint8_t type, uint8_t len, const uint8_t *data)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_DATA32_LEN];
+ _mav_put_uint8_t(buf, 0, type);
+ _mav_put_uint8_t(buf, 1, len);
+ _mav_put_uint8_t_array(buf, 2, data, 32);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DATA32_LEN);
+#else
+ mavlink_data32_t packet;
+ packet.type = type;
+ packet.len = len;
+ mav_array_memcpy(packet.data, data, sizeof(uint8_t)*32);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DATA32_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_DATA32;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_DATA32_MIN_LEN, MAVLINK_MSG_ID_DATA32_LEN, MAVLINK_MSG_ID_DATA32_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_DATA32_MIN_LEN, MAVLINK_MSG_ID_DATA32_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a data32 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 type Data type.
+ * @param len [bytes] Data length.
+ * @param data Raw data.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_data32_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint8_t type,uint8_t len,const uint8_t *data)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_DATA32_LEN];
+ _mav_put_uint8_t(buf, 0, type);
+ _mav_put_uint8_t(buf, 1, len);
+ _mav_put_uint8_t_array(buf, 2, data, 32);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DATA32_LEN);
+#else
+ mavlink_data32_t packet;
+ packet.type = type;
+ packet.len = len;
+ mav_array_assign_uint8_t(packet.data, data, 32);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DATA32_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_DATA32;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DATA32_MIN_LEN, MAVLINK_MSG_ID_DATA32_LEN, MAVLINK_MSG_ID_DATA32_CRC);
+}
+
+/**
+ * @brief Encode a data32 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 data32 C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_data32_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_data32_t* data32)
+{
+ return mavlink_msg_data32_pack(system_id, component_id, msg, data32->type, data32->len, data32->data);
+}
+
+/**
+ * @brief Encode a data32 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 data32 C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_data32_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_data32_t* data32)
+{
+ return mavlink_msg_data32_pack_chan(system_id, component_id, chan, msg, data32->type, data32->len, data32->data);
+}
+
+/**
+ * @brief Encode a data32 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 data32 C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_data32_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_data32_t* data32)
+{
+ return mavlink_msg_data32_pack_status(system_id, component_id, _status, msg, data32->type, data32->len, data32->data);
+}
+
+/**
+ * @brief Send a data32 message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param type Data type.
+ * @param len [bytes] Data length.
+ * @param data Raw data.
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_data32_send(mavlink_channel_t chan, uint8_t type, uint8_t len, const uint8_t *data)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_DATA32_LEN];
+ _mav_put_uint8_t(buf, 0, type);
+ _mav_put_uint8_t(buf, 1, len);
+ _mav_put_uint8_t_array(buf, 2, data, 32);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA32, buf, MAVLINK_MSG_ID_DATA32_MIN_LEN, MAVLINK_MSG_ID_DATA32_LEN, MAVLINK_MSG_ID_DATA32_CRC);
+#else
+ mavlink_data32_t packet;
+ packet.type = type;
+ packet.len = len;
+ mav_array_assign_uint8_t(packet.data, data, 32);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA32, (const char *)&packet, MAVLINK_MSG_ID_DATA32_MIN_LEN, MAVLINK_MSG_ID_DATA32_LEN, MAVLINK_MSG_ID_DATA32_CRC);
+#endif
+}
+
+/**
+ * @brief Send a data32 message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_data32_send_struct(mavlink_channel_t chan, const mavlink_data32_t* data32)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_data32_send(chan, data32->type, data32->len, data32->data);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA32, (const char *)data32, MAVLINK_MSG_ID_DATA32_MIN_LEN, MAVLINK_MSG_ID_DATA32_LEN, MAVLINK_MSG_ID_DATA32_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_DATA32_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_data32_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t type, uint8_t len, const uint8_t *data)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint8_t(buf, 0, type);
+ _mav_put_uint8_t(buf, 1, len);
+ _mav_put_uint8_t_array(buf, 2, data, 32);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA32, buf, MAVLINK_MSG_ID_DATA32_MIN_LEN, MAVLINK_MSG_ID_DATA32_LEN, MAVLINK_MSG_ID_DATA32_CRC);
+#else
+ mavlink_data32_t *packet = (mavlink_data32_t *)msgbuf;
+ packet->type = type;
+ packet->len = len;
+ mav_array_assign_uint8_t(packet->data, data, 32);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA32, (const char *)packet, MAVLINK_MSG_ID_DATA32_MIN_LEN, MAVLINK_MSG_ID_DATA32_LEN, MAVLINK_MSG_ID_DATA32_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE DATA32 UNPACKING
+
+
+/**
+ * @brief Get field type from data32 message
+ *
+ * @return Data type.
+ */
+static inline uint8_t mavlink_msg_data32_get_type(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 0);
+}
+
+/**
+ * @brief Get field len from data32 message
+ *
+ * @return [bytes] Data length.
+ */
+static inline uint8_t mavlink_msg_data32_get_len(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 1);
+}
+
+/**
+ * @brief Get field data from data32 message
+ *
+ * @return Raw data.
+ */
+static inline uint16_t mavlink_msg_data32_get_data(const mavlink_message_t* msg, uint8_t *data)
+{
+ return _MAV_RETURN_uint8_t_array(msg, data, 32, 2);
+}
+
+/**
+ * @brief Decode a data32 message into a struct
+ *
+ * @param msg The message to decode
+ * @param data32 C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_data32_decode(const mavlink_message_t* msg, mavlink_data32_t* data32)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ data32->type = mavlink_msg_data32_get_type(msg);
+ data32->len = mavlink_msg_data32_get_len(msg);
+ mavlink_msg_data32_get_data(msg, data32->data);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_DATA32_LEN? msg->len : MAVLINK_MSG_ID_DATA32_LEN;
+ memset(data32, 0, MAVLINK_MSG_ID_DATA32_LEN);
+ memcpy(data32, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/ardupilotmega/mavlink_msg_data64.h b/lib/main/MAVLink/ardupilotmega/mavlink_msg_data64.h
new file mode 100644
index 00000000000..211878d71d2
--- /dev/null
+++ b/lib/main/MAVLink/ardupilotmega/mavlink_msg_data64.h
@@ -0,0 +1,306 @@
+#pragma once
+// MESSAGE DATA64 PACKING
+
+#define MAVLINK_MSG_ID_DATA64 171
+
+
+typedef struct __mavlink_data64_t {
+ uint8_t type; /*< Data type.*/
+ uint8_t len; /*< [bytes] Data length.*/
+ uint8_t data[64]; /*< Raw data.*/
+} mavlink_data64_t;
+
+#define MAVLINK_MSG_ID_DATA64_LEN 66
+#define MAVLINK_MSG_ID_DATA64_MIN_LEN 66
+#define MAVLINK_MSG_ID_171_LEN 66
+#define MAVLINK_MSG_ID_171_MIN_LEN 66
+
+#define MAVLINK_MSG_ID_DATA64_CRC 181
+#define MAVLINK_MSG_ID_171_CRC 181
+
+#define MAVLINK_MSG_DATA64_FIELD_DATA_LEN 64
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_DATA64 { \
+ 171, \
+ "DATA64", \
+ 3, \
+ { { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_data64_t, type) }, \
+ { "len", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_data64_t, len) }, \
+ { "data", NULL, MAVLINK_TYPE_UINT8_T, 64, 2, offsetof(mavlink_data64_t, data) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_DATA64 { \
+ "DATA64", \
+ 3, \
+ { { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_data64_t, type) }, \
+ { "len", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_data64_t, len) }, \
+ { "data", NULL, MAVLINK_TYPE_UINT8_T, 64, 2, offsetof(mavlink_data64_t, data) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a data64 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 type Data type.
+ * @param len [bytes] Data length.
+ * @param data Raw data.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_data64_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint8_t type, uint8_t len, const uint8_t *data)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_DATA64_LEN];
+ _mav_put_uint8_t(buf, 0, type);
+ _mav_put_uint8_t(buf, 1, len);
+ _mav_put_uint8_t_array(buf, 2, data, 64);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DATA64_LEN);
+#else
+ mavlink_data64_t packet;
+ packet.type = type;
+ packet.len = len;
+ mav_array_assign_uint8_t(packet.data, data, 64);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DATA64_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_DATA64;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DATA64_MIN_LEN, MAVLINK_MSG_ID_DATA64_LEN, MAVLINK_MSG_ID_DATA64_CRC);
+}
+
+/**
+ * @brief Pack a data64 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 type Data type.
+ * @param len [bytes] Data length.
+ * @param data Raw data.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_data64_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ uint8_t type, uint8_t len, const uint8_t *data)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_DATA64_LEN];
+ _mav_put_uint8_t(buf, 0, type);
+ _mav_put_uint8_t(buf, 1, len);
+ _mav_put_uint8_t_array(buf, 2, data, 64);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DATA64_LEN);
+#else
+ mavlink_data64_t packet;
+ packet.type = type;
+ packet.len = len;
+ mav_array_memcpy(packet.data, data, sizeof(uint8_t)*64);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DATA64_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_DATA64;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_DATA64_MIN_LEN, MAVLINK_MSG_ID_DATA64_LEN, MAVLINK_MSG_ID_DATA64_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_DATA64_MIN_LEN, MAVLINK_MSG_ID_DATA64_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a data64 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 type Data type.
+ * @param len [bytes] Data length.
+ * @param data Raw data.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_data64_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint8_t type,uint8_t len,const uint8_t *data)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_DATA64_LEN];
+ _mav_put_uint8_t(buf, 0, type);
+ _mav_put_uint8_t(buf, 1, len);
+ _mav_put_uint8_t_array(buf, 2, data, 64);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DATA64_LEN);
+#else
+ mavlink_data64_t packet;
+ packet.type = type;
+ packet.len = len;
+ mav_array_assign_uint8_t(packet.data, data, 64);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DATA64_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_DATA64;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DATA64_MIN_LEN, MAVLINK_MSG_ID_DATA64_LEN, MAVLINK_MSG_ID_DATA64_CRC);
+}
+
+/**
+ * @brief Encode a data64 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 data64 C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_data64_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_data64_t* data64)
+{
+ return mavlink_msg_data64_pack(system_id, component_id, msg, data64->type, data64->len, data64->data);
+}
+
+/**
+ * @brief Encode a data64 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 data64 C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_data64_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_data64_t* data64)
+{
+ return mavlink_msg_data64_pack_chan(system_id, component_id, chan, msg, data64->type, data64->len, data64->data);
+}
+
+/**
+ * @brief Encode a data64 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 data64 C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_data64_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_data64_t* data64)
+{
+ return mavlink_msg_data64_pack_status(system_id, component_id, _status, msg, data64->type, data64->len, data64->data);
+}
+
+/**
+ * @brief Send a data64 message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param type Data type.
+ * @param len [bytes] Data length.
+ * @param data Raw data.
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_data64_send(mavlink_channel_t chan, uint8_t type, uint8_t len, const uint8_t *data)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_DATA64_LEN];
+ _mav_put_uint8_t(buf, 0, type);
+ _mav_put_uint8_t(buf, 1, len);
+ _mav_put_uint8_t_array(buf, 2, data, 64);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA64, buf, MAVLINK_MSG_ID_DATA64_MIN_LEN, MAVLINK_MSG_ID_DATA64_LEN, MAVLINK_MSG_ID_DATA64_CRC);
+#else
+ mavlink_data64_t packet;
+ packet.type = type;
+ packet.len = len;
+ mav_array_assign_uint8_t(packet.data, data, 64);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA64, (const char *)&packet, MAVLINK_MSG_ID_DATA64_MIN_LEN, MAVLINK_MSG_ID_DATA64_LEN, MAVLINK_MSG_ID_DATA64_CRC);
+#endif
+}
+
+/**
+ * @brief Send a data64 message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_data64_send_struct(mavlink_channel_t chan, const mavlink_data64_t* data64)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_data64_send(chan, data64->type, data64->len, data64->data);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA64, (const char *)data64, MAVLINK_MSG_ID_DATA64_MIN_LEN, MAVLINK_MSG_ID_DATA64_LEN, MAVLINK_MSG_ID_DATA64_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_DATA64_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_data64_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t type, uint8_t len, const uint8_t *data)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint8_t(buf, 0, type);
+ _mav_put_uint8_t(buf, 1, len);
+ _mav_put_uint8_t_array(buf, 2, data, 64);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA64, buf, MAVLINK_MSG_ID_DATA64_MIN_LEN, MAVLINK_MSG_ID_DATA64_LEN, MAVLINK_MSG_ID_DATA64_CRC);
+#else
+ mavlink_data64_t *packet = (mavlink_data64_t *)msgbuf;
+ packet->type = type;
+ packet->len = len;
+ mav_array_assign_uint8_t(packet->data, data, 64);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA64, (const char *)packet, MAVLINK_MSG_ID_DATA64_MIN_LEN, MAVLINK_MSG_ID_DATA64_LEN, MAVLINK_MSG_ID_DATA64_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE DATA64 UNPACKING
+
+
+/**
+ * @brief Get field type from data64 message
+ *
+ * @return Data type.
+ */
+static inline uint8_t mavlink_msg_data64_get_type(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 0);
+}
+
+/**
+ * @brief Get field len from data64 message
+ *
+ * @return [bytes] Data length.
+ */
+static inline uint8_t mavlink_msg_data64_get_len(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 1);
+}
+
+/**
+ * @brief Get field data from data64 message
+ *
+ * @return Raw data.
+ */
+static inline uint16_t mavlink_msg_data64_get_data(const mavlink_message_t* msg, uint8_t *data)
+{
+ return _MAV_RETURN_uint8_t_array(msg, data, 64, 2);
+}
+
+/**
+ * @brief Decode a data64 message into a struct
+ *
+ * @param msg The message to decode
+ * @param data64 C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_data64_decode(const mavlink_message_t* msg, mavlink_data64_t* data64)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ data64->type = mavlink_msg_data64_get_type(msg);
+ data64->len = mavlink_msg_data64_get_len(msg);
+ mavlink_msg_data64_get_data(msg, data64->data);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_DATA64_LEN? msg->len : MAVLINK_MSG_ID_DATA64_LEN;
+ memset(data64, 0, MAVLINK_MSG_ID_DATA64_LEN);
+ memcpy(data64, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/ardupilotmega/mavlink_msg_data96.h b/lib/main/MAVLink/ardupilotmega/mavlink_msg_data96.h
new file mode 100644
index 00000000000..8d283f9d68a
--- /dev/null
+++ b/lib/main/MAVLink/ardupilotmega/mavlink_msg_data96.h
@@ -0,0 +1,306 @@
+#pragma once
+// MESSAGE DATA96 PACKING
+
+#define MAVLINK_MSG_ID_DATA96 172
+
+
+typedef struct __mavlink_data96_t {
+ uint8_t type; /*< Data type.*/
+ uint8_t len; /*< [bytes] Data length.*/
+ uint8_t data[96]; /*< Raw data.*/
+} mavlink_data96_t;
+
+#define MAVLINK_MSG_ID_DATA96_LEN 98
+#define MAVLINK_MSG_ID_DATA96_MIN_LEN 98
+#define MAVLINK_MSG_ID_172_LEN 98
+#define MAVLINK_MSG_ID_172_MIN_LEN 98
+
+#define MAVLINK_MSG_ID_DATA96_CRC 22
+#define MAVLINK_MSG_ID_172_CRC 22
+
+#define MAVLINK_MSG_DATA96_FIELD_DATA_LEN 96
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_DATA96 { \
+ 172, \
+ "DATA96", \
+ 3, \
+ { { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_data96_t, type) }, \
+ { "len", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_data96_t, len) }, \
+ { "data", NULL, MAVLINK_TYPE_UINT8_T, 96, 2, offsetof(mavlink_data96_t, data) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_DATA96 { \
+ "DATA96", \
+ 3, \
+ { { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_data96_t, type) }, \
+ { "len", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_data96_t, len) }, \
+ { "data", NULL, MAVLINK_TYPE_UINT8_T, 96, 2, offsetof(mavlink_data96_t, data) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a data96 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 type Data type.
+ * @param len [bytes] Data length.
+ * @param data Raw data.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_data96_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint8_t type, uint8_t len, const uint8_t *data)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_DATA96_LEN];
+ _mav_put_uint8_t(buf, 0, type);
+ _mav_put_uint8_t(buf, 1, len);
+ _mav_put_uint8_t_array(buf, 2, data, 96);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DATA96_LEN);
+#else
+ mavlink_data96_t packet;
+ packet.type = type;
+ packet.len = len;
+ mav_array_assign_uint8_t(packet.data, data, 96);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DATA96_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_DATA96;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DATA96_MIN_LEN, MAVLINK_MSG_ID_DATA96_LEN, MAVLINK_MSG_ID_DATA96_CRC);
+}
+
+/**
+ * @brief Pack a data96 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 type Data type.
+ * @param len [bytes] Data length.
+ * @param data Raw data.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_data96_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ uint8_t type, uint8_t len, const uint8_t *data)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_DATA96_LEN];
+ _mav_put_uint8_t(buf, 0, type);
+ _mav_put_uint8_t(buf, 1, len);
+ _mav_put_uint8_t_array(buf, 2, data, 96);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DATA96_LEN);
+#else
+ mavlink_data96_t packet;
+ packet.type = type;
+ packet.len = len;
+ mav_array_memcpy(packet.data, data, sizeof(uint8_t)*96);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DATA96_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_DATA96;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_DATA96_MIN_LEN, MAVLINK_MSG_ID_DATA96_LEN, MAVLINK_MSG_ID_DATA96_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_DATA96_MIN_LEN, MAVLINK_MSG_ID_DATA96_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a data96 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 type Data type.
+ * @param len [bytes] Data length.
+ * @param data Raw data.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_data96_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint8_t type,uint8_t len,const uint8_t *data)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_DATA96_LEN];
+ _mav_put_uint8_t(buf, 0, type);
+ _mav_put_uint8_t(buf, 1, len);
+ _mav_put_uint8_t_array(buf, 2, data, 96);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DATA96_LEN);
+#else
+ mavlink_data96_t packet;
+ packet.type = type;
+ packet.len = len;
+ mav_array_assign_uint8_t(packet.data, data, 96);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DATA96_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_DATA96;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DATA96_MIN_LEN, MAVLINK_MSG_ID_DATA96_LEN, MAVLINK_MSG_ID_DATA96_CRC);
+}
+
+/**
+ * @brief Encode a data96 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 data96 C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_data96_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_data96_t* data96)
+{
+ return mavlink_msg_data96_pack(system_id, component_id, msg, data96->type, data96->len, data96->data);
+}
+
+/**
+ * @brief Encode a data96 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 data96 C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_data96_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_data96_t* data96)
+{
+ return mavlink_msg_data96_pack_chan(system_id, component_id, chan, msg, data96->type, data96->len, data96->data);
+}
+
+/**
+ * @brief Encode a data96 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 data96 C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_data96_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_data96_t* data96)
+{
+ return mavlink_msg_data96_pack_status(system_id, component_id, _status, msg, data96->type, data96->len, data96->data);
+}
+
+/**
+ * @brief Send a data96 message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param type Data type.
+ * @param len [bytes] Data length.
+ * @param data Raw data.
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_data96_send(mavlink_channel_t chan, uint8_t type, uint8_t len, const uint8_t *data)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_DATA96_LEN];
+ _mav_put_uint8_t(buf, 0, type);
+ _mav_put_uint8_t(buf, 1, len);
+ _mav_put_uint8_t_array(buf, 2, data, 96);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA96, buf, MAVLINK_MSG_ID_DATA96_MIN_LEN, MAVLINK_MSG_ID_DATA96_LEN, MAVLINK_MSG_ID_DATA96_CRC);
+#else
+ mavlink_data96_t packet;
+ packet.type = type;
+ packet.len = len;
+ mav_array_assign_uint8_t(packet.data, data, 96);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA96, (const char *)&packet, MAVLINK_MSG_ID_DATA96_MIN_LEN, MAVLINK_MSG_ID_DATA96_LEN, MAVLINK_MSG_ID_DATA96_CRC);
+#endif
+}
+
+/**
+ * @brief Send a data96 message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_data96_send_struct(mavlink_channel_t chan, const mavlink_data96_t* data96)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_data96_send(chan, data96->type, data96->len, data96->data);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA96, (const char *)data96, MAVLINK_MSG_ID_DATA96_MIN_LEN, MAVLINK_MSG_ID_DATA96_LEN, MAVLINK_MSG_ID_DATA96_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_DATA96_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_data96_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t type, uint8_t len, const uint8_t *data)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint8_t(buf, 0, type);
+ _mav_put_uint8_t(buf, 1, len);
+ _mav_put_uint8_t_array(buf, 2, data, 96);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA96, buf, MAVLINK_MSG_ID_DATA96_MIN_LEN, MAVLINK_MSG_ID_DATA96_LEN, MAVLINK_MSG_ID_DATA96_CRC);
+#else
+ mavlink_data96_t *packet = (mavlink_data96_t *)msgbuf;
+ packet->type = type;
+ packet->len = len;
+ mav_array_assign_uint8_t(packet->data, data, 96);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA96, (const char *)packet, MAVLINK_MSG_ID_DATA96_MIN_LEN, MAVLINK_MSG_ID_DATA96_LEN, MAVLINK_MSG_ID_DATA96_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE DATA96 UNPACKING
+
+
+/**
+ * @brief Get field type from data96 message
+ *
+ * @return Data type.
+ */
+static inline uint8_t mavlink_msg_data96_get_type(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 0);
+}
+
+/**
+ * @brief Get field len from data96 message
+ *
+ * @return [bytes] Data length.
+ */
+static inline uint8_t mavlink_msg_data96_get_len(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 1);
+}
+
+/**
+ * @brief Get field data from data96 message
+ *
+ * @return Raw data.
+ */
+static inline uint16_t mavlink_msg_data96_get_data(const mavlink_message_t* msg, uint8_t *data)
+{
+ return _MAV_RETURN_uint8_t_array(msg, data, 96, 2);
+}
+
+/**
+ * @brief Decode a data96 message into a struct
+ *
+ * @param msg The message to decode
+ * @param data96 C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_data96_decode(const mavlink_message_t* msg, mavlink_data96_t* data96)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ data96->type = mavlink_msg_data96_get_type(msg);
+ data96->len = mavlink_msg_data96_get_len(msg);
+ mavlink_msg_data96_get_data(msg, data96->data);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_DATA96_LEN? msg->len : MAVLINK_MSG_ID_DATA96_LEN;
+ memset(data96, 0, MAVLINK_MSG_ID_DATA96_LEN);
+ memcpy(data96, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/ardupilotmega/mavlink_msg_deepstall.h b/lib/main/MAVLink/ardupilotmega/mavlink_msg_deepstall.h
new file mode 100644
index 00000000000..489d6956405
--- /dev/null
+++ b/lib/main/MAVLink/ardupilotmega/mavlink_msg_deepstall.h
@@ -0,0 +1,512 @@
+#pragma once
+// MESSAGE DEEPSTALL PACKING
+
+#define MAVLINK_MSG_ID_DEEPSTALL 195
+
+
+typedef struct __mavlink_deepstall_t {
+ int32_t landing_lat; /*< [degE7] Landing latitude.*/
+ int32_t landing_lon; /*< [degE7] Landing longitude.*/
+ int32_t path_lat; /*< [degE7] Final heading start point, latitude.*/
+ int32_t path_lon; /*< [degE7] Final heading start point, longitude.*/
+ int32_t arc_entry_lat; /*< [degE7] Arc entry point, latitude.*/
+ int32_t arc_entry_lon; /*< [degE7] Arc entry point, longitude.*/
+ float altitude; /*< [m] Altitude.*/
+ float expected_travel_distance; /*< [m] Distance the aircraft expects to travel during the deepstall.*/
+ float cross_track_error; /*< [m] Deepstall cross track error (only valid when in DEEPSTALL_STAGE_LAND).*/
+ uint8_t stage; /*< Deepstall stage.*/
+} mavlink_deepstall_t;
+
+#define MAVLINK_MSG_ID_DEEPSTALL_LEN 37
+#define MAVLINK_MSG_ID_DEEPSTALL_MIN_LEN 37
+#define MAVLINK_MSG_ID_195_LEN 37
+#define MAVLINK_MSG_ID_195_MIN_LEN 37
+
+#define MAVLINK_MSG_ID_DEEPSTALL_CRC 120
+#define MAVLINK_MSG_ID_195_CRC 120
+
+
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_DEEPSTALL { \
+ 195, \
+ "DEEPSTALL", \
+ 10, \
+ { { "landing_lat", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_deepstall_t, landing_lat) }, \
+ { "landing_lon", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_deepstall_t, landing_lon) }, \
+ { "path_lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_deepstall_t, path_lat) }, \
+ { "path_lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_deepstall_t, path_lon) }, \
+ { "arc_entry_lat", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_deepstall_t, arc_entry_lat) }, \
+ { "arc_entry_lon", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_deepstall_t, arc_entry_lon) }, \
+ { "altitude", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_deepstall_t, altitude) }, \
+ { "expected_travel_distance", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_deepstall_t, expected_travel_distance) }, \
+ { "cross_track_error", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_deepstall_t, cross_track_error) }, \
+ { "stage", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_deepstall_t, stage) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_DEEPSTALL { \
+ "DEEPSTALL", \
+ 10, \
+ { { "landing_lat", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_deepstall_t, landing_lat) }, \
+ { "landing_lon", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_deepstall_t, landing_lon) }, \
+ { "path_lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_deepstall_t, path_lat) }, \
+ { "path_lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_deepstall_t, path_lon) }, \
+ { "arc_entry_lat", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_deepstall_t, arc_entry_lat) }, \
+ { "arc_entry_lon", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_deepstall_t, arc_entry_lon) }, \
+ { "altitude", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_deepstall_t, altitude) }, \
+ { "expected_travel_distance", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_deepstall_t, expected_travel_distance) }, \
+ { "cross_track_error", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_deepstall_t, cross_track_error) }, \
+ { "stage", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_deepstall_t, stage) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a deepstall 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 landing_lat [degE7] Landing latitude.
+ * @param landing_lon [degE7] Landing longitude.
+ * @param path_lat [degE7] Final heading start point, latitude.
+ * @param path_lon [degE7] Final heading start point, longitude.
+ * @param arc_entry_lat [degE7] Arc entry point, latitude.
+ * @param arc_entry_lon [degE7] Arc entry point, longitude.
+ * @param altitude [m] Altitude.
+ * @param expected_travel_distance [m] Distance the aircraft expects to travel during the deepstall.
+ * @param cross_track_error [m] Deepstall cross track error (only valid when in DEEPSTALL_STAGE_LAND).
+ * @param stage Deepstall stage.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_deepstall_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ int32_t landing_lat, int32_t landing_lon, int32_t path_lat, int32_t path_lon, int32_t arc_entry_lat, int32_t arc_entry_lon, float altitude, float expected_travel_distance, float cross_track_error, uint8_t stage)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_DEEPSTALL_LEN];
+ _mav_put_int32_t(buf, 0, landing_lat);
+ _mav_put_int32_t(buf, 4, landing_lon);
+ _mav_put_int32_t(buf, 8, path_lat);
+ _mav_put_int32_t(buf, 12, path_lon);
+ _mav_put_int32_t(buf, 16, arc_entry_lat);
+ _mav_put_int32_t(buf, 20, arc_entry_lon);
+ _mav_put_float(buf, 24, altitude);
+ _mav_put_float(buf, 28, expected_travel_distance);
+ _mav_put_float(buf, 32, cross_track_error);
+ _mav_put_uint8_t(buf, 36, stage);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DEEPSTALL_LEN);
+#else
+ mavlink_deepstall_t packet;
+ packet.landing_lat = landing_lat;
+ packet.landing_lon = landing_lon;
+ packet.path_lat = path_lat;
+ packet.path_lon = path_lon;
+ packet.arc_entry_lat = arc_entry_lat;
+ packet.arc_entry_lon = arc_entry_lon;
+ packet.altitude = altitude;
+ packet.expected_travel_distance = expected_travel_distance;
+ packet.cross_track_error = cross_track_error;
+ packet.stage = stage;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DEEPSTALL_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_DEEPSTALL;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DEEPSTALL_MIN_LEN, MAVLINK_MSG_ID_DEEPSTALL_LEN, MAVLINK_MSG_ID_DEEPSTALL_CRC);
+}
+
+/**
+ * @brief Pack a deepstall 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 landing_lat [degE7] Landing latitude.
+ * @param landing_lon [degE7] Landing longitude.
+ * @param path_lat [degE7] Final heading start point, latitude.
+ * @param path_lon [degE7] Final heading start point, longitude.
+ * @param arc_entry_lat [degE7] Arc entry point, latitude.
+ * @param arc_entry_lon [degE7] Arc entry point, longitude.
+ * @param altitude [m] Altitude.
+ * @param expected_travel_distance [m] Distance the aircraft expects to travel during the deepstall.
+ * @param cross_track_error [m] Deepstall cross track error (only valid when in DEEPSTALL_STAGE_LAND).
+ * @param stage Deepstall stage.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_deepstall_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ int32_t landing_lat, int32_t landing_lon, int32_t path_lat, int32_t path_lon, int32_t arc_entry_lat, int32_t arc_entry_lon, float altitude, float expected_travel_distance, float cross_track_error, uint8_t stage)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_DEEPSTALL_LEN];
+ _mav_put_int32_t(buf, 0, landing_lat);
+ _mav_put_int32_t(buf, 4, landing_lon);
+ _mav_put_int32_t(buf, 8, path_lat);
+ _mav_put_int32_t(buf, 12, path_lon);
+ _mav_put_int32_t(buf, 16, arc_entry_lat);
+ _mav_put_int32_t(buf, 20, arc_entry_lon);
+ _mav_put_float(buf, 24, altitude);
+ _mav_put_float(buf, 28, expected_travel_distance);
+ _mav_put_float(buf, 32, cross_track_error);
+ _mav_put_uint8_t(buf, 36, stage);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DEEPSTALL_LEN);
+#else
+ mavlink_deepstall_t packet;
+ packet.landing_lat = landing_lat;
+ packet.landing_lon = landing_lon;
+ packet.path_lat = path_lat;
+ packet.path_lon = path_lon;
+ packet.arc_entry_lat = arc_entry_lat;
+ packet.arc_entry_lon = arc_entry_lon;
+ packet.altitude = altitude;
+ packet.expected_travel_distance = expected_travel_distance;
+ packet.cross_track_error = cross_track_error;
+ packet.stage = stage;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DEEPSTALL_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_DEEPSTALL;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_DEEPSTALL_MIN_LEN, MAVLINK_MSG_ID_DEEPSTALL_LEN, MAVLINK_MSG_ID_DEEPSTALL_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_DEEPSTALL_MIN_LEN, MAVLINK_MSG_ID_DEEPSTALL_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a deepstall 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 landing_lat [degE7] Landing latitude.
+ * @param landing_lon [degE7] Landing longitude.
+ * @param path_lat [degE7] Final heading start point, latitude.
+ * @param path_lon [degE7] Final heading start point, longitude.
+ * @param arc_entry_lat [degE7] Arc entry point, latitude.
+ * @param arc_entry_lon [degE7] Arc entry point, longitude.
+ * @param altitude [m] Altitude.
+ * @param expected_travel_distance [m] Distance the aircraft expects to travel during the deepstall.
+ * @param cross_track_error [m] Deepstall cross track error (only valid when in DEEPSTALL_STAGE_LAND).
+ * @param stage Deepstall stage.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_deepstall_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ int32_t landing_lat,int32_t landing_lon,int32_t path_lat,int32_t path_lon,int32_t arc_entry_lat,int32_t arc_entry_lon,float altitude,float expected_travel_distance,float cross_track_error,uint8_t stage)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_DEEPSTALL_LEN];
+ _mav_put_int32_t(buf, 0, landing_lat);
+ _mav_put_int32_t(buf, 4, landing_lon);
+ _mav_put_int32_t(buf, 8, path_lat);
+ _mav_put_int32_t(buf, 12, path_lon);
+ _mav_put_int32_t(buf, 16, arc_entry_lat);
+ _mav_put_int32_t(buf, 20, arc_entry_lon);
+ _mav_put_float(buf, 24, altitude);
+ _mav_put_float(buf, 28, expected_travel_distance);
+ _mav_put_float(buf, 32, cross_track_error);
+ _mav_put_uint8_t(buf, 36, stage);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DEEPSTALL_LEN);
+#else
+ mavlink_deepstall_t packet;
+ packet.landing_lat = landing_lat;
+ packet.landing_lon = landing_lon;
+ packet.path_lat = path_lat;
+ packet.path_lon = path_lon;
+ packet.arc_entry_lat = arc_entry_lat;
+ packet.arc_entry_lon = arc_entry_lon;
+ packet.altitude = altitude;
+ packet.expected_travel_distance = expected_travel_distance;
+ packet.cross_track_error = cross_track_error;
+ packet.stage = stage;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DEEPSTALL_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_DEEPSTALL;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DEEPSTALL_MIN_LEN, MAVLINK_MSG_ID_DEEPSTALL_LEN, MAVLINK_MSG_ID_DEEPSTALL_CRC);
+}
+
+/**
+ * @brief Encode a deepstall 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 deepstall C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_deepstall_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_deepstall_t* deepstall)
+{
+ return mavlink_msg_deepstall_pack(system_id, component_id, msg, deepstall->landing_lat, deepstall->landing_lon, deepstall->path_lat, deepstall->path_lon, deepstall->arc_entry_lat, deepstall->arc_entry_lon, deepstall->altitude, deepstall->expected_travel_distance, deepstall->cross_track_error, deepstall->stage);
+}
+
+/**
+ * @brief Encode a deepstall 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 deepstall C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_deepstall_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_deepstall_t* deepstall)
+{
+ return mavlink_msg_deepstall_pack_chan(system_id, component_id, chan, msg, deepstall->landing_lat, deepstall->landing_lon, deepstall->path_lat, deepstall->path_lon, deepstall->arc_entry_lat, deepstall->arc_entry_lon, deepstall->altitude, deepstall->expected_travel_distance, deepstall->cross_track_error, deepstall->stage);
+}
+
+/**
+ * @brief Encode a deepstall 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 deepstall C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_deepstall_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_deepstall_t* deepstall)
+{
+ return mavlink_msg_deepstall_pack_status(system_id, component_id, _status, msg, deepstall->landing_lat, deepstall->landing_lon, deepstall->path_lat, deepstall->path_lon, deepstall->arc_entry_lat, deepstall->arc_entry_lon, deepstall->altitude, deepstall->expected_travel_distance, deepstall->cross_track_error, deepstall->stage);
+}
+
+/**
+ * @brief Send a deepstall message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param landing_lat [degE7] Landing latitude.
+ * @param landing_lon [degE7] Landing longitude.
+ * @param path_lat [degE7] Final heading start point, latitude.
+ * @param path_lon [degE7] Final heading start point, longitude.
+ * @param arc_entry_lat [degE7] Arc entry point, latitude.
+ * @param arc_entry_lon [degE7] Arc entry point, longitude.
+ * @param altitude [m] Altitude.
+ * @param expected_travel_distance [m] Distance the aircraft expects to travel during the deepstall.
+ * @param cross_track_error [m] Deepstall cross track error (only valid when in DEEPSTALL_STAGE_LAND).
+ * @param stage Deepstall stage.
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_deepstall_send(mavlink_channel_t chan, int32_t landing_lat, int32_t landing_lon, int32_t path_lat, int32_t path_lon, int32_t arc_entry_lat, int32_t arc_entry_lon, float altitude, float expected_travel_distance, float cross_track_error, uint8_t stage)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_DEEPSTALL_LEN];
+ _mav_put_int32_t(buf, 0, landing_lat);
+ _mav_put_int32_t(buf, 4, landing_lon);
+ _mav_put_int32_t(buf, 8, path_lat);
+ _mav_put_int32_t(buf, 12, path_lon);
+ _mav_put_int32_t(buf, 16, arc_entry_lat);
+ _mav_put_int32_t(buf, 20, arc_entry_lon);
+ _mav_put_float(buf, 24, altitude);
+ _mav_put_float(buf, 28, expected_travel_distance);
+ _mav_put_float(buf, 32, cross_track_error);
+ _mav_put_uint8_t(buf, 36, stage);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEEPSTALL, buf, MAVLINK_MSG_ID_DEEPSTALL_MIN_LEN, MAVLINK_MSG_ID_DEEPSTALL_LEN, MAVLINK_MSG_ID_DEEPSTALL_CRC);
+#else
+ mavlink_deepstall_t packet;
+ packet.landing_lat = landing_lat;
+ packet.landing_lon = landing_lon;
+ packet.path_lat = path_lat;
+ packet.path_lon = path_lon;
+ packet.arc_entry_lat = arc_entry_lat;
+ packet.arc_entry_lon = arc_entry_lon;
+ packet.altitude = altitude;
+ packet.expected_travel_distance = expected_travel_distance;
+ packet.cross_track_error = cross_track_error;
+ packet.stage = stage;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEEPSTALL, (const char *)&packet, MAVLINK_MSG_ID_DEEPSTALL_MIN_LEN, MAVLINK_MSG_ID_DEEPSTALL_LEN, MAVLINK_MSG_ID_DEEPSTALL_CRC);
+#endif
+}
+
+/**
+ * @brief Send a deepstall message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_deepstall_send_struct(mavlink_channel_t chan, const mavlink_deepstall_t* deepstall)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_deepstall_send(chan, deepstall->landing_lat, deepstall->landing_lon, deepstall->path_lat, deepstall->path_lon, deepstall->arc_entry_lat, deepstall->arc_entry_lon, deepstall->altitude, deepstall->expected_travel_distance, deepstall->cross_track_error, deepstall->stage);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEEPSTALL, (const char *)deepstall, MAVLINK_MSG_ID_DEEPSTALL_MIN_LEN, MAVLINK_MSG_ID_DEEPSTALL_LEN, MAVLINK_MSG_ID_DEEPSTALL_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_DEEPSTALL_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_deepstall_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, int32_t landing_lat, int32_t landing_lon, int32_t path_lat, int32_t path_lon, int32_t arc_entry_lat, int32_t arc_entry_lon, float altitude, float expected_travel_distance, float cross_track_error, uint8_t stage)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_int32_t(buf, 0, landing_lat);
+ _mav_put_int32_t(buf, 4, landing_lon);
+ _mav_put_int32_t(buf, 8, path_lat);
+ _mav_put_int32_t(buf, 12, path_lon);
+ _mav_put_int32_t(buf, 16, arc_entry_lat);
+ _mav_put_int32_t(buf, 20, arc_entry_lon);
+ _mav_put_float(buf, 24, altitude);
+ _mav_put_float(buf, 28, expected_travel_distance);
+ _mav_put_float(buf, 32, cross_track_error);
+ _mav_put_uint8_t(buf, 36, stage);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEEPSTALL, buf, MAVLINK_MSG_ID_DEEPSTALL_MIN_LEN, MAVLINK_MSG_ID_DEEPSTALL_LEN, MAVLINK_MSG_ID_DEEPSTALL_CRC);
+#else
+ mavlink_deepstall_t *packet = (mavlink_deepstall_t *)msgbuf;
+ packet->landing_lat = landing_lat;
+ packet->landing_lon = landing_lon;
+ packet->path_lat = path_lat;
+ packet->path_lon = path_lon;
+ packet->arc_entry_lat = arc_entry_lat;
+ packet->arc_entry_lon = arc_entry_lon;
+ packet->altitude = altitude;
+ packet->expected_travel_distance = expected_travel_distance;
+ packet->cross_track_error = cross_track_error;
+ packet->stage = stage;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEEPSTALL, (const char *)packet, MAVLINK_MSG_ID_DEEPSTALL_MIN_LEN, MAVLINK_MSG_ID_DEEPSTALL_LEN, MAVLINK_MSG_ID_DEEPSTALL_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE DEEPSTALL UNPACKING
+
+
+/**
+ * @brief Get field landing_lat from deepstall message
+ *
+ * @return [degE7] Landing latitude.
+ */
+static inline int32_t mavlink_msg_deepstall_get_landing_lat(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_int32_t(msg, 0);
+}
+
+/**
+ * @brief Get field landing_lon from deepstall message
+ *
+ * @return [degE7] Landing longitude.
+ */
+static inline int32_t mavlink_msg_deepstall_get_landing_lon(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_int32_t(msg, 4);
+}
+
+/**
+ * @brief Get field path_lat from deepstall message
+ *
+ * @return [degE7] Final heading start point, latitude.
+ */
+static inline int32_t mavlink_msg_deepstall_get_path_lat(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_int32_t(msg, 8);
+}
+
+/**
+ * @brief Get field path_lon from deepstall message
+ *
+ * @return [degE7] Final heading start point, longitude.
+ */
+static inline int32_t mavlink_msg_deepstall_get_path_lon(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_int32_t(msg, 12);
+}
+
+/**
+ * @brief Get field arc_entry_lat from deepstall message
+ *
+ * @return [degE7] Arc entry point, latitude.
+ */
+static inline int32_t mavlink_msg_deepstall_get_arc_entry_lat(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_int32_t(msg, 16);
+}
+
+/**
+ * @brief Get field arc_entry_lon from deepstall message
+ *
+ * @return [degE7] Arc entry point, longitude.
+ */
+static inline int32_t mavlink_msg_deepstall_get_arc_entry_lon(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_int32_t(msg, 20);
+}
+
+/**
+ * @brief Get field altitude from deepstall message
+ *
+ * @return [m] Altitude.
+ */
+static inline float mavlink_msg_deepstall_get_altitude(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 24);
+}
+
+/**
+ * @brief Get field expected_travel_distance from deepstall message
+ *
+ * @return [m] Distance the aircraft expects to travel during the deepstall.
+ */
+static inline float mavlink_msg_deepstall_get_expected_travel_distance(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 28);
+}
+
+/**
+ * @brief Get field cross_track_error from deepstall message
+ *
+ * @return [m] Deepstall cross track error (only valid when in DEEPSTALL_STAGE_LAND).
+ */
+static inline float mavlink_msg_deepstall_get_cross_track_error(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 32);
+}
+
+/**
+ * @brief Get field stage from deepstall message
+ *
+ * @return Deepstall stage.
+ */
+static inline uint8_t mavlink_msg_deepstall_get_stage(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 36);
+}
+
+/**
+ * @brief Decode a deepstall message into a struct
+ *
+ * @param msg The message to decode
+ * @param deepstall C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_deepstall_decode(const mavlink_message_t* msg, mavlink_deepstall_t* deepstall)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ deepstall->landing_lat = mavlink_msg_deepstall_get_landing_lat(msg);
+ deepstall->landing_lon = mavlink_msg_deepstall_get_landing_lon(msg);
+ deepstall->path_lat = mavlink_msg_deepstall_get_path_lat(msg);
+ deepstall->path_lon = mavlink_msg_deepstall_get_path_lon(msg);
+ deepstall->arc_entry_lat = mavlink_msg_deepstall_get_arc_entry_lat(msg);
+ deepstall->arc_entry_lon = mavlink_msg_deepstall_get_arc_entry_lon(msg);
+ deepstall->altitude = mavlink_msg_deepstall_get_altitude(msg);
+ deepstall->expected_travel_distance = mavlink_msg_deepstall_get_expected_travel_distance(msg);
+ deepstall->cross_track_error = mavlink_msg_deepstall_get_cross_track_error(msg);
+ deepstall->stage = mavlink_msg_deepstall_get_stage(msg);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_DEEPSTALL_LEN? msg->len : MAVLINK_MSG_ID_DEEPSTALL_LEN;
+ memset(deepstall, 0, MAVLINK_MSG_ID_DEEPSTALL_LEN);
+ memcpy(deepstall, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/ardupilotmega/mavlink_msg_device_op_read.h b/lib/main/MAVLink/ardupilotmega/mavlink_msg_device_op_read.h
new file mode 100644
index 00000000000..3920ec8f0bc
--- /dev/null
+++ b/lib/main/MAVLink/ardupilotmega/mavlink_msg_device_op_read.h
@@ -0,0 +1,502 @@
+#pragma once
+// MESSAGE DEVICE_OP_READ PACKING
+
+#define MAVLINK_MSG_ID_DEVICE_OP_READ 11000
+
+
+typedef struct __mavlink_device_op_read_t {
+ uint32_t request_id; /*< Request ID - copied to reply.*/
+ uint8_t target_system; /*< System ID.*/
+ uint8_t target_component; /*< Component ID.*/
+ uint8_t bustype; /*< The bus type.*/
+ uint8_t bus; /*< Bus number.*/
+ uint8_t address; /*< Bus address.*/
+ char busname[40]; /*< Name of device on bus (for SPI).*/
+ uint8_t regstart; /*< First register to read.*/
+ uint8_t count; /*< Count of registers to read.*/
+ uint8_t bank; /*< Bank number.*/
+} mavlink_device_op_read_t;
+
+#define MAVLINK_MSG_ID_DEVICE_OP_READ_LEN 52
+#define MAVLINK_MSG_ID_DEVICE_OP_READ_MIN_LEN 51
+#define MAVLINK_MSG_ID_11000_LEN 52
+#define MAVLINK_MSG_ID_11000_MIN_LEN 51
+
+#define MAVLINK_MSG_ID_DEVICE_OP_READ_CRC 134
+#define MAVLINK_MSG_ID_11000_CRC 134
+
+#define MAVLINK_MSG_DEVICE_OP_READ_FIELD_BUSNAME_LEN 40
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_DEVICE_OP_READ { \
+ 11000, \
+ "DEVICE_OP_READ", \
+ 10, \
+ { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_device_op_read_t, target_system) }, \
+ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_device_op_read_t, target_component) }, \
+ { "request_id", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_device_op_read_t, request_id) }, \
+ { "bustype", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_device_op_read_t, bustype) }, \
+ { "bus", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_device_op_read_t, bus) }, \
+ { "address", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_device_op_read_t, address) }, \
+ { "busname", NULL, MAVLINK_TYPE_CHAR, 40, 9, offsetof(mavlink_device_op_read_t, busname) }, \
+ { "regstart", NULL, MAVLINK_TYPE_UINT8_T, 0, 49, offsetof(mavlink_device_op_read_t, regstart) }, \
+ { "count", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_device_op_read_t, count) }, \
+ { "bank", NULL, MAVLINK_TYPE_UINT8_T, 0, 51, offsetof(mavlink_device_op_read_t, bank) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_DEVICE_OP_READ { \
+ "DEVICE_OP_READ", \
+ 10, \
+ { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_device_op_read_t, target_system) }, \
+ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_device_op_read_t, target_component) }, \
+ { "request_id", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_device_op_read_t, request_id) }, \
+ { "bustype", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_device_op_read_t, bustype) }, \
+ { "bus", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_device_op_read_t, bus) }, \
+ { "address", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_device_op_read_t, address) }, \
+ { "busname", NULL, MAVLINK_TYPE_CHAR, 40, 9, offsetof(mavlink_device_op_read_t, busname) }, \
+ { "regstart", NULL, MAVLINK_TYPE_UINT8_T, 0, 49, offsetof(mavlink_device_op_read_t, regstart) }, \
+ { "count", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_device_op_read_t, count) }, \
+ { "bank", NULL, MAVLINK_TYPE_UINT8_T, 0, 51, offsetof(mavlink_device_op_read_t, bank) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a device_op_read 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 target_system System ID.
+ * @param target_component Component ID.
+ * @param request_id Request ID - copied to reply.
+ * @param bustype The bus type.
+ * @param bus Bus number.
+ * @param address Bus address.
+ * @param busname Name of device on bus (for SPI).
+ * @param regstart First register to read.
+ * @param count Count of registers to read.
+ * @param bank Bank number.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_device_op_read_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint8_t target_system, uint8_t target_component, uint32_t request_id, uint8_t bustype, uint8_t bus, uint8_t address, const char *busname, uint8_t regstart, uint8_t count, uint8_t bank)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_DEVICE_OP_READ_LEN];
+ _mav_put_uint32_t(buf, 0, request_id);
+ _mav_put_uint8_t(buf, 4, target_system);
+ _mav_put_uint8_t(buf, 5, target_component);
+ _mav_put_uint8_t(buf, 6, bustype);
+ _mav_put_uint8_t(buf, 7, bus);
+ _mav_put_uint8_t(buf, 8, address);
+ _mav_put_uint8_t(buf, 49, regstart);
+ _mav_put_uint8_t(buf, 50, count);
+ _mav_put_uint8_t(buf, 51, bank);
+ _mav_put_char_array(buf, 9, busname, 40);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DEVICE_OP_READ_LEN);
+#else
+ mavlink_device_op_read_t packet;
+ packet.request_id = request_id;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.bustype = bustype;
+ packet.bus = bus;
+ packet.address = address;
+ packet.regstart = regstart;
+ packet.count = count;
+ packet.bank = bank;
+ mav_array_assign_char(packet.busname, busname, 40);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DEVICE_OP_READ_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_DEVICE_OP_READ;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DEVICE_OP_READ_MIN_LEN, MAVLINK_MSG_ID_DEVICE_OP_READ_LEN, MAVLINK_MSG_ID_DEVICE_OP_READ_CRC);
+}
+
+/**
+ * @brief Pack a device_op_read 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 target_system System ID.
+ * @param target_component Component ID.
+ * @param request_id Request ID - copied to reply.
+ * @param bustype The bus type.
+ * @param bus Bus number.
+ * @param address Bus address.
+ * @param busname Name of device on bus (for SPI).
+ * @param regstart First register to read.
+ * @param count Count of registers to read.
+ * @param bank Bank number.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_device_op_read_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ uint8_t target_system, uint8_t target_component, uint32_t request_id, uint8_t bustype, uint8_t bus, uint8_t address, const char *busname, uint8_t regstart, uint8_t count, uint8_t bank)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_DEVICE_OP_READ_LEN];
+ _mav_put_uint32_t(buf, 0, request_id);
+ _mav_put_uint8_t(buf, 4, target_system);
+ _mav_put_uint8_t(buf, 5, target_component);
+ _mav_put_uint8_t(buf, 6, bustype);
+ _mav_put_uint8_t(buf, 7, bus);
+ _mav_put_uint8_t(buf, 8, address);
+ _mav_put_uint8_t(buf, 49, regstart);
+ _mav_put_uint8_t(buf, 50, count);
+ _mav_put_uint8_t(buf, 51, bank);
+ _mav_put_char_array(buf, 9, busname, 40);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DEVICE_OP_READ_LEN);
+#else
+ mavlink_device_op_read_t packet;
+ packet.request_id = request_id;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.bustype = bustype;
+ packet.bus = bus;
+ packet.address = address;
+ packet.regstart = regstart;
+ packet.count = count;
+ packet.bank = bank;
+ mav_array_memcpy(packet.busname, busname, sizeof(char)*40);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DEVICE_OP_READ_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_DEVICE_OP_READ;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_DEVICE_OP_READ_MIN_LEN, MAVLINK_MSG_ID_DEVICE_OP_READ_LEN, MAVLINK_MSG_ID_DEVICE_OP_READ_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_DEVICE_OP_READ_MIN_LEN, MAVLINK_MSG_ID_DEVICE_OP_READ_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a device_op_read 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 target_system System ID.
+ * @param target_component Component ID.
+ * @param request_id Request ID - copied to reply.
+ * @param bustype The bus type.
+ * @param bus Bus number.
+ * @param address Bus address.
+ * @param busname Name of device on bus (for SPI).
+ * @param regstart First register to read.
+ * @param count Count of registers to read.
+ * @param bank Bank number.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_device_op_read_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint8_t target_system,uint8_t target_component,uint32_t request_id,uint8_t bustype,uint8_t bus,uint8_t address,const char *busname,uint8_t regstart,uint8_t count,uint8_t bank)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_DEVICE_OP_READ_LEN];
+ _mav_put_uint32_t(buf, 0, request_id);
+ _mav_put_uint8_t(buf, 4, target_system);
+ _mav_put_uint8_t(buf, 5, target_component);
+ _mav_put_uint8_t(buf, 6, bustype);
+ _mav_put_uint8_t(buf, 7, bus);
+ _mav_put_uint8_t(buf, 8, address);
+ _mav_put_uint8_t(buf, 49, regstart);
+ _mav_put_uint8_t(buf, 50, count);
+ _mav_put_uint8_t(buf, 51, bank);
+ _mav_put_char_array(buf, 9, busname, 40);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DEVICE_OP_READ_LEN);
+#else
+ mavlink_device_op_read_t packet;
+ packet.request_id = request_id;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.bustype = bustype;
+ packet.bus = bus;
+ packet.address = address;
+ packet.regstart = regstart;
+ packet.count = count;
+ packet.bank = bank;
+ mav_array_assign_char(packet.busname, busname, 40);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DEVICE_OP_READ_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_DEVICE_OP_READ;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DEVICE_OP_READ_MIN_LEN, MAVLINK_MSG_ID_DEVICE_OP_READ_LEN, MAVLINK_MSG_ID_DEVICE_OP_READ_CRC);
+}
+
+/**
+ * @brief Encode a device_op_read 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 device_op_read C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_device_op_read_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_device_op_read_t* device_op_read)
+{
+ return mavlink_msg_device_op_read_pack(system_id, component_id, msg, device_op_read->target_system, device_op_read->target_component, device_op_read->request_id, device_op_read->bustype, device_op_read->bus, device_op_read->address, device_op_read->busname, device_op_read->regstart, device_op_read->count, device_op_read->bank);
+}
+
+/**
+ * @brief Encode a device_op_read 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 device_op_read C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_device_op_read_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_device_op_read_t* device_op_read)
+{
+ return mavlink_msg_device_op_read_pack_chan(system_id, component_id, chan, msg, device_op_read->target_system, device_op_read->target_component, device_op_read->request_id, device_op_read->bustype, device_op_read->bus, device_op_read->address, device_op_read->busname, device_op_read->regstart, device_op_read->count, device_op_read->bank);
+}
+
+/**
+ * @brief Encode a device_op_read 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 device_op_read C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_device_op_read_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_device_op_read_t* device_op_read)
+{
+ return mavlink_msg_device_op_read_pack_status(system_id, component_id, _status, msg, device_op_read->target_system, device_op_read->target_component, device_op_read->request_id, device_op_read->bustype, device_op_read->bus, device_op_read->address, device_op_read->busname, device_op_read->regstart, device_op_read->count, device_op_read->bank);
+}
+
+/**
+ * @brief Send a device_op_read message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param target_system System ID.
+ * @param target_component Component ID.
+ * @param request_id Request ID - copied to reply.
+ * @param bustype The bus type.
+ * @param bus Bus number.
+ * @param address Bus address.
+ * @param busname Name of device on bus (for SPI).
+ * @param regstart First register to read.
+ * @param count Count of registers to read.
+ * @param bank Bank number.
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_device_op_read_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint32_t request_id, uint8_t bustype, uint8_t bus, uint8_t address, const char *busname, uint8_t regstart, uint8_t count, uint8_t bank)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_DEVICE_OP_READ_LEN];
+ _mav_put_uint32_t(buf, 0, request_id);
+ _mav_put_uint8_t(buf, 4, target_system);
+ _mav_put_uint8_t(buf, 5, target_component);
+ _mav_put_uint8_t(buf, 6, bustype);
+ _mav_put_uint8_t(buf, 7, bus);
+ _mav_put_uint8_t(buf, 8, address);
+ _mav_put_uint8_t(buf, 49, regstart);
+ _mav_put_uint8_t(buf, 50, count);
+ _mav_put_uint8_t(buf, 51, bank);
+ _mav_put_char_array(buf, 9, busname, 40);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEVICE_OP_READ, buf, MAVLINK_MSG_ID_DEVICE_OP_READ_MIN_LEN, MAVLINK_MSG_ID_DEVICE_OP_READ_LEN, MAVLINK_MSG_ID_DEVICE_OP_READ_CRC);
+#else
+ mavlink_device_op_read_t packet;
+ packet.request_id = request_id;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.bustype = bustype;
+ packet.bus = bus;
+ packet.address = address;
+ packet.regstart = regstart;
+ packet.count = count;
+ packet.bank = bank;
+ mav_array_assign_char(packet.busname, busname, 40);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEVICE_OP_READ, (const char *)&packet, MAVLINK_MSG_ID_DEVICE_OP_READ_MIN_LEN, MAVLINK_MSG_ID_DEVICE_OP_READ_LEN, MAVLINK_MSG_ID_DEVICE_OP_READ_CRC);
+#endif
+}
+
+/**
+ * @brief Send a device_op_read message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_device_op_read_send_struct(mavlink_channel_t chan, const mavlink_device_op_read_t* device_op_read)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_device_op_read_send(chan, device_op_read->target_system, device_op_read->target_component, device_op_read->request_id, device_op_read->bustype, device_op_read->bus, device_op_read->address, device_op_read->busname, device_op_read->regstart, device_op_read->count, device_op_read->bank);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEVICE_OP_READ, (const char *)device_op_read, MAVLINK_MSG_ID_DEVICE_OP_READ_MIN_LEN, MAVLINK_MSG_ID_DEVICE_OP_READ_LEN, MAVLINK_MSG_ID_DEVICE_OP_READ_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_DEVICE_OP_READ_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_device_op_read_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint32_t request_id, uint8_t bustype, uint8_t bus, uint8_t address, const char *busname, uint8_t regstart, uint8_t count, uint8_t bank)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint32_t(buf, 0, request_id);
+ _mav_put_uint8_t(buf, 4, target_system);
+ _mav_put_uint8_t(buf, 5, target_component);
+ _mav_put_uint8_t(buf, 6, bustype);
+ _mav_put_uint8_t(buf, 7, bus);
+ _mav_put_uint8_t(buf, 8, address);
+ _mav_put_uint8_t(buf, 49, regstart);
+ _mav_put_uint8_t(buf, 50, count);
+ _mav_put_uint8_t(buf, 51, bank);
+ _mav_put_char_array(buf, 9, busname, 40);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEVICE_OP_READ, buf, MAVLINK_MSG_ID_DEVICE_OP_READ_MIN_LEN, MAVLINK_MSG_ID_DEVICE_OP_READ_LEN, MAVLINK_MSG_ID_DEVICE_OP_READ_CRC);
+#else
+ mavlink_device_op_read_t *packet = (mavlink_device_op_read_t *)msgbuf;
+ packet->request_id = request_id;
+ packet->target_system = target_system;
+ packet->target_component = target_component;
+ packet->bustype = bustype;
+ packet->bus = bus;
+ packet->address = address;
+ packet->regstart = regstart;
+ packet->count = count;
+ packet->bank = bank;
+ mav_array_assign_char(packet->busname, busname, 40);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEVICE_OP_READ, (const char *)packet, MAVLINK_MSG_ID_DEVICE_OP_READ_MIN_LEN, MAVLINK_MSG_ID_DEVICE_OP_READ_LEN, MAVLINK_MSG_ID_DEVICE_OP_READ_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE DEVICE_OP_READ UNPACKING
+
+
+/**
+ * @brief Get field target_system from device_op_read message
+ *
+ * @return System ID.
+ */
+static inline uint8_t mavlink_msg_device_op_read_get_target_system(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 4);
+}
+
+/**
+ * @brief Get field target_component from device_op_read message
+ *
+ * @return Component ID.
+ */
+static inline uint8_t mavlink_msg_device_op_read_get_target_component(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 5);
+}
+
+/**
+ * @brief Get field request_id from device_op_read message
+ *
+ * @return Request ID - copied to reply.
+ */
+static inline uint32_t mavlink_msg_device_op_read_get_request_id(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint32_t(msg, 0);
+}
+
+/**
+ * @brief Get field bustype from device_op_read message
+ *
+ * @return The bus type.
+ */
+static inline uint8_t mavlink_msg_device_op_read_get_bustype(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 6);
+}
+
+/**
+ * @brief Get field bus from device_op_read message
+ *
+ * @return Bus number.
+ */
+static inline uint8_t mavlink_msg_device_op_read_get_bus(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 7);
+}
+
+/**
+ * @brief Get field address from device_op_read message
+ *
+ * @return Bus address.
+ */
+static inline uint8_t mavlink_msg_device_op_read_get_address(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 8);
+}
+
+/**
+ * @brief Get field busname from device_op_read message
+ *
+ * @return Name of device on bus (for SPI).
+ */
+static inline uint16_t mavlink_msg_device_op_read_get_busname(const mavlink_message_t* msg, char *busname)
+{
+ return _MAV_RETURN_char_array(msg, busname, 40, 9);
+}
+
+/**
+ * @brief Get field regstart from device_op_read message
+ *
+ * @return First register to read.
+ */
+static inline uint8_t mavlink_msg_device_op_read_get_regstart(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 49);
+}
+
+/**
+ * @brief Get field count from device_op_read message
+ *
+ * @return Count of registers to read.
+ */
+static inline uint8_t mavlink_msg_device_op_read_get_count(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 50);
+}
+
+/**
+ * @brief Get field bank from device_op_read message
+ *
+ * @return Bank number.
+ */
+static inline uint8_t mavlink_msg_device_op_read_get_bank(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 51);
+}
+
+/**
+ * @brief Decode a device_op_read message into a struct
+ *
+ * @param msg The message to decode
+ * @param device_op_read C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_device_op_read_decode(const mavlink_message_t* msg, mavlink_device_op_read_t* device_op_read)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ device_op_read->request_id = mavlink_msg_device_op_read_get_request_id(msg);
+ device_op_read->target_system = mavlink_msg_device_op_read_get_target_system(msg);
+ device_op_read->target_component = mavlink_msg_device_op_read_get_target_component(msg);
+ device_op_read->bustype = mavlink_msg_device_op_read_get_bustype(msg);
+ device_op_read->bus = mavlink_msg_device_op_read_get_bus(msg);
+ device_op_read->address = mavlink_msg_device_op_read_get_address(msg);
+ mavlink_msg_device_op_read_get_busname(msg, device_op_read->busname);
+ device_op_read->regstart = mavlink_msg_device_op_read_get_regstart(msg);
+ device_op_read->count = mavlink_msg_device_op_read_get_count(msg);
+ device_op_read->bank = mavlink_msg_device_op_read_get_bank(msg);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_DEVICE_OP_READ_LEN? msg->len : MAVLINK_MSG_ID_DEVICE_OP_READ_LEN;
+ memset(device_op_read, 0, MAVLINK_MSG_ID_DEVICE_OP_READ_LEN);
+ memcpy(device_op_read, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/ardupilotmega/mavlink_msg_device_op_read_reply.h b/lib/main/MAVLink/ardupilotmega/mavlink_msg_device_op_read_reply.h
new file mode 100644
index 00000000000..4c2675cb39f
--- /dev/null
+++ b/lib/main/MAVLink/ardupilotmega/mavlink_msg_device_op_read_reply.h
@@ -0,0 +1,390 @@
+#pragma once
+// MESSAGE DEVICE_OP_READ_REPLY PACKING
+
+#define MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY 11001
+
+
+typedef struct __mavlink_device_op_read_reply_t {
+ uint32_t request_id; /*< Request ID - copied from request.*/
+ uint8_t result; /*< 0 for success, anything else is failure code.*/
+ uint8_t regstart; /*< Starting register.*/
+ uint8_t count; /*< Count of bytes read.*/
+ uint8_t data[128]; /*< Reply data.*/
+ uint8_t bank; /*< Bank number.*/
+} mavlink_device_op_read_reply_t;
+
+#define MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY_LEN 136
+#define MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY_MIN_LEN 135
+#define MAVLINK_MSG_ID_11001_LEN 136
+#define MAVLINK_MSG_ID_11001_MIN_LEN 135
+
+#define MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY_CRC 15
+#define MAVLINK_MSG_ID_11001_CRC 15
+
+#define MAVLINK_MSG_DEVICE_OP_READ_REPLY_FIELD_DATA_LEN 128
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_DEVICE_OP_READ_REPLY { \
+ 11001, \
+ "DEVICE_OP_READ_REPLY", \
+ 6, \
+ { { "request_id", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_device_op_read_reply_t, request_id) }, \
+ { "result", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_device_op_read_reply_t, result) }, \
+ { "regstart", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_device_op_read_reply_t, regstart) }, \
+ { "count", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_device_op_read_reply_t, count) }, \
+ { "data", NULL, MAVLINK_TYPE_UINT8_T, 128, 7, offsetof(mavlink_device_op_read_reply_t, data) }, \
+ { "bank", NULL, MAVLINK_TYPE_UINT8_T, 0, 135, offsetof(mavlink_device_op_read_reply_t, bank) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_DEVICE_OP_READ_REPLY { \
+ "DEVICE_OP_READ_REPLY", \
+ 6, \
+ { { "request_id", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_device_op_read_reply_t, request_id) }, \
+ { "result", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_device_op_read_reply_t, result) }, \
+ { "regstart", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_device_op_read_reply_t, regstart) }, \
+ { "count", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_device_op_read_reply_t, count) }, \
+ { "data", NULL, MAVLINK_TYPE_UINT8_T, 128, 7, offsetof(mavlink_device_op_read_reply_t, data) }, \
+ { "bank", NULL, MAVLINK_TYPE_UINT8_T, 0, 135, offsetof(mavlink_device_op_read_reply_t, bank) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a device_op_read_reply 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 request_id Request ID - copied from request.
+ * @param result 0 for success, anything else is failure code.
+ * @param regstart Starting register.
+ * @param count Count of bytes read.
+ * @param data Reply data.
+ * @param bank Bank number.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_device_op_read_reply_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint32_t request_id, uint8_t result, uint8_t regstart, uint8_t count, const uint8_t *data, uint8_t bank)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY_LEN];
+ _mav_put_uint32_t(buf, 0, request_id);
+ _mav_put_uint8_t(buf, 4, result);
+ _mav_put_uint8_t(buf, 5, regstart);
+ _mav_put_uint8_t(buf, 6, count);
+ _mav_put_uint8_t(buf, 135, bank);
+ _mav_put_uint8_t_array(buf, 7, data, 128);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY_LEN);
+#else
+ mavlink_device_op_read_reply_t packet;
+ packet.request_id = request_id;
+ packet.result = result;
+ packet.regstart = regstart;
+ packet.count = count;
+ packet.bank = bank;
+ mav_array_assign_uint8_t(packet.data, data, 128);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY_MIN_LEN, MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY_LEN, MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY_CRC);
+}
+
+/**
+ * @brief Pack a device_op_read_reply 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 request_id Request ID - copied from request.
+ * @param result 0 for success, anything else is failure code.
+ * @param regstart Starting register.
+ * @param count Count of bytes read.
+ * @param data Reply data.
+ * @param bank Bank number.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_device_op_read_reply_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ uint32_t request_id, uint8_t result, uint8_t regstart, uint8_t count, const uint8_t *data, uint8_t bank)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY_LEN];
+ _mav_put_uint32_t(buf, 0, request_id);
+ _mav_put_uint8_t(buf, 4, result);
+ _mav_put_uint8_t(buf, 5, regstart);
+ _mav_put_uint8_t(buf, 6, count);
+ _mav_put_uint8_t(buf, 135, bank);
+ _mav_put_uint8_t_array(buf, 7, data, 128);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY_LEN);
+#else
+ mavlink_device_op_read_reply_t packet;
+ packet.request_id = request_id;
+ packet.result = result;
+ packet.regstart = regstart;
+ packet.count = count;
+ packet.bank = bank;
+ mav_array_memcpy(packet.data, data, sizeof(uint8_t)*128);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY_MIN_LEN, MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY_LEN, MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY_MIN_LEN, MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a device_op_read_reply 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 request_id Request ID - copied from request.
+ * @param result 0 for success, anything else is failure code.
+ * @param regstart Starting register.
+ * @param count Count of bytes read.
+ * @param data Reply data.
+ * @param bank Bank number.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_device_op_read_reply_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint32_t request_id,uint8_t result,uint8_t regstart,uint8_t count,const uint8_t *data,uint8_t bank)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY_LEN];
+ _mav_put_uint32_t(buf, 0, request_id);
+ _mav_put_uint8_t(buf, 4, result);
+ _mav_put_uint8_t(buf, 5, regstart);
+ _mav_put_uint8_t(buf, 6, count);
+ _mav_put_uint8_t(buf, 135, bank);
+ _mav_put_uint8_t_array(buf, 7, data, 128);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY_LEN);
+#else
+ mavlink_device_op_read_reply_t packet;
+ packet.request_id = request_id;
+ packet.result = result;
+ packet.regstart = regstart;
+ packet.count = count;
+ packet.bank = bank;
+ mav_array_assign_uint8_t(packet.data, data, 128);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY_MIN_LEN, MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY_LEN, MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY_CRC);
+}
+
+/**
+ * @brief Encode a device_op_read_reply 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 device_op_read_reply C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_device_op_read_reply_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_device_op_read_reply_t* device_op_read_reply)
+{
+ return mavlink_msg_device_op_read_reply_pack(system_id, component_id, msg, device_op_read_reply->request_id, device_op_read_reply->result, device_op_read_reply->regstart, device_op_read_reply->count, device_op_read_reply->data, device_op_read_reply->bank);
+}
+
+/**
+ * @brief Encode a device_op_read_reply 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 device_op_read_reply C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_device_op_read_reply_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_device_op_read_reply_t* device_op_read_reply)
+{
+ return mavlink_msg_device_op_read_reply_pack_chan(system_id, component_id, chan, msg, device_op_read_reply->request_id, device_op_read_reply->result, device_op_read_reply->regstart, device_op_read_reply->count, device_op_read_reply->data, device_op_read_reply->bank);
+}
+
+/**
+ * @brief Encode a device_op_read_reply 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 device_op_read_reply C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_device_op_read_reply_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_device_op_read_reply_t* device_op_read_reply)
+{
+ return mavlink_msg_device_op_read_reply_pack_status(system_id, component_id, _status, msg, device_op_read_reply->request_id, device_op_read_reply->result, device_op_read_reply->regstart, device_op_read_reply->count, device_op_read_reply->data, device_op_read_reply->bank);
+}
+
+/**
+ * @brief Send a device_op_read_reply message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param request_id Request ID - copied from request.
+ * @param result 0 for success, anything else is failure code.
+ * @param regstart Starting register.
+ * @param count Count of bytes read.
+ * @param data Reply data.
+ * @param bank Bank number.
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_device_op_read_reply_send(mavlink_channel_t chan, uint32_t request_id, uint8_t result, uint8_t regstart, uint8_t count, const uint8_t *data, uint8_t bank)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY_LEN];
+ _mav_put_uint32_t(buf, 0, request_id);
+ _mav_put_uint8_t(buf, 4, result);
+ _mav_put_uint8_t(buf, 5, regstart);
+ _mav_put_uint8_t(buf, 6, count);
+ _mav_put_uint8_t(buf, 135, bank);
+ _mav_put_uint8_t_array(buf, 7, data, 128);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY, buf, MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY_MIN_LEN, MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY_LEN, MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY_CRC);
+#else
+ mavlink_device_op_read_reply_t packet;
+ packet.request_id = request_id;
+ packet.result = result;
+ packet.regstart = regstart;
+ packet.count = count;
+ packet.bank = bank;
+ mav_array_assign_uint8_t(packet.data, data, 128);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY, (const char *)&packet, MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY_MIN_LEN, MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY_LEN, MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY_CRC);
+#endif
+}
+
+/**
+ * @brief Send a device_op_read_reply message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_device_op_read_reply_send_struct(mavlink_channel_t chan, const mavlink_device_op_read_reply_t* device_op_read_reply)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_device_op_read_reply_send(chan, device_op_read_reply->request_id, device_op_read_reply->result, device_op_read_reply->regstart, device_op_read_reply->count, device_op_read_reply->data, device_op_read_reply->bank);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY, (const char *)device_op_read_reply, MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY_MIN_LEN, MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY_LEN, MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_device_op_read_reply_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t request_id, uint8_t result, uint8_t regstart, uint8_t count, const uint8_t *data, uint8_t bank)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint32_t(buf, 0, request_id);
+ _mav_put_uint8_t(buf, 4, result);
+ _mav_put_uint8_t(buf, 5, regstart);
+ _mav_put_uint8_t(buf, 6, count);
+ _mav_put_uint8_t(buf, 135, bank);
+ _mav_put_uint8_t_array(buf, 7, data, 128);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY, buf, MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY_MIN_LEN, MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY_LEN, MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY_CRC);
+#else
+ mavlink_device_op_read_reply_t *packet = (mavlink_device_op_read_reply_t *)msgbuf;
+ packet->request_id = request_id;
+ packet->result = result;
+ packet->regstart = regstart;
+ packet->count = count;
+ packet->bank = bank;
+ mav_array_assign_uint8_t(packet->data, data, 128);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY, (const char *)packet, MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY_MIN_LEN, MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY_LEN, MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE DEVICE_OP_READ_REPLY UNPACKING
+
+
+/**
+ * @brief Get field request_id from device_op_read_reply message
+ *
+ * @return Request ID - copied from request.
+ */
+static inline uint32_t mavlink_msg_device_op_read_reply_get_request_id(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint32_t(msg, 0);
+}
+
+/**
+ * @brief Get field result from device_op_read_reply message
+ *
+ * @return 0 for success, anything else is failure code.
+ */
+static inline uint8_t mavlink_msg_device_op_read_reply_get_result(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 4);
+}
+
+/**
+ * @brief Get field regstart from device_op_read_reply message
+ *
+ * @return Starting register.
+ */
+static inline uint8_t mavlink_msg_device_op_read_reply_get_regstart(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 5);
+}
+
+/**
+ * @brief Get field count from device_op_read_reply message
+ *
+ * @return Count of bytes read.
+ */
+static inline uint8_t mavlink_msg_device_op_read_reply_get_count(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 6);
+}
+
+/**
+ * @brief Get field data from device_op_read_reply message
+ *
+ * @return Reply data.
+ */
+static inline uint16_t mavlink_msg_device_op_read_reply_get_data(const mavlink_message_t* msg, uint8_t *data)
+{
+ return _MAV_RETURN_uint8_t_array(msg, data, 128, 7);
+}
+
+/**
+ * @brief Get field bank from device_op_read_reply message
+ *
+ * @return Bank number.
+ */
+static inline uint8_t mavlink_msg_device_op_read_reply_get_bank(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 135);
+}
+
+/**
+ * @brief Decode a device_op_read_reply message into a struct
+ *
+ * @param msg The message to decode
+ * @param device_op_read_reply C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_device_op_read_reply_decode(const mavlink_message_t* msg, mavlink_device_op_read_reply_t* device_op_read_reply)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ device_op_read_reply->request_id = mavlink_msg_device_op_read_reply_get_request_id(msg);
+ device_op_read_reply->result = mavlink_msg_device_op_read_reply_get_result(msg);
+ device_op_read_reply->regstart = mavlink_msg_device_op_read_reply_get_regstart(msg);
+ device_op_read_reply->count = mavlink_msg_device_op_read_reply_get_count(msg);
+ mavlink_msg_device_op_read_reply_get_data(msg, device_op_read_reply->data);
+ device_op_read_reply->bank = mavlink_msg_device_op_read_reply_get_bank(msg);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY_LEN? msg->len : MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY_LEN;
+ memset(device_op_read_reply, 0, MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY_LEN);
+ memcpy(device_op_read_reply, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/ardupilotmega/mavlink_msg_device_op_write.h b/lib/main/MAVLink/ardupilotmega/mavlink_msg_device_op_write.h
new file mode 100644
index 00000000000..3ff5c666843
--- /dev/null
+++ b/lib/main/MAVLink/ardupilotmega/mavlink_msg_device_op_write.h
@@ -0,0 +1,531 @@
+#pragma once
+// MESSAGE DEVICE_OP_WRITE PACKING
+
+#define MAVLINK_MSG_ID_DEVICE_OP_WRITE 11002
+
+
+typedef struct __mavlink_device_op_write_t {
+ uint32_t request_id; /*< Request ID - copied to reply.*/
+ uint8_t target_system; /*< System ID.*/
+ uint8_t target_component; /*< Component ID.*/
+ uint8_t bustype; /*< The bus type.*/
+ uint8_t bus; /*< Bus number.*/
+ uint8_t address; /*< Bus address.*/
+ char busname[40]; /*< Name of device on bus (for SPI).*/
+ uint8_t regstart; /*< First register to write.*/
+ uint8_t count; /*< Count of registers to write.*/
+ uint8_t data[128]; /*< Write data.*/
+ uint8_t bank; /*< Bank number.*/
+} mavlink_device_op_write_t;
+
+#define MAVLINK_MSG_ID_DEVICE_OP_WRITE_LEN 180
+#define MAVLINK_MSG_ID_DEVICE_OP_WRITE_MIN_LEN 179
+#define MAVLINK_MSG_ID_11002_LEN 180
+#define MAVLINK_MSG_ID_11002_MIN_LEN 179
+
+#define MAVLINK_MSG_ID_DEVICE_OP_WRITE_CRC 234
+#define MAVLINK_MSG_ID_11002_CRC 234
+
+#define MAVLINK_MSG_DEVICE_OP_WRITE_FIELD_BUSNAME_LEN 40
+#define MAVLINK_MSG_DEVICE_OP_WRITE_FIELD_DATA_LEN 128
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_DEVICE_OP_WRITE { \
+ 11002, \
+ "DEVICE_OP_WRITE", \
+ 11, \
+ { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_device_op_write_t, target_system) }, \
+ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_device_op_write_t, target_component) }, \
+ { "request_id", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_device_op_write_t, request_id) }, \
+ { "bustype", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_device_op_write_t, bustype) }, \
+ { "bus", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_device_op_write_t, bus) }, \
+ { "address", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_device_op_write_t, address) }, \
+ { "busname", NULL, MAVLINK_TYPE_CHAR, 40, 9, offsetof(mavlink_device_op_write_t, busname) }, \
+ { "regstart", NULL, MAVLINK_TYPE_UINT8_T, 0, 49, offsetof(mavlink_device_op_write_t, regstart) }, \
+ { "count", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_device_op_write_t, count) }, \
+ { "data", NULL, MAVLINK_TYPE_UINT8_T, 128, 51, offsetof(mavlink_device_op_write_t, data) }, \
+ { "bank", NULL, MAVLINK_TYPE_UINT8_T, 0, 179, offsetof(mavlink_device_op_write_t, bank) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_DEVICE_OP_WRITE { \
+ "DEVICE_OP_WRITE", \
+ 11, \
+ { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_device_op_write_t, target_system) }, \
+ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_device_op_write_t, target_component) }, \
+ { "request_id", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_device_op_write_t, request_id) }, \
+ { "bustype", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_device_op_write_t, bustype) }, \
+ { "bus", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_device_op_write_t, bus) }, \
+ { "address", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_device_op_write_t, address) }, \
+ { "busname", NULL, MAVLINK_TYPE_CHAR, 40, 9, offsetof(mavlink_device_op_write_t, busname) }, \
+ { "regstart", NULL, MAVLINK_TYPE_UINT8_T, 0, 49, offsetof(mavlink_device_op_write_t, regstart) }, \
+ { "count", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_device_op_write_t, count) }, \
+ { "data", NULL, MAVLINK_TYPE_UINT8_T, 128, 51, offsetof(mavlink_device_op_write_t, data) }, \
+ { "bank", NULL, MAVLINK_TYPE_UINT8_T, 0, 179, offsetof(mavlink_device_op_write_t, bank) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a device_op_write 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 target_system System ID.
+ * @param target_component Component ID.
+ * @param request_id Request ID - copied to reply.
+ * @param bustype The bus type.
+ * @param bus Bus number.
+ * @param address Bus address.
+ * @param busname Name of device on bus (for SPI).
+ * @param regstart First register to write.
+ * @param count Count of registers to write.
+ * @param data Write data.
+ * @param bank Bank number.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_device_op_write_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint8_t target_system, uint8_t target_component, uint32_t request_id, uint8_t bustype, uint8_t bus, uint8_t address, const char *busname, uint8_t regstart, uint8_t count, const uint8_t *data, uint8_t bank)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_DEVICE_OP_WRITE_LEN];
+ _mav_put_uint32_t(buf, 0, request_id);
+ _mav_put_uint8_t(buf, 4, target_system);
+ _mav_put_uint8_t(buf, 5, target_component);
+ _mav_put_uint8_t(buf, 6, bustype);
+ _mav_put_uint8_t(buf, 7, bus);
+ _mav_put_uint8_t(buf, 8, address);
+ _mav_put_uint8_t(buf, 49, regstart);
+ _mav_put_uint8_t(buf, 50, count);
+ _mav_put_uint8_t(buf, 179, bank);
+ _mav_put_char_array(buf, 9, busname, 40);
+ _mav_put_uint8_t_array(buf, 51, data, 128);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DEVICE_OP_WRITE_LEN);
+#else
+ mavlink_device_op_write_t packet;
+ packet.request_id = request_id;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.bustype = bustype;
+ packet.bus = bus;
+ packet.address = address;
+ packet.regstart = regstart;
+ packet.count = count;
+ packet.bank = bank;
+ mav_array_assign_char(packet.busname, busname, 40);
+ mav_array_assign_uint8_t(packet.data, data, 128);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DEVICE_OP_WRITE_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_DEVICE_OP_WRITE;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DEVICE_OP_WRITE_MIN_LEN, MAVLINK_MSG_ID_DEVICE_OP_WRITE_LEN, MAVLINK_MSG_ID_DEVICE_OP_WRITE_CRC);
+}
+
+/**
+ * @brief Pack a device_op_write 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 target_system System ID.
+ * @param target_component Component ID.
+ * @param request_id Request ID - copied to reply.
+ * @param bustype The bus type.
+ * @param bus Bus number.
+ * @param address Bus address.
+ * @param busname Name of device on bus (for SPI).
+ * @param regstart First register to write.
+ * @param count Count of registers to write.
+ * @param data Write data.
+ * @param bank Bank number.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_device_op_write_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ uint8_t target_system, uint8_t target_component, uint32_t request_id, uint8_t bustype, uint8_t bus, uint8_t address, const char *busname, uint8_t regstart, uint8_t count, const uint8_t *data, uint8_t bank)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_DEVICE_OP_WRITE_LEN];
+ _mav_put_uint32_t(buf, 0, request_id);
+ _mav_put_uint8_t(buf, 4, target_system);
+ _mav_put_uint8_t(buf, 5, target_component);
+ _mav_put_uint8_t(buf, 6, bustype);
+ _mav_put_uint8_t(buf, 7, bus);
+ _mav_put_uint8_t(buf, 8, address);
+ _mav_put_uint8_t(buf, 49, regstart);
+ _mav_put_uint8_t(buf, 50, count);
+ _mav_put_uint8_t(buf, 179, bank);
+ _mav_put_char_array(buf, 9, busname, 40);
+ _mav_put_uint8_t_array(buf, 51, data, 128);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DEVICE_OP_WRITE_LEN);
+#else
+ mavlink_device_op_write_t packet;
+ packet.request_id = request_id;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.bustype = bustype;
+ packet.bus = bus;
+ packet.address = address;
+ packet.regstart = regstart;
+ packet.count = count;
+ packet.bank = bank;
+ mav_array_memcpy(packet.busname, busname, sizeof(char)*40);
+ mav_array_memcpy(packet.data, data, sizeof(uint8_t)*128);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DEVICE_OP_WRITE_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_DEVICE_OP_WRITE;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_DEVICE_OP_WRITE_MIN_LEN, MAVLINK_MSG_ID_DEVICE_OP_WRITE_LEN, MAVLINK_MSG_ID_DEVICE_OP_WRITE_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_DEVICE_OP_WRITE_MIN_LEN, MAVLINK_MSG_ID_DEVICE_OP_WRITE_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a device_op_write 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 target_system System ID.
+ * @param target_component Component ID.
+ * @param request_id Request ID - copied to reply.
+ * @param bustype The bus type.
+ * @param bus Bus number.
+ * @param address Bus address.
+ * @param busname Name of device on bus (for SPI).
+ * @param regstart First register to write.
+ * @param count Count of registers to write.
+ * @param data Write data.
+ * @param bank Bank number.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_device_op_write_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint8_t target_system,uint8_t target_component,uint32_t request_id,uint8_t bustype,uint8_t bus,uint8_t address,const char *busname,uint8_t regstart,uint8_t count,const uint8_t *data,uint8_t bank)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_DEVICE_OP_WRITE_LEN];
+ _mav_put_uint32_t(buf, 0, request_id);
+ _mav_put_uint8_t(buf, 4, target_system);
+ _mav_put_uint8_t(buf, 5, target_component);
+ _mav_put_uint8_t(buf, 6, bustype);
+ _mav_put_uint8_t(buf, 7, bus);
+ _mav_put_uint8_t(buf, 8, address);
+ _mav_put_uint8_t(buf, 49, regstart);
+ _mav_put_uint8_t(buf, 50, count);
+ _mav_put_uint8_t(buf, 179, bank);
+ _mav_put_char_array(buf, 9, busname, 40);
+ _mav_put_uint8_t_array(buf, 51, data, 128);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DEVICE_OP_WRITE_LEN);
+#else
+ mavlink_device_op_write_t packet;
+ packet.request_id = request_id;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.bustype = bustype;
+ packet.bus = bus;
+ packet.address = address;
+ packet.regstart = regstart;
+ packet.count = count;
+ packet.bank = bank;
+ mav_array_assign_char(packet.busname, busname, 40);
+ mav_array_assign_uint8_t(packet.data, data, 128);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DEVICE_OP_WRITE_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_DEVICE_OP_WRITE;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DEVICE_OP_WRITE_MIN_LEN, MAVLINK_MSG_ID_DEVICE_OP_WRITE_LEN, MAVLINK_MSG_ID_DEVICE_OP_WRITE_CRC);
+}
+
+/**
+ * @brief Encode a device_op_write 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 device_op_write C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_device_op_write_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_device_op_write_t* device_op_write)
+{
+ return mavlink_msg_device_op_write_pack(system_id, component_id, msg, device_op_write->target_system, device_op_write->target_component, device_op_write->request_id, device_op_write->bustype, device_op_write->bus, device_op_write->address, device_op_write->busname, device_op_write->regstart, device_op_write->count, device_op_write->data, device_op_write->bank);
+}
+
+/**
+ * @brief Encode a device_op_write 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 device_op_write C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_device_op_write_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_device_op_write_t* device_op_write)
+{
+ return mavlink_msg_device_op_write_pack_chan(system_id, component_id, chan, msg, device_op_write->target_system, device_op_write->target_component, device_op_write->request_id, device_op_write->bustype, device_op_write->bus, device_op_write->address, device_op_write->busname, device_op_write->regstart, device_op_write->count, device_op_write->data, device_op_write->bank);
+}
+
+/**
+ * @brief Encode a device_op_write 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 device_op_write C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_device_op_write_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_device_op_write_t* device_op_write)
+{
+ return mavlink_msg_device_op_write_pack_status(system_id, component_id, _status, msg, device_op_write->target_system, device_op_write->target_component, device_op_write->request_id, device_op_write->bustype, device_op_write->bus, device_op_write->address, device_op_write->busname, device_op_write->regstart, device_op_write->count, device_op_write->data, device_op_write->bank);
+}
+
+/**
+ * @brief Send a device_op_write message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param target_system System ID.
+ * @param target_component Component ID.
+ * @param request_id Request ID - copied to reply.
+ * @param bustype The bus type.
+ * @param bus Bus number.
+ * @param address Bus address.
+ * @param busname Name of device on bus (for SPI).
+ * @param regstart First register to write.
+ * @param count Count of registers to write.
+ * @param data Write data.
+ * @param bank Bank number.
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_device_op_write_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint32_t request_id, uint8_t bustype, uint8_t bus, uint8_t address, const char *busname, uint8_t regstart, uint8_t count, const uint8_t *data, uint8_t bank)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_DEVICE_OP_WRITE_LEN];
+ _mav_put_uint32_t(buf, 0, request_id);
+ _mav_put_uint8_t(buf, 4, target_system);
+ _mav_put_uint8_t(buf, 5, target_component);
+ _mav_put_uint8_t(buf, 6, bustype);
+ _mav_put_uint8_t(buf, 7, bus);
+ _mav_put_uint8_t(buf, 8, address);
+ _mav_put_uint8_t(buf, 49, regstart);
+ _mav_put_uint8_t(buf, 50, count);
+ _mav_put_uint8_t(buf, 179, bank);
+ _mav_put_char_array(buf, 9, busname, 40);
+ _mav_put_uint8_t_array(buf, 51, data, 128);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEVICE_OP_WRITE, buf, MAVLINK_MSG_ID_DEVICE_OP_WRITE_MIN_LEN, MAVLINK_MSG_ID_DEVICE_OP_WRITE_LEN, MAVLINK_MSG_ID_DEVICE_OP_WRITE_CRC);
+#else
+ mavlink_device_op_write_t packet;
+ packet.request_id = request_id;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.bustype = bustype;
+ packet.bus = bus;
+ packet.address = address;
+ packet.regstart = regstart;
+ packet.count = count;
+ packet.bank = bank;
+ mav_array_assign_char(packet.busname, busname, 40);
+ mav_array_assign_uint8_t(packet.data, data, 128);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEVICE_OP_WRITE, (const char *)&packet, MAVLINK_MSG_ID_DEVICE_OP_WRITE_MIN_LEN, MAVLINK_MSG_ID_DEVICE_OP_WRITE_LEN, MAVLINK_MSG_ID_DEVICE_OP_WRITE_CRC);
+#endif
+}
+
+/**
+ * @brief Send a device_op_write message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_device_op_write_send_struct(mavlink_channel_t chan, const mavlink_device_op_write_t* device_op_write)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_device_op_write_send(chan, device_op_write->target_system, device_op_write->target_component, device_op_write->request_id, device_op_write->bustype, device_op_write->bus, device_op_write->address, device_op_write->busname, device_op_write->regstart, device_op_write->count, device_op_write->data, device_op_write->bank);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEVICE_OP_WRITE, (const char *)device_op_write, MAVLINK_MSG_ID_DEVICE_OP_WRITE_MIN_LEN, MAVLINK_MSG_ID_DEVICE_OP_WRITE_LEN, MAVLINK_MSG_ID_DEVICE_OP_WRITE_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_DEVICE_OP_WRITE_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_device_op_write_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint32_t request_id, uint8_t bustype, uint8_t bus, uint8_t address, const char *busname, uint8_t regstart, uint8_t count, const uint8_t *data, uint8_t bank)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint32_t(buf, 0, request_id);
+ _mav_put_uint8_t(buf, 4, target_system);
+ _mav_put_uint8_t(buf, 5, target_component);
+ _mav_put_uint8_t(buf, 6, bustype);
+ _mav_put_uint8_t(buf, 7, bus);
+ _mav_put_uint8_t(buf, 8, address);
+ _mav_put_uint8_t(buf, 49, regstart);
+ _mav_put_uint8_t(buf, 50, count);
+ _mav_put_uint8_t(buf, 179, bank);
+ _mav_put_char_array(buf, 9, busname, 40);
+ _mav_put_uint8_t_array(buf, 51, data, 128);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEVICE_OP_WRITE, buf, MAVLINK_MSG_ID_DEVICE_OP_WRITE_MIN_LEN, MAVLINK_MSG_ID_DEVICE_OP_WRITE_LEN, MAVLINK_MSG_ID_DEVICE_OP_WRITE_CRC);
+#else
+ mavlink_device_op_write_t *packet = (mavlink_device_op_write_t *)msgbuf;
+ packet->request_id = request_id;
+ packet->target_system = target_system;
+ packet->target_component = target_component;
+ packet->bustype = bustype;
+ packet->bus = bus;
+ packet->address = address;
+ packet->regstart = regstart;
+ packet->count = count;
+ packet->bank = bank;
+ mav_array_assign_char(packet->busname, busname, 40);
+ mav_array_assign_uint8_t(packet->data, data, 128);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEVICE_OP_WRITE, (const char *)packet, MAVLINK_MSG_ID_DEVICE_OP_WRITE_MIN_LEN, MAVLINK_MSG_ID_DEVICE_OP_WRITE_LEN, MAVLINK_MSG_ID_DEVICE_OP_WRITE_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE DEVICE_OP_WRITE UNPACKING
+
+
+/**
+ * @brief Get field target_system from device_op_write message
+ *
+ * @return System ID.
+ */
+static inline uint8_t mavlink_msg_device_op_write_get_target_system(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 4);
+}
+
+/**
+ * @brief Get field target_component from device_op_write message
+ *
+ * @return Component ID.
+ */
+static inline uint8_t mavlink_msg_device_op_write_get_target_component(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 5);
+}
+
+/**
+ * @brief Get field request_id from device_op_write message
+ *
+ * @return Request ID - copied to reply.
+ */
+static inline uint32_t mavlink_msg_device_op_write_get_request_id(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint32_t(msg, 0);
+}
+
+/**
+ * @brief Get field bustype from device_op_write message
+ *
+ * @return The bus type.
+ */
+static inline uint8_t mavlink_msg_device_op_write_get_bustype(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 6);
+}
+
+/**
+ * @brief Get field bus from device_op_write message
+ *
+ * @return Bus number.
+ */
+static inline uint8_t mavlink_msg_device_op_write_get_bus(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 7);
+}
+
+/**
+ * @brief Get field address from device_op_write message
+ *
+ * @return Bus address.
+ */
+static inline uint8_t mavlink_msg_device_op_write_get_address(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 8);
+}
+
+/**
+ * @brief Get field busname from device_op_write message
+ *
+ * @return Name of device on bus (for SPI).
+ */
+static inline uint16_t mavlink_msg_device_op_write_get_busname(const mavlink_message_t* msg, char *busname)
+{
+ return _MAV_RETURN_char_array(msg, busname, 40, 9);
+}
+
+/**
+ * @brief Get field regstart from device_op_write message
+ *
+ * @return First register to write.
+ */
+static inline uint8_t mavlink_msg_device_op_write_get_regstart(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 49);
+}
+
+/**
+ * @brief Get field count from device_op_write message
+ *
+ * @return Count of registers to write.
+ */
+static inline uint8_t mavlink_msg_device_op_write_get_count(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 50);
+}
+
+/**
+ * @brief Get field data from device_op_write message
+ *
+ * @return Write data.
+ */
+static inline uint16_t mavlink_msg_device_op_write_get_data(const mavlink_message_t* msg, uint8_t *data)
+{
+ return _MAV_RETURN_uint8_t_array(msg, data, 128, 51);
+}
+
+/**
+ * @brief Get field bank from device_op_write message
+ *
+ * @return Bank number.
+ */
+static inline uint8_t mavlink_msg_device_op_write_get_bank(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 179);
+}
+
+/**
+ * @brief Decode a device_op_write message into a struct
+ *
+ * @param msg The message to decode
+ * @param device_op_write C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_device_op_write_decode(const mavlink_message_t* msg, mavlink_device_op_write_t* device_op_write)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ device_op_write->request_id = mavlink_msg_device_op_write_get_request_id(msg);
+ device_op_write->target_system = mavlink_msg_device_op_write_get_target_system(msg);
+ device_op_write->target_component = mavlink_msg_device_op_write_get_target_component(msg);
+ device_op_write->bustype = mavlink_msg_device_op_write_get_bustype(msg);
+ device_op_write->bus = mavlink_msg_device_op_write_get_bus(msg);
+ device_op_write->address = mavlink_msg_device_op_write_get_address(msg);
+ mavlink_msg_device_op_write_get_busname(msg, device_op_write->busname);
+ device_op_write->regstart = mavlink_msg_device_op_write_get_regstart(msg);
+ device_op_write->count = mavlink_msg_device_op_write_get_count(msg);
+ mavlink_msg_device_op_write_get_data(msg, device_op_write->data);
+ device_op_write->bank = mavlink_msg_device_op_write_get_bank(msg);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_DEVICE_OP_WRITE_LEN? msg->len : MAVLINK_MSG_ID_DEVICE_OP_WRITE_LEN;
+ memset(device_op_write, 0, MAVLINK_MSG_ID_DEVICE_OP_WRITE_LEN);
+ memcpy(device_op_write, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/ardupilotmega/mavlink_msg_device_op_write_reply.h b/lib/main/MAVLink/ardupilotmega/mavlink_msg_device_op_write_reply.h
new file mode 100644
index 00000000000..7128655be55
--- /dev/null
+++ b/lib/main/MAVLink/ardupilotmega/mavlink_msg_device_op_write_reply.h
@@ -0,0 +1,288 @@
+#pragma once
+// MESSAGE DEVICE_OP_WRITE_REPLY PACKING
+
+#define MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY 11003
+
+
+typedef struct __mavlink_device_op_write_reply_t {
+ uint32_t request_id; /*< Request ID - copied from request.*/
+ uint8_t result; /*< 0 for success, anything else is failure code.*/
+} mavlink_device_op_write_reply_t;
+
+#define MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY_LEN 5
+#define MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY_MIN_LEN 5
+#define MAVLINK_MSG_ID_11003_LEN 5
+#define MAVLINK_MSG_ID_11003_MIN_LEN 5
+
+#define MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY_CRC 64
+#define MAVLINK_MSG_ID_11003_CRC 64
+
+
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_DEVICE_OP_WRITE_REPLY { \
+ 11003, \
+ "DEVICE_OP_WRITE_REPLY", \
+ 2, \
+ { { "request_id", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_device_op_write_reply_t, request_id) }, \
+ { "result", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_device_op_write_reply_t, result) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_DEVICE_OP_WRITE_REPLY { \
+ "DEVICE_OP_WRITE_REPLY", \
+ 2, \
+ { { "request_id", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_device_op_write_reply_t, request_id) }, \
+ { "result", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_device_op_write_reply_t, result) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a device_op_write_reply 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 request_id Request ID - copied from request.
+ * @param result 0 for success, anything else is failure code.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_device_op_write_reply_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint32_t request_id, uint8_t result)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY_LEN];
+ _mav_put_uint32_t(buf, 0, request_id);
+ _mav_put_uint8_t(buf, 4, result);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY_LEN);
+#else
+ mavlink_device_op_write_reply_t packet;
+ packet.request_id = request_id;
+ packet.result = result;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY_MIN_LEN, MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY_LEN, MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY_CRC);
+}
+
+/**
+ * @brief Pack a device_op_write_reply 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 request_id Request ID - copied from request.
+ * @param result 0 for success, anything else is failure code.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_device_op_write_reply_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ uint32_t request_id, uint8_t result)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY_LEN];
+ _mav_put_uint32_t(buf, 0, request_id);
+ _mav_put_uint8_t(buf, 4, result);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY_LEN);
+#else
+ mavlink_device_op_write_reply_t packet;
+ packet.request_id = request_id;
+ packet.result = result;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY_MIN_LEN, MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY_LEN, MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY_MIN_LEN, MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a device_op_write_reply 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 request_id Request ID - copied from request.
+ * @param result 0 for success, anything else is failure code.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_device_op_write_reply_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint32_t request_id,uint8_t result)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY_LEN];
+ _mav_put_uint32_t(buf, 0, request_id);
+ _mav_put_uint8_t(buf, 4, result);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY_LEN);
+#else
+ mavlink_device_op_write_reply_t packet;
+ packet.request_id = request_id;
+ packet.result = result;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY_MIN_LEN, MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY_LEN, MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY_CRC);
+}
+
+/**
+ * @brief Encode a device_op_write_reply 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 device_op_write_reply C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_device_op_write_reply_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_device_op_write_reply_t* device_op_write_reply)
+{
+ return mavlink_msg_device_op_write_reply_pack(system_id, component_id, msg, device_op_write_reply->request_id, device_op_write_reply->result);
+}
+
+/**
+ * @brief Encode a device_op_write_reply 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 device_op_write_reply C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_device_op_write_reply_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_device_op_write_reply_t* device_op_write_reply)
+{
+ return mavlink_msg_device_op_write_reply_pack_chan(system_id, component_id, chan, msg, device_op_write_reply->request_id, device_op_write_reply->result);
+}
+
+/**
+ * @brief Encode a device_op_write_reply 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 device_op_write_reply C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_device_op_write_reply_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_device_op_write_reply_t* device_op_write_reply)
+{
+ return mavlink_msg_device_op_write_reply_pack_status(system_id, component_id, _status, msg, device_op_write_reply->request_id, device_op_write_reply->result);
+}
+
+/**
+ * @brief Send a device_op_write_reply message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param request_id Request ID - copied from request.
+ * @param result 0 for success, anything else is failure code.
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_device_op_write_reply_send(mavlink_channel_t chan, uint32_t request_id, uint8_t result)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY_LEN];
+ _mav_put_uint32_t(buf, 0, request_id);
+ _mav_put_uint8_t(buf, 4, result);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY, buf, MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY_MIN_LEN, MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY_LEN, MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY_CRC);
+#else
+ mavlink_device_op_write_reply_t packet;
+ packet.request_id = request_id;
+ packet.result = result;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY, (const char *)&packet, MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY_MIN_LEN, MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY_LEN, MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY_CRC);
+#endif
+}
+
+/**
+ * @brief Send a device_op_write_reply message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_device_op_write_reply_send_struct(mavlink_channel_t chan, const mavlink_device_op_write_reply_t* device_op_write_reply)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_device_op_write_reply_send(chan, device_op_write_reply->request_id, device_op_write_reply->result);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY, (const char *)device_op_write_reply, MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY_MIN_LEN, MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY_LEN, MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_device_op_write_reply_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t request_id, uint8_t result)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint32_t(buf, 0, request_id);
+ _mav_put_uint8_t(buf, 4, result);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY, buf, MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY_MIN_LEN, MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY_LEN, MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY_CRC);
+#else
+ mavlink_device_op_write_reply_t *packet = (mavlink_device_op_write_reply_t *)msgbuf;
+ packet->request_id = request_id;
+ packet->result = result;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY, (const char *)packet, MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY_MIN_LEN, MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY_LEN, MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE DEVICE_OP_WRITE_REPLY UNPACKING
+
+
+/**
+ * @brief Get field request_id from device_op_write_reply message
+ *
+ * @return Request ID - copied from request.
+ */
+static inline uint32_t mavlink_msg_device_op_write_reply_get_request_id(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint32_t(msg, 0);
+}
+
+/**
+ * @brief Get field result from device_op_write_reply message
+ *
+ * @return 0 for success, anything else is failure code.
+ */
+static inline uint8_t mavlink_msg_device_op_write_reply_get_result(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 4);
+}
+
+/**
+ * @brief Decode a device_op_write_reply message into a struct
+ *
+ * @param msg The message to decode
+ * @param device_op_write_reply C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_device_op_write_reply_decode(const mavlink_message_t* msg, mavlink_device_op_write_reply_t* device_op_write_reply)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ device_op_write_reply->request_id = mavlink_msg_device_op_write_reply_get_request_id(msg);
+ device_op_write_reply->result = mavlink_msg_device_op_write_reply_get_result(msg);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY_LEN? msg->len : MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY_LEN;
+ memset(device_op_write_reply, 0, MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY_LEN);
+ memcpy(device_op_write_reply, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/ardupilotmega/mavlink_msg_digicam_configure.h b/lib/main/MAVLink/ardupilotmega/mavlink_msg_digicam_configure.h
new file mode 100644
index 00000000000..86ee7fba7b0
--- /dev/null
+++ b/lib/main/MAVLink/ardupilotmega/mavlink_msg_digicam_configure.h
@@ -0,0 +1,540 @@
+#pragma once
+// MESSAGE DIGICAM_CONFIGURE PACKING
+
+#define MAVLINK_MSG_ID_DIGICAM_CONFIGURE 154
+
+
+typedef struct __mavlink_digicam_configure_t {
+ float extra_value; /*< Correspondent value to given extra_param.*/
+ uint16_t shutter_speed; /*< Divisor number //e.g. 1000 means 1/1000 (0 means ignore).*/
+ uint8_t target_system; /*< System ID.*/
+ uint8_t target_component; /*< Component ID.*/
+ uint8_t mode; /*< Mode enumeration from 1 to N //P, TV, AV, M, etc. (0 means ignore).*/
+ uint8_t aperture; /*< F stop number x 10 //e.g. 28 means 2.8 (0 means ignore).*/
+ uint8_t iso; /*< ISO enumeration from 1 to N //e.g. 80, 100, 200, Etc (0 means ignore).*/
+ uint8_t exposure_type; /*< Exposure type enumeration from 1 to N (0 means ignore).*/
+ uint8_t command_id; /*< Command Identity (incremental loop: 0 to 255). //A command sent multiple times will be executed or pooled just once.*/
+ uint8_t engine_cut_off; /*< [ds] Main engine cut-off time before camera trigger (0 means no cut-off).*/
+ uint8_t extra_param; /*< Extra parameters enumeration (0 means ignore).*/
+} mavlink_digicam_configure_t;
+
+#define MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN 15
+#define MAVLINK_MSG_ID_DIGICAM_CONFIGURE_MIN_LEN 15
+#define MAVLINK_MSG_ID_154_LEN 15
+#define MAVLINK_MSG_ID_154_MIN_LEN 15
+
+#define MAVLINK_MSG_ID_DIGICAM_CONFIGURE_CRC 84
+#define MAVLINK_MSG_ID_154_CRC 84
+
+
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_DIGICAM_CONFIGURE { \
+ 154, \
+ "DIGICAM_CONFIGURE", \
+ 11, \
+ { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_digicam_configure_t, target_system) }, \
+ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_digicam_configure_t, target_component) }, \
+ { "mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_digicam_configure_t, mode) }, \
+ { "shutter_speed", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_digicam_configure_t, shutter_speed) }, \
+ { "aperture", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_digicam_configure_t, aperture) }, \
+ { "iso", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_digicam_configure_t, iso) }, \
+ { "exposure_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_digicam_configure_t, exposure_type) }, \
+ { "command_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_digicam_configure_t, command_id) }, \
+ { "engine_cut_off", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_digicam_configure_t, engine_cut_off) }, \
+ { "extra_param", NULL, MAVLINK_TYPE_UINT8_T, 0, 14, offsetof(mavlink_digicam_configure_t, extra_param) }, \
+ { "extra_value", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_digicam_configure_t, extra_value) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_DIGICAM_CONFIGURE { \
+ "DIGICAM_CONFIGURE", \
+ 11, \
+ { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_digicam_configure_t, target_system) }, \
+ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_digicam_configure_t, target_component) }, \
+ { "mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_digicam_configure_t, mode) }, \
+ { "shutter_speed", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_digicam_configure_t, shutter_speed) }, \
+ { "aperture", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_digicam_configure_t, aperture) }, \
+ { "iso", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_digicam_configure_t, iso) }, \
+ { "exposure_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_digicam_configure_t, exposure_type) }, \
+ { "command_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_digicam_configure_t, command_id) }, \
+ { "engine_cut_off", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_digicam_configure_t, engine_cut_off) }, \
+ { "extra_param", NULL, MAVLINK_TYPE_UINT8_T, 0, 14, offsetof(mavlink_digicam_configure_t, extra_param) }, \
+ { "extra_value", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_digicam_configure_t, extra_value) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a digicam_configure 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 target_system System ID.
+ * @param target_component Component ID.
+ * @param mode Mode enumeration from 1 to N //P, TV, AV, M, etc. (0 means ignore).
+ * @param shutter_speed Divisor number //e.g. 1000 means 1/1000 (0 means ignore).
+ * @param aperture F stop number x 10 //e.g. 28 means 2.8 (0 means ignore).
+ * @param iso ISO enumeration from 1 to N //e.g. 80, 100, 200, Etc (0 means ignore).
+ * @param exposure_type Exposure type enumeration from 1 to N (0 means ignore).
+ * @param command_id Command Identity (incremental loop: 0 to 255). //A command sent multiple times will be executed or pooled just once.
+ * @param engine_cut_off [ds] Main engine cut-off time before camera trigger (0 means no cut-off).
+ * @param extra_param Extra parameters enumeration (0 means ignore).
+ * @param extra_value Correspondent value to given extra_param.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_digicam_configure_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint8_t target_system, uint8_t target_component, uint8_t mode, uint16_t shutter_speed, uint8_t aperture, uint8_t iso, uint8_t exposure_type, uint8_t command_id, uint8_t engine_cut_off, uint8_t extra_param, float extra_value)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN];
+ _mav_put_float(buf, 0, extra_value);
+ _mav_put_uint16_t(buf, 4, shutter_speed);
+ _mav_put_uint8_t(buf, 6, target_system);
+ _mav_put_uint8_t(buf, 7, target_component);
+ _mav_put_uint8_t(buf, 8, mode);
+ _mav_put_uint8_t(buf, 9, aperture);
+ _mav_put_uint8_t(buf, 10, iso);
+ _mav_put_uint8_t(buf, 11, exposure_type);
+ _mav_put_uint8_t(buf, 12, command_id);
+ _mav_put_uint8_t(buf, 13, engine_cut_off);
+ _mav_put_uint8_t(buf, 14, extra_param);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN);
+#else
+ mavlink_digicam_configure_t packet;
+ packet.extra_value = extra_value;
+ packet.shutter_speed = shutter_speed;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.mode = mode;
+ packet.aperture = aperture;
+ packet.iso = iso;
+ packet.exposure_type = exposure_type;
+ packet.command_id = command_id;
+ packet.engine_cut_off = engine_cut_off;
+ packet.extra_param = extra_param;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_DIGICAM_CONFIGURE;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_MIN_LEN, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_CRC);
+}
+
+/**
+ * @brief Pack a digicam_configure 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 target_system System ID.
+ * @param target_component Component ID.
+ * @param mode Mode enumeration from 1 to N //P, TV, AV, M, etc. (0 means ignore).
+ * @param shutter_speed Divisor number //e.g. 1000 means 1/1000 (0 means ignore).
+ * @param aperture F stop number x 10 //e.g. 28 means 2.8 (0 means ignore).
+ * @param iso ISO enumeration from 1 to N //e.g. 80, 100, 200, Etc (0 means ignore).
+ * @param exposure_type Exposure type enumeration from 1 to N (0 means ignore).
+ * @param command_id Command Identity (incremental loop: 0 to 255). //A command sent multiple times will be executed or pooled just once.
+ * @param engine_cut_off [ds] Main engine cut-off time before camera trigger (0 means no cut-off).
+ * @param extra_param Extra parameters enumeration (0 means ignore).
+ * @param extra_value Correspondent value to given extra_param.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_digicam_configure_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ uint8_t target_system, uint8_t target_component, uint8_t mode, uint16_t shutter_speed, uint8_t aperture, uint8_t iso, uint8_t exposure_type, uint8_t command_id, uint8_t engine_cut_off, uint8_t extra_param, float extra_value)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN];
+ _mav_put_float(buf, 0, extra_value);
+ _mav_put_uint16_t(buf, 4, shutter_speed);
+ _mav_put_uint8_t(buf, 6, target_system);
+ _mav_put_uint8_t(buf, 7, target_component);
+ _mav_put_uint8_t(buf, 8, mode);
+ _mav_put_uint8_t(buf, 9, aperture);
+ _mav_put_uint8_t(buf, 10, iso);
+ _mav_put_uint8_t(buf, 11, exposure_type);
+ _mav_put_uint8_t(buf, 12, command_id);
+ _mav_put_uint8_t(buf, 13, engine_cut_off);
+ _mav_put_uint8_t(buf, 14, extra_param);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN);
+#else
+ mavlink_digicam_configure_t packet;
+ packet.extra_value = extra_value;
+ packet.shutter_speed = shutter_speed;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.mode = mode;
+ packet.aperture = aperture;
+ packet.iso = iso;
+ packet.exposure_type = exposure_type;
+ packet.command_id = command_id;
+ packet.engine_cut_off = engine_cut_off;
+ packet.extra_param = extra_param;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_DIGICAM_CONFIGURE;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_MIN_LEN, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_MIN_LEN, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a digicam_configure 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 target_system System ID.
+ * @param target_component Component ID.
+ * @param mode Mode enumeration from 1 to N //P, TV, AV, M, etc. (0 means ignore).
+ * @param shutter_speed Divisor number //e.g. 1000 means 1/1000 (0 means ignore).
+ * @param aperture F stop number x 10 //e.g. 28 means 2.8 (0 means ignore).
+ * @param iso ISO enumeration from 1 to N //e.g. 80, 100, 200, Etc (0 means ignore).
+ * @param exposure_type Exposure type enumeration from 1 to N (0 means ignore).
+ * @param command_id Command Identity (incremental loop: 0 to 255). //A command sent multiple times will be executed or pooled just once.
+ * @param engine_cut_off [ds] Main engine cut-off time before camera trigger (0 means no cut-off).
+ * @param extra_param Extra parameters enumeration (0 means ignore).
+ * @param extra_value Correspondent value to given extra_param.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_digicam_configure_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint8_t target_system,uint8_t target_component,uint8_t mode,uint16_t shutter_speed,uint8_t aperture,uint8_t iso,uint8_t exposure_type,uint8_t command_id,uint8_t engine_cut_off,uint8_t extra_param,float extra_value)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN];
+ _mav_put_float(buf, 0, extra_value);
+ _mav_put_uint16_t(buf, 4, shutter_speed);
+ _mav_put_uint8_t(buf, 6, target_system);
+ _mav_put_uint8_t(buf, 7, target_component);
+ _mav_put_uint8_t(buf, 8, mode);
+ _mav_put_uint8_t(buf, 9, aperture);
+ _mav_put_uint8_t(buf, 10, iso);
+ _mav_put_uint8_t(buf, 11, exposure_type);
+ _mav_put_uint8_t(buf, 12, command_id);
+ _mav_put_uint8_t(buf, 13, engine_cut_off);
+ _mav_put_uint8_t(buf, 14, extra_param);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN);
+#else
+ mavlink_digicam_configure_t packet;
+ packet.extra_value = extra_value;
+ packet.shutter_speed = shutter_speed;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.mode = mode;
+ packet.aperture = aperture;
+ packet.iso = iso;
+ packet.exposure_type = exposure_type;
+ packet.command_id = command_id;
+ packet.engine_cut_off = engine_cut_off;
+ packet.extra_param = extra_param;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_DIGICAM_CONFIGURE;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_MIN_LEN, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_CRC);
+}
+
+/**
+ * @brief Encode a digicam_configure 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 digicam_configure C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_digicam_configure_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_digicam_configure_t* digicam_configure)
+{
+ return mavlink_msg_digicam_configure_pack(system_id, component_id, msg, digicam_configure->target_system, digicam_configure->target_component, digicam_configure->mode, digicam_configure->shutter_speed, digicam_configure->aperture, digicam_configure->iso, digicam_configure->exposure_type, digicam_configure->command_id, digicam_configure->engine_cut_off, digicam_configure->extra_param, digicam_configure->extra_value);
+}
+
+/**
+ * @brief Encode a digicam_configure 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 digicam_configure C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_digicam_configure_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_digicam_configure_t* digicam_configure)
+{
+ return mavlink_msg_digicam_configure_pack_chan(system_id, component_id, chan, msg, digicam_configure->target_system, digicam_configure->target_component, digicam_configure->mode, digicam_configure->shutter_speed, digicam_configure->aperture, digicam_configure->iso, digicam_configure->exposure_type, digicam_configure->command_id, digicam_configure->engine_cut_off, digicam_configure->extra_param, digicam_configure->extra_value);
+}
+
+/**
+ * @brief Encode a digicam_configure 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 digicam_configure C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_digicam_configure_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_digicam_configure_t* digicam_configure)
+{
+ return mavlink_msg_digicam_configure_pack_status(system_id, component_id, _status, msg, digicam_configure->target_system, digicam_configure->target_component, digicam_configure->mode, digicam_configure->shutter_speed, digicam_configure->aperture, digicam_configure->iso, digicam_configure->exposure_type, digicam_configure->command_id, digicam_configure->engine_cut_off, digicam_configure->extra_param, digicam_configure->extra_value);
+}
+
+/**
+ * @brief Send a digicam_configure message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param target_system System ID.
+ * @param target_component Component ID.
+ * @param mode Mode enumeration from 1 to N //P, TV, AV, M, etc. (0 means ignore).
+ * @param shutter_speed Divisor number //e.g. 1000 means 1/1000 (0 means ignore).
+ * @param aperture F stop number x 10 //e.g. 28 means 2.8 (0 means ignore).
+ * @param iso ISO enumeration from 1 to N //e.g. 80, 100, 200, Etc (0 means ignore).
+ * @param exposure_type Exposure type enumeration from 1 to N (0 means ignore).
+ * @param command_id Command Identity (incremental loop: 0 to 255). //A command sent multiple times will be executed or pooled just once.
+ * @param engine_cut_off [ds] Main engine cut-off time before camera trigger (0 means no cut-off).
+ * @param extra_param Extra parameters enumeration (0 means ignore).
+ * @param extra_value Correspondent value to given extra_param.
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_digicam_configure_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t mode, uint16_t shutter_speed, uint8_t aperture, uint8_t iso, uint8_t exposure_type, uint8_t command_id, uint8_t engine_cut_off, uint8_t extra_param, float extra_value)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN];
+ _mav_put_float(buf, 0, extra_value);
+ _mav_put_uint16_t(buf, 4, shutter_speed);
+ _mav_put_uint8_t(buf, 6, target_system);
+ _mav_put_uint8_t(buf, 7, target_component);
+ _mav_put_uint8_t(buf, 8, mode);
+ _mav_put_uint8_t(buf, 9, aperture);
+ _mav_put_uint8_t(buf, 10, iso);
+ _mav_put_uint8_t(buf, 11, exposure_type);
+ _mav_put_uint8_t(buf, 12, command_id);
+ _mav_put_uint8_t(buf, 13, engine_cut_off);
+ _mav_put_uint8_t(buf, 14, extra_param);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIGICAM_CONFIGURE, buf, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_MIN_LEN, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_CRC);
+#else
+ mavlink_digicam_configure_t packet;
+ packet.extra_value = extra_value;
+ packet.shutter_speed = shutter_speed;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.mode = mode;
+ packet.aperture = aperture;
+ packet.iso = iso;
+ packet.exposure_type = exposure_type;
+ packet.command_id = command_id;
+ packet.engine_cut_off = engine_cut_off;
+ packet.extra_param = extra_param;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIGICAM_CONFIGURE, (const char *)&packet, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_MIN_LEN, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_CRC);
+#endif
+}
+
+/**
+ * @brief Send a digicam_configure message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_digicam_configure_send_struct(mavlink_channel_t chan, const mavlink_digicam_configure_t* digicam_configure)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_digicam_configure_send(chan, digicam_configure->target_system, digicam_configure->target_component, digicam_configure->mode, digicam_configure->shutter_speed, digicam_configure->aperture, digicam_configure->iso, digicam_configure->exposure_type, digicam_configure->command_id, digicam_configure->engine_cut_off, digicam_configure->extra_param, digicam_configure->extra_value);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIGICAM_CONFIGURE, (const char *)digicam_configure, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_MIN_LEN, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_digicam_configure_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t mode, uint16_t shutter_speed, uint8_t aperture, uint8_t iso, uint8_t exposure_type, uint8_t command_id, uint8_t engine_cut_off, uint8_t extra_param, float extra_value)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_float(buf, 0, extra_value);
+ _mav_put_uint16_t(buf, 4, shutter_speed);
+ _mav_put_uint8_t(buf, 6, target_system);
+ _mav_put_uint8_t(buf, 7, target_component);
+ _mav_put_uint8_t(buf, 8, mode);
+ _mav_put_uint8_t(buf, 9, aperture);
+ _mav_put_uint8_t(buf, 10, iso);
+ _mav_put_uint8_t(buf, 11, exposure_type);
+ _mav_put_uint8_t(buf, 12, command_id);
+ _mav_put_uint8_t(buf, 13, engine_cut_off);
+ _mav_put_uint8_t(buf, 14, extra_param);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIGICAM_CONFIGURE, buf, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_MIN_LEN, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_CRC);
+#else
+ mavlink_digicam_configure_t *packet = (mavlink_digicam_configure_t *)msgbuf;
+ packet->extra_value = extra_value;
+ packet->shutter_speed = shutter_speed;
+ packet->target_system = target_system;
+ packet->target_component = target_component;
+ packet->mode = mode;
+ packet->aperture = aperture;
+ packet->iso = iso;
+ packet->exposure_type = exposure_type;
+ packet->command_id = command_id;
+ packet->engine_cut_off = engine_cut_off;
+ packet->extra_param = extra_param;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIGICAM_CONFIGURE, (const char *)packet, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_MIN_LEN, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE DIGICAM_CONFIGURE UNPACKING
+
+
+/**
+ * @brief Get field target_system from digicam_configure message
+ *
+ * @return System ID.
+ */
+static inline uint8_t mavlink_msg_digicam_configure_get_target_system(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 6);
+}
+
+/**
+ * @brief Get field target_component from digicam_configure message
+ *
+ * @return Component ID.
+ */
+static inline uint8_t mavlink_msg_digicam_configure_get_target_component(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 7);
+}
+
+/**
+ * @brief Get field mode from digicam_configure message
+ *
+ * @return Mode enumeration from 1 to N //P, TV, AV, M, etc. (0 means ignore).
+ */
+static inline uint8_t mavlink_msg_digicam_configure_get_mode(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 8);
+}
+
+/**
+ * @brief Get field shutter_speed from digicam_configure message
+ *
+ * @return Divisor number //e.g. 1000 means 1/1000 (0 means ignore).
+ */
+static inline uint16_t mavlink_msg_digicam_configure_get_shutter_speed(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 4);
+}
+
+/**
+ * @brief Get field aperture from digicam_configure message
+ *
+ * @return F stop number x 10 //e.g. 28 means 2.8 (0 means ignore).
+ */
+static inline uint8_t mavlink_msg_digicam_configure_get_aperture(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 9);
+}
+
+/**
+ * @brief Get field iso from digicam_configure message
+ *
+ * @return ISO enumeration from 1 to N //e.g. 80, 100, 200, Etc (0 means ignore).
+ */
+static inline uint8_t mavlink_msg_digicam_configure_get_iso(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 10);
+}
+
+/**
+ * @brief Get field exposure_type from digicam_configure message
+ *
+ * @return Exposure type enumeration from 1 to N (0 means ignore).
+ */
+static inline uint8_t mavlink_msg_digicam_configure_get_exposure_type(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 11);
+}
+
+/**
+ * @brief Get field command_id from digicam_configure message
+ *
+ * @return Command Identity (incremental loop: 0 to 255). //A command sent multiple times will be executed or pooled just once.
+ */
+static inline uint8_t mavlink_msg_digicam_configure_get_command_id(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 12);
+}
+
+/**
+ * @brief Get field engine_cut_off from digicam_configure message
+ *
+ * @return [ds] Main engine cut-off time before camera trigger (0 means no cut-off).
+ */
+static inline uint8_t mavlink_msg_digicam_configure_get_engine_cut_off(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 13);
+}
+
+/**
+ * @brief Get field extra_param from digicam_configure message
+ *
+ * @return Extra parameters enumeration (0 means ignore).
+ */
+static inline uint8_t mavlink_msg_digicam_configure_get_extra_param(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 14);
+}
+
+/**
+ * @brief Get field extra_value from digicam_configure message
+ *
+ * @return Correspondent value to given extra_param.
+ */
+static inline float mavlink_msg_digicam_configure_get_extra_value(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 0);
+}
+
+/**
+ * @brief Decode a digicam_configure message into a struct
+ *
+ * @param msg The message to decode
+ * @param digicam_configure C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_digicam_configure_decode(const mavlink_message_t* msg, mavlink_digicam_configure_t* digicam_configure)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ digicam_configure->extra_value = mavlink_msg_digicam_configure_get_extra_value(msg);
+ digicam_configure->shutter_speed = mavlink_msg_digicam_configure_get_shutter_speed(msg);
+ digicam_configure->target_system = mavlink_msg_digicam_configure_get_target_system(msg);
+ digicam_configure->target_component = mavlink_msg_digicam_configure_get_target_component(msg);
+ digicam_configure->mode = mavlink_msg_digicam_configure_get_mode(msg);
+ digicam_configure->aperture = mavlink_msg_digicam_configure_get_aperture(msg);
+ digicam_configure->iso = mavlink_msg_digicam_configure_get_iso(msg);
+ digicam_configure->exposure_type = mavlink_msg_digicam_configure_get_exposure_type(msg);
+ digicam_configure->command_id = mavlink_msg_digicam_configure_get_command_id(msg);
+ digicam_configure->engine_cut_off = mavlink_msg_digicam_configure_get_engine_cut_off(msg);
+ digicam_configure->extra_param = mavlink_msg_digicam_configure_get_extra_param(msg);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN? msg->len : MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN;
+ memset(digicam_configure, 0, MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN);
+ memcpy(digicam_configure, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/ardupilotmega/mavlink_msg_digicam_control.h b/lib/main/MAVLink/ardupilotmega/mavlink_msg_digicam_control.h
new file mode 100644
index 00000000000..f70d4b6f1ca
--- /dev/null
+++ b/lib/main/MAVLink/ardupilotmega/mavlink_msg_digicam_control.h
@@ -0,0 +1,512 @@
+#pragma once
+// MESSAGE DIGICAM_CONTROL PACKING
+
+#define MAVLINK_MSG_ID_DIGICAM_CONTROL 155
+
+
+typedef struct __mavlink_digicam_control_t {
+ float extra_value; /*< Correspondent value to given extra_param.*/
+ uint8_t target_system; /*< System ID.*/
+ uint8_t target_component; /*< Component ID.*/
+ uint8_t session; /*< 0: stop, 1: start or keep it up //Session control e.g. show/hide lens.*/
+ uint8_t zoom_pos; /*< 1 to N //Zoom's absolute position (0 means ignore).*/
+ int8_t zoom_step; /*< -100 to 100 //Zooming step value to offset zoom from the current position.*/
+ uint8_t focus_lock; /*< 0: unlock focus or keep unlocked, 1: lock focus or keep locked, 3: re-lock focus.*/
+ uint8_t shot; /*< 0: ignore, 1: shot or start filming.*/
+ uint8_t command_id; /*< Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once.*/
+ uint8_t extra_param; /*< Extra parameters enumeration (0 means ignore).*/
+} mavlink_digicam_control_t;
+
+#define MAVLINK_MSG_ID_DIGICAM_CONTROL_LEN 13
+#define MAVLINK_MSG_ID_DIGICAM_CONTROL_MIN_LEN 13
+#define MAVLINK_MSG_ID_155_LEN 13
+#define MAVLINK_MSG_ID_155_MIN_LEN 13
+
+#define MAVLINK_MSG_ID_DIGICAM_CONTROL_CRC 22
+#define MAVLINK_MSG_ID_155_CRC 22
+
+
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_DIGICAM_CONTROL { \
+ 155, \
+ "DIGICAM_CONTROL", \
+ 10, \
+ { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_digicam_control_t, target_system) }, \
+ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_digicam_control_t, target_component) }, \
+ { "session", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_digicam_control_t, session) }, \
+ { "zoom_pos", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_digicam_control_t, zoom_pos) }, \
+ { "zoom_step", NULL, MAVLINK_TYPE_INT8_T, 0, 8, offsetof(mavlink_digicam_control_t, zoom_step) }, \
+ { "focus_lock", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_digicam_control_t, focus_lock) }, \
+ { "shot", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_digicam_control_t, shot) }, \
+ { "command_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_digicam_control_t, command_id) }, \
+ { "extra_param", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_digicam_control_t, extra_param) }, \
+ { "extra_value", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_digicam_control_t, extra_value) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_DIGICAM_CONTROL { \
+ "DIGICAM_CONTROL", \
+ 10, \
+ { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_digicam_control_t, target_system) }, \
+ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_digicam_control_t, target_component) }, \
+ { "session", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_digicam_control_t, session) }, \
+ { "zoom_pos", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_digicam_control_t, zoom_pos) }, \
+ { "zoom_step", NULL, MAVLINK_TYPE_INT8_T, 0, 8, offsetof(mavlink_digicam_control_t, zoom_step) }, \
+ { "focus_lock", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_digicam_control_t, focus_lock) }, \
+ { "shot", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_digicam_control_t, shot) }, \
+ { "command_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_digicam_control_t, command_id) }, \
+ { "extra_param", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_digicam_control_t, extra_param) }, \
+ { "extra_value", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_digicam_control_t, extra_value) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a digicam_control 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 target_system System ID.
+ * @param target_component Component ID.
+ * @param session 0: stop, 1: start or keep it up //Session control e.g. show/hide lens.
+ * @param zoom_pos 1 to N //Zoom's absolute position (0 means ignore).
+ * @param zoom_step -100 to 100 //Zooming step value to offset zoom from the current position.
+ * @param focus_lock 0: unlock focus or keep unlocked, 1: lock focus or keep locked, 3: re-lock focus.
+ * @param shot 0: ignore, 1: shot or start filming.
+ * @param command_id Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once.
+ * @param extra_param Extra parameters enumeration (0 means ignore).
+ * @param extra_value Correspondent value to given extra_param.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_digicam_control_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint8_t target_system, uint8_t target_component, uint8_t session, uint8_t zoom_pos, int8_t zoom_step, uint8_t focus_lock, uint8_t shot, uint8_t command_id, uint8_t extra_param, float extra_value)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_DIGICAM_CONTROL_LEN];
+ _mav_put_float(buf, 0, extra_value);
+ _mav_put_uint8_t(buf, 4, target_system);
+ _mav_put_uint8_t(buf, 5, target_component);
+ _mav_put_uint8_t(buf, 6, session);
+ _mav_put_uint8_t(buf, 7, zoom_pos);
+ _mav_put_int8_t(buf, 8, zoom_step);
+ _mav_put_uint8_t(buf, 9, focus_lock);
+ _mav_put_uint8_t(buf, 10, shot);
+ _mav_put_uint8_t(buf, 11, command_id);
+ _mav_put_uint8_t(buf, 12, extra_param);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DIGICAM_CONTROL_LEN);
+#else
+ mavlink_digicam_control_t packet;
+ packet.extra_value = extra_value;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.session = session;
+ packet.zoom_pos = zoom_pos;
+ packet.zoom_step = zoom_step;
+ packet.focus_lock = focus_lock;
+ packet.shot = shot;
+ packet.command_id = command_id;
+ packet.extra_param = extra_param;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DIGICAM_CONTROL_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_DIGICAM_CONTROL;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DIGICAM_CONTROL_MIN_LEN, MAVLINK_MSG_ID_DIGICAM_CONTROL_LEN, MAVLINK_MSG_ID_DIGICAM_CONTROL_CRC);
+}
+
+/**
+ * @brief Pack a digicam_control 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 target_system System ID.
+ * @param target_component Component ID.
+ * @param session 0: stop, 1: start or keep it up //Session control e.g. show/hide lens.
+ * @param zoom_pos 1 to N //Zoom's absolute position (0 means ignore).
+ * @param zoom_step -100 to 100 //Zooming step value to offset zoom from the current position.
+ * @param focus_lock 0: unlock focus or keep unlocked, 1: lock focus or keep locked, 3: re-lock focus.
+ * @param shot 0: ignore, 1: shot or start filming.
+ * @param command_id Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once.
+ * @param extra_param Extra parameters enumeration (0 means ignore).
+ * @param extra_value Correspondent value to given extra_param.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_digicam_control_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ uint8_t target_system, uint8_t target_component, uint8_t session, uint8_t zoom_pos, int8_t zoom_step, uint8_t focus_lock, uint8_t shot, uint8_t command_id, uint8_t extra_param, float extra_value)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_DIGICAM_CONTROL_LEN];
+ _mav_put_float(buf, 0, extra_value);
+ _mav_put_uint8_t(buf, 4, target_system);
+ _mav_put_uint8_t(buf, 5, target_component);
+ _mav_put_uint8_t(buf, 6, session);
+ _mav_put_uint8_t(buf, 7, zoom_pos);
+ _mav_put_int8_t(buf, 8, zoom_step);
+ _mav_put_uint8_t(buf, 9, focus_lock);
+ _mav_put_uint8_t(buf, 10, shot);
+ _mav_put_uint8_t(buf, 11, command_id);
+ _mav_put_uint8_t(buf, 12, extra_param);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DIGICAM_CONTROL_LEN);
+#else
+ mavlink_digicam_control_t packet;
+ packet.extra_value = extra_value;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.session = session;
+ packet.zoom_pos = zoom_pos;
+ packet.zoom_step = zoom_step;
+ packet.focus_lock = focus_lock;
+ packet.shot = shot;
+ packet.command_id = command_id;
+ packet.extra_param = extra_param;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DIGICAM_CONTROL_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_DIGICAM_CONTROL;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_DIGICAM_CONTROL_MIN_LEN, MAVLINK_MSG_ID_DIGICAM_CONTROL_LEN, MAVLINK_MSG_ID_DIGICAM_CONTROL_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_DIGICAM_CONTROL_MIN_LEN, MAVLINK_MSG_ID_DIGICAM_CONTROL_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a digicam_control 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 target_system System ID.
+ * @param target_component Component ID.
+ * @param session 0: stop, 1: start or keep it up //Session control e.g. show/hide lens.
+ * @param zoom_pos 1 to N //Zoom's absolute position (0 means ignore).
+ * @param zoom_step -100 to 100 //Zooming step value to offset zoom from the current position.
+ * @param focus_lock 0: unlock focus or keep unlocked, 1: lock focus or keep locked, 3: re-lock focus.
+ * @param shot 0: ignore, 1: shot or start filming.
+ * @param command_id Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once.
+ * @param extra_param Extra parameters enumeration (0 means ignore).
+ * @param extra_value Correspondent value to given extra_param.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_digicam_control_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint8_t target_system,uint8_t target_component,uint8_t session,uint8_t zoom_pos,int8_t zoom_step,uint8_t focus_lock,uint8_t shot,uint8_t command_id,uint8_t extra_param,float extra_value)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_DIGICAM_CONTROL_LEN];
+ _mav_put_float(buf, 0, extra_value);
+ _mav_put_uint8_t(buf, 4, target_system);
+ _mav_put_uint8_t(buf, 5, target_component);
+ _mav_put_uint8_t(buf, 6, session);
+ _mav_put_uint8_t(buf, 7, zoom_pos);
+ _mav_put_int8_t(buf, 8, zoom_step);
+ _mav_put_uint8_t(buf, 9, focus_lock);
+ _mav_put_uint8_t(buf, 10, shot);
+ _mav_put_uint8_t(buf, 11, command_id);
+ _mav_put_uint8_t(buf, 12, extra_param);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DIGICAM_CONTROL_LEN);
+#else
+ mavlink_digicam_control_t packet;
+ packet.extra_value = extra_value;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.session = session;
+ packet.zoom_pos = zoom_pos;
+ packet.zoom_step = zoom_step;
+ packet.focus_lock = focus_lock;
+ packet.shot = shot;
+ packet.command_id = command_id;
+ packet.extra_param = extra_param;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DIGICAM_CONTROL_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_DIGICAM_CONTROL;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DIGICAM_CONTROL_MIN_LEN, MAVLINK_MSG_ID_DIGICAM_CONTROL_LEN, MAVLINK_MSG_ID_DIGICAM_CONTROL_CRC);
+}
+
+/**
+ * @brief Encode a digicam_control 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 digicam_control C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_digicam_control_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_digicam_control_t* digicam_control)
+{
+ return mavlink_msg_digicam_control_pack(system_id, component_id, msg, digicam_control->target_system, digicam_control->target_component, digicam_control->session, digicam_control->zoom_pos, digicam_control->zoom_step, digicam_control->focus_lock, digicam_control->shot, digicam_control->command_id, digicam_control->extra_param, digicam_control->extra_value);
+}
+
+/**
+ * @brief Encode a digicam_control 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 digicam_control C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_digicam_control_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_digicam_control_t* digicam_control)
+{
+ return mavlink_msg_digicam_control_pack_chan(system_id, component_id, chan, msg, digicam_control->target_system, digicam_control->target_component, digicam_control->session, digicam_control->zoom_pos, digicam_control->zoom_step, digicam_control->focus_lock, digicam_control->shot, digicam_control->command_id, digicam_control->extra_param, digicam_control->extra_value);
+}
+
+/**
+ * @brief Encode a digicam_control 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 digicam_control C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_digicam_control_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_digicam_control_t* digicam_control)
+{
+ return mavlink_msg_digicam_control_pack_status(system_id, component_id, _status, msg, digicam_control->target_system, digicam_control->target_component, digicam_control->session, digicam_control->zoom_pos, digicam_control->zoom_step, digicam_control->focus_lock, digicam_control->shot, digicam_control->command_id, digicam_control->extra_param, digicam_control->extra_value);
+}
+
+/**
+ * @brief Send a digicam_control message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param target_system System ID.
+ * @param target_component Component ID.
+ * @param session 0: stop, 1: start or keep it up //Session control e.g. show/hide lens.
+ * @param zoom_pos 1 to N //Zoom's absolute position (0 means ignore).
+ * @param zoom_step -100 to 100 //Zooming step value to offset zoom from the current position.
+ * @param focus_lock 0: unlock focus or keep unlocked, 1: lock focus or keep locked, 3: re-lock focus.
+ * @param shot 0: ignore, 1: shot or start filming.
+ * @param command_id Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once.
+ * @param extra_param Extra parameters enumeration (0 means ignore).
+ * @param extra_value Correspondent value to given extra_param.
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_digicam_control_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t session, uint8_t zoom_pos, int8_t zoom_step, uint8_t focus_lock, uint8_t shot, uint8_t command_id, uint8_t extra_param, float extra_value)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_DIGICAM_CONTROL_LEN];
+ _mav_put_float(buf, 0, extra_value);
+ _mav_put_uint8_t(buf, 4, target_system);
+ _mav_put_uint8_t(buf, 5, target_component);
+ _mav_put_uint8_t(buf, 6, session);
+ _mav_put_uint8_t(buf, 7, zoom_pos);
+ _mav_put_int8_t(buf, 8, zoom_step);
+ _mav_put_uint8_t(buf, 9, focus_lock);
+ _mav_put_uint8_t(buf, 10, shot);
+ _mav_put_uint8_t(buf, 11, command_id);
+ _mav_put_uint8_t(buf, 12, extra_param);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIGICAM_CONTROL, buf, MAVLINK_MSG_ID_DIGICAM_CONTROL_MIN_LEN, MAVLINK_MSG_ID_DIGICAM_CONTROL_LEN, MAVLINK_MSG_ID_DIGICAM_CONTROL_CRC);
+#else
+ mavlink_digicam_control_t packet;
+ packet.extra_value = extra_value;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.session = session;
+ packet.zoom_pos = zoom_pos;
+ packet.zoom_step = zoom_step;
+ packet.focus_lock = focus_lock;
+ packet.shot = shot;
+ packet.command_id = command_id;
+ packet.extra_param = extra_param;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIGICAM_CONTROL, (const char *)&packet, MAVLINK_MSG_ID_DIGICAM_CONTROL_MIN_LEN, MAVLINK_MSG_ID_DIGICAM_CONTROL_LEN, MAVLINK_MSG_ID_DIGICAM_CONTROL_CRC);
+#endif
+}
+
+/**
+ * @brief Send a digicam_control message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_digicam_control_send_struct(mavlink_channel_t chan, const mavlink_digicam_control_t* digicam_control)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_digicam_control_send(chan, digicam_control->target_system, digicam_control->target_component, digicam_control->session, digicam_control->zoom_pos, digicam_control->zoom_step, digicam_control->focus_lock, digicam_control->shot, digicam_control->command_id, digicam_control->extra_param, digicam_control->extra_value);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIGICAM_CONTROL, (const char *)digicam_control, MAVLINK_MSG_ID_DIGICAM_CONTROL_MIN_LEN, MAVLINK_MSG_ID_DIGICAM_CONTROL_LEN, MAVLINK_MSG_ID_DIGICAM_CONTROL_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_DIGICAM_CONTROL_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_digicam_control_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t session, uint8_t zoom_pos, int8_t zoom_step, uint8_t focus_lock, uint8_t shot, uint8_t command_id, uint8_t extra_param, float extra_value)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_float(buf, 0, extra_value);
+ _mav_put_uint8_t(buf, 4, target_system);
+ _mav_put_uint8_t(buf, 5, target_component);
+ _mav_put_uint8_t(buf, 6, session);
+ _mav_put_uint8_t(buf, 7, zoom_pos);
+ _mav_put_int8_t(buf, 8, zoom_step);
+ _mav_put_uint8_t(buf, 9, focus_lock);
+ _mav_put_uint8_t(buf, 10, shot);
+ _mav_put_uint8_t(buf, 11, command_id);
+ _mav_put_uint8_t(buf, 12, extra_param);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIGICAM_CONTROL, buf, MAVLINK_MSG_ID_DIGICAM_CONTROL_MIN_LEN, MAVLINK_MSG_ID_DIGICAM_CONTROL_LEN, MAVLINK_MSG_ID_DIGICAM_CONTROL_CRC);
+#else
+ mavlink_digicam_control_t *packet = (mavlink_digicam_control_t *)msgbuf;
+ packet->extra_value = extra_value;
+ packet->target_system = target_system;
+ packet->target_component = target_component;
+ packet->session = session;
+ packet->zoom_pos = zoom_pos;
+ packet->zoom_step = zoom_step;
+ packet->focus_lock = focus_lock;
+ packet->shot = shot;
+ packet->command_id = command_id;
+ packet->extra_param = extra_param;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIGICAM_CONTROL, (const char *)packet, MAVLINK_MSG_ID_DIGICAM_CONTROL_MIN_LEN, MAVLINK_MSG_ID_DIGICAM_CONTROL_LEN, MAVLINK_MSG_ID_DIGICAM_CONTROL_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE DIGICAM_CONTROL UNPACKING
+
+
+/**
+ * @brief Get field target_system from digicam_control message
+ *
+ * @return System ID.
+ */
+static inline uint8_t mavlink_msg_digicam_control_get_target_system(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 4);
+}
+
+/**
+ * @brief Get field target_component from digicam_control message
+ *
+ * @return Component ID.
+ */
+static inline uint8_t mavlink_msg_digicam_control_get_target_component(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 5);
+}
+
+/**
+ * @brief Get field session from digicam_control message
+ *
+ * @return 0: stop, 1: start or keep it up //Session control e.g. show/hide lens.
+ */
+static inline uint8_t mavlink_msg_digicam_control_get_session(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 6);
+}
+
+/**
+ * @brief Get field zoom_pos from digicam_control message
+ *
+ * @return 1 to N //Zoom's absolute position (0 means ignore).
+ */
+static inline uint8_t mavlink_msg_digicam_control_get_zoom_pos(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 7);
+}
+
+/**
+ * @brief Get field zoom_step from digicam_control message
+ *
+ * @return -100 to 100 //Zooming step value to offset zoom from the current position.
+ */
+static inline int8_t mavlink_msg_digicam_control_get_zoom_step(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_int8_t(msg, 8);
+}
+
+/**
+ * @brief Get field focus_lock from digicam_control message
+ *
+ * @return 0: unlock focus or keep unlocked, 1: lock focus or keep locked, 3: re-lock focus.
+ */
+static inline uint8_t mavlink_msg_digicam_control_get_focus_lock(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 9);
+}
+
+/**
+ * @brief Get field shot from digicam_control message
+ *
+ * @return 0: ignore, 1: shot or start filming.
+ */
+static inline uint8_t mavlink_msg_digicam_control_get_shot(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 10);
+}
+
+/**
+ * @brief Get field command_id from digicam_control message
+ *
+ * @return Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once.
+ */
+static inline uint8_t mavlink_msg_digicam_control_get_command_id(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 11);
+}
+
+/**
+ * @brief Get field extra_param from digicam_control message
+ *
+ * @return Extra parameters enumeration (0 means ignore).
+ */
+static inline uint8_t mavlink_msg_digicam_control_get_extra_param(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 12);
+}
+
+/**
+ * @brief Get field extra_value from digicam_control message
+ *
+ * @return Correspondent value to given extra_param.
+ */
+static inline float mavlink_msg_digicam_control_get_extra_value(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 0);
+}
+
+/**
+ * @brief Decode a digicam_control message into a struct
+ *
+ * @param msg The message to decode
+ * @param digicam_control C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_digicam_control_decode(const mavlink_message_t* msg, mavlink_digicam_control_t* digicam_control)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ digicam_control->extra_value = mavlink_msg_digicam_control_get_extra_value(msg);
+ digicam_control->target_system = mavlink_msg_digicam_control_get_target_system(msg);
+ digicam_control->target_component = mavlink_msg_digicam_control_get_target_component(msg);
+ digicam_control->session = mavlink_msg_digicam_control_get_session(msg);
+ digicam_control->zoom_pos = mavlink_msg_digicam_control_get_zoom_pos(msg);
+ digicam_control->zoom_step = mavlink_msg_digicam_control_get_zoom_step(msg);
+ digicam_control->focus_lock = mavlink_msg_digicam_control_get_focus_lock(msg);
+ digicam_control->shot = mavlink_msg_digicam_control_get_shot(msg);
+ digicam_control->command_id = mavlink_msg_digicam_control_get_command_id(msg);
+ digicam_control->extra_param = mavlink_msg_digicam_control_get_extra_param(msg);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_DIGICAM_CONTROL_LEN? msg->len : MAVLINK_MSG_ID_DIGICAM_CONTROL_LEN;
+ memset(digicam_control, 0, MAVLINK_MSG_ID_DIGICAM_CONTROL_LEN);
+ memcpy(digicam_control, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/ardupilotmega/mavlink_msg_ekf_status_report.h b/lib/main/MAVLink/ardupilotmega/mavlink_msg_ekf_status_report.h
new file mode 100644
index 00000000000..977a1892da6
--- /dev/null
+++ b/lib/main/MAVLink/ardupilotmega/mavlink_msg_ekf_status_report.h
@@ -0,0 +1,428 @@
+#pragma once
+// MESSAGE EKF_STATUS_REPORT PACKING
+
+#define MAVLINK_MSG_ID_EKF_STATUS_REPORT 193
+
+MAVPACKED(
+typedef struct __mavlink_ekf_status_report_t {
+ float velocity_variance; /*< Velocity variance.*/
+ float pos_horiz_variance; /*< Horizontal Position variance.*/
+ float pos_vert_variance; /*< Vertical Position variance.*/
+ float compass_variance; /*< Compass variance.*/
+ float terrain_alt_variance; /*< Terrain Altitude variance.*/
+ uint16_t flags; /*< Flags.*/
+ float airspeed_variance; /*< Airspeed variance.*/
+}) mavlink_ekf_status_report_t;
+
+#define MAVLINK_MSG_ID_EKF_STATUS_REPORT_LEN 26
+#define MAVLINK_MSG_ID_EKF_STATUS_REPORT_MIN_LEN 22
+#define MAVLINK_MSG_ID_193_LEN 26
+#define MAVLINK_MSG_ID_193_MIN_LEN 22
+
+#define MAVLINK_MSG_ID_EKF_STATUS_REPORT_CRC 71
+#define MAVLINK_MSG_ID_193_CRC 71
+
+
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_EKF_STATUS_REPORT { \
+ 193, \
+ "EKF_STATUS_REPORT", \
+ 7, \
+ { { "flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_ekf_status_report_t, flags) }, \
+ { "velocity_variance", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_ekf_status_report_t, velocity_variance) }, \
+ { "pos_horiz_variance", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_ekf_status_report_t, pos_horiz_variance) }, \
+ { "pos_vert_variance", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_ekf_status_report_t, pos_vert_variance) }, \
+ { "compass_variance", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_ekf_status_report_t, compass_variance) }, \
+ { "terrain_alt_variance", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_ekf_status_report_t, terrain_alt_variance) }, \
+ { "airspeed_variance", NULL, MAVLINK_TYPE_FLOAT, 0, 22, offsetof(mavlink_ekf_status_report_t, airspeed_variance) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_EKF_STATUS_REPORT { \
+ "EKF_STATUS_REPORT", \
+ 7, \
+ { { "flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_ekf_status_report_t, flags) }, \
+ { "velocity_variance", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_ekf_status_report_t, velocity_variance) }, \
+ { "pos_horiz_variance", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_ekf_status_report_t, pos_horiz_variance) }, \
+ { "pos_vert_variance", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_ekf_status_report_t, pos_vert_variance) }, \
+ { "compass_variance", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_ekf_status_report_t, compass_variance) }, \
+ { "terrain_alt_variance", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_ekf_status_report_t, terrain_alt_variance) }, \
+ { "airspeed_variance", NULL, MAVLINK_TYPE_FLOAT, 0, 22, offsetof(mavlink_ekf_status_report_t, airspeed_variance) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a ekf_status_report 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 flags Flags.
+ * @param velocity_variance Velocity variance.
+ * @param pos_horiz_variance Horizontal Position variance.
+ * @param pos_vert_variance Vertical Position variance.
+ * @param compass_variance Compass variance.
+ * @param terrain_alt_variance Terrain Altitude variance.
+ * @param airspeed_variance Airspeed variance.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_ekf_status_report_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint16_t flags, float velocity_variance, float pos_horiz_variance, float pos_vert_variance, float compass_variance, float terrain_alt_variance, float airspeed_variance)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_EKF_STATUS_REPORT_LEN];
+ _mav_put_float(buf, 0, velocity_variance);
+ _mav_put_float(buf, 4, pos_horiz_variance);
+ _mav_put_float(buf, 8, pos_vert_variance);
+ _mav_put_float(buf, 12, compass_variance);
+ _mav_put_float(buf, 16, terrain_alt_variance);
+ _mav_put_uint16_t(buf, 20, flags);
+ _mav_put_float(buf, 22, airspeed_variance);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_EKF_STATUS_REPORT_LEN);
+#else
+ mavlink_ekf_status_report_t packet;
+ packet.velocity_variance = velocity_variance;
+ packet.pos_horiz_variance = pos_horiz_variance;
+ packet.pos_vert_variance = pos_vert_variance;
+ packet.compass_variance = compass_variance;
+ packet.terrain_alt_variance = terrain_alt_variance;
+ packet.flags = flags;
+ packet.airspeed_variance = airspeed_variance;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_EKF_STATUS_REPORT_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_EKF_STATUS_REPORT;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_EKF_STATUS_REPORT_MIN_LEN, MAVLINK_MSG_ID_EKF_STATUS_REPORT_LEN, MAVLINK_MSG_ID_EKF_STATUS_REPORT_CRC);
+}
+
+/**
+ * @brief Pack a ekf_status_report 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 flags Flags.
+ * @param velocity_variance Velocity variance.
+ * @param pos_horiz_variance Horizontal Position variance.
+ * @param pos_vert_variance Vertical Position variance.
+ * @param compass_variance Compass variance.
+ * @param terrain_alt_variance Terrain Altitude variance.
+ * @param airspeed_variance Airspeed variance.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_ekf_status_report_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ uint16_t flags, float velocity_variance, float pos_horiz_variance, float pos_vert_variance, float compass_variance, float terrain_alt_variance, float airspeed_variance)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_EKF_STATUS_REPORT_LEN];
+ _mav_put_float(buf, 0, velocity_variance);
+ _mav_put_float(buf, 4, pos_horiz_variance);
+ _mav_put_float(buf, 8, pos_vert_variance);
+ _mav_put_float(buf, 12, compass_variance);
+ _mav_put_float(buf, 16, terrain_alt_variance);
+ _mav_put_uint16_t(buf, 20, flags);
+ _mav_put_float(buf, 22, airspeed_variance);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_EKF_STATUS_REPORT_LEN);
+#else
+ mavlink_ekf_status_report_t packet;
+ packet.velocity_variance = velocity_variance;
+ packet.pos_horiz_variance = pos_horiz_variance;
+ packet.pos_vert_variance = pos_vert_variance;
+ packet.compass_variance = compass_variance;
+ packet.terrain_alt_variance = terrain_alt_variance;
+ packet.flags = flags;
+ packet.airspeed_variance = airspeed_variance;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_EKF_STATUS_REPORT_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_EKF_STATUS_REPORT;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_EKF_STATUS_REPORT_MIN_LEN, MAVLINK_MSG_ID_EKF_STATUS_REPORT_LEN, MAVLINK_MSG_ID_EKF_STATUS_REPORT_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_EKF_STATUS_REPORT_MIN_LEN, MAVLINK_MSG_ID_EKF_STATUS_REPORT_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a ekf_status_report 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 flags Flags.
+ * @param velocity_variance Velocity variance.
+ * @param pos_horiz_variance Horizontal Position variance.
+ * @param pos_vert_variance Vertical Position variance.
+ * @param compass_variance Compass variance.
+ * @param terrain_alt_variance Terrain Altitude variance.
+ * @param airspeed_variance Airspeed variance.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_ekf_status_report_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint16_t flags,float velocity_variance,float pos_horiz_variance,float pos_vert_variance,float compass_variance,float terrain_alt_variance,float airspeed_variance)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_EKF_STATUS_REPORT_LEN];
+ _mav_put_float(buf, 0, velocity_variance);
+ _mav_put_float(buf, 4, pos_horiz_variance);
+ _mav_put_float(buf, 8, pos_vert_variance);
+ _mav_put_float(buf, 12, compass_variance);
+ _mav_put_float(buf, 16, terrain_alt_variance);
+ _mav_put_uint16_t(buf, 20, flags);
+ _mav_put_float(buf, 22, airspeed_variance);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_EKF_STATUS_REPORT_LEN);
+#else
+ mavlink_ekf_status_report_t packet;
+ packet.velocity_variance = velocity_variance;
+ packet.pos_horiz_variance = pos_horiz_variance;
+ packet.pos_vert_variance = pos_vert_variance;
+ packet.compass_variance = compass_variance;
+ packet.terrain_alt_variance = terrain_alt_variance;
+ packet.flags = flags;
+ packet.airspeed_variance = airspeed_variance;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_EKF_STATUS_REPORT_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_EKF_STATUS_REPORT;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_EKF_STATUS_REPORT_MIN_LEN, MAVLINK_MSG_ID_EKF_STATUS_REPORT_LEN, MAVLINK_MSG_ID_EKF_STATUS_REPORT_CRC);
+}
+
+/**
+ * @brief Encode a ekf_status_report 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 ekf_status_report C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_ekf_status_report_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_ekf_status_report_t* ekf_status_report)
+{
+ return mavlink_msg_ekf_status_report_pack(system_id, component_id, msg, ekf_status_report->flags, ekf_status_report->velocity_variance, ekf_status_report->pos_horiz_variance, ekf_status_report->pos_vert_variance, ekf_status_report->compass_variance, ekf_status_report->terrain_alt_variance, ekf_status_report->airspeed_variance);
+}
+
+/**
+ * @brief Encode a ekf_status_report 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 ekf_status_report C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_ekf_status_report_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_ekf_status_report_t* ekf_status_report)
+{
+ return mavlink_msg_ekf_status_report_pack_chan(system_id, component_id, chan, msg, ekf_status_report->flags, ekf_status_report->velocity_variance, ekf_status_report->pos_horiz_variance, ekf_status_report->pos_vert_variance, ekf_status_report->compass_variance, ekf_status_report->terrain_alt_variance, ekf_status_report->airspeed_variance);
+}
+
+/**
+ * @brief Encode a ekf_status_report 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 ekf_status_report C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_ekf_status_report_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_ekf_status_report_t* ekf_status_report)
+{
+ return mavlink_msg_ekf_status_report_pack_status(system_id, component_id, _status, msg, ekf_status_report->flags, ekf_status_report->velocity_variance, ekf_status_report->pos_horiz_variance, ekf_status_report->pos_vert_variance, ekf_status_report->compass_variance, ekf_status_report->terrain_alt_variance, ekf_status_report->airspeed_variance);
+}
+
+/**
+ * @brief Send a ekf_status_report message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param flags Flags.
+ * @param velocity_variance Velocity variance.
+ * @param pos_horiz_variance Horizontal Position variance.
+ * @param pos_vert_variance Vertical Position variance.
+ * @param compass_variance Compass variance.
+ * @param terrain_alt_variance Terrain Altitude variance.
+ * @param airspeed_variance Airspeed variance.
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_ekf_status_report_send(mavlink_channel_t chan, uint16_t flags, float velocity_variance, float pos_horiz_variance, float pos_vert_variance, float compass_variance, float terrain_alt_variance, float airspeed_variance)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_EKF_STATUS_REPORT_LEN];
+ _mav_put_float(buf, 0, velocity_variance);
+ _mav_put_float(buf, 4, pos_horiz_variance);
+ _mav_put_float(buf, 8, pos_vert_variance);
+ _mav_put_float(buf, 12, compass_variance);
+ _mav_put_float(buf, 16, terrain_alt_variance);
+ _mav_put_uint16_t(buf, 20, flags);
+ _mav_put_float(buf, 22, airspeed_variance);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_EKF_STATUS_REPORT, buf, MAVLINK_MSG_ID_EKF_STATUS_REPORT_MIN_LEN, MAVLINK_MSG_ID_EKF_STATUS_REPORT_LEN, MAVLINK_MSG_ID_EKF_STATUS_REPORT_CRC);
+#else
+ mavlink_ekf_status_report_t packet;
+ packet.velocity_variance = velocity_variance;
+ packet.pos_horiz_variance = pos_horiz_variance;
+ packet.pos_vert_variance = pos_vert_variance;
+ packet.compass_variance = compass_variance;
+ packet.terrain_alt_variance = terrain_alt_variance;
+ packet.flags = flags;
+ packet.airspeed_variance = airspeed_variance;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_EKF_STATUS_REPORT, (const char *)&packet, MAVLINK_MSG_ID_EKF_STATUS_REPORT_MIN_LEN, MAVLINK_MSG_ID_EKF_STATUS_REPORT_LEN, MAVLINK_MSG_ID_EKF_STATUS_REPORT_CRC);
+#endif
+}
+
+/**
+ * @brief Send a ekf_status_report message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_ekf_status_report_send_struct(mavlink_channel_t chan, const mavlink_ekf_status_report_t* ekf_status_report)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_ekf_status_report_send(chan, ekf_status_report->flags, ekf_status_report->velocity_variance, ekf_status_report->pos_horiz_variance, ekf_status_report->pos_vert_variance, ekf_status_report->compass_variance, ekf_status_report->terrain_alt_variance, ekf_status_report->airspeed_variance);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_EKF_STATUS_REPORT, (const char *)ekf_status_report, MAVLINK_MSG_ID_EKF_STATUS_REPORT_MIN_LEN, MAVLINK_MSG_ID_EKF_STATUS_REPORT_LEN, MAVLINK_MSG_ID_EKF_STATUS_REPORT_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_EKF_STATUS_REPORT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_ekf_status_report_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t flags, float velocity_variance, float pos_horiz_variance, float pos_vert_variance, float compass_variance, float terrain_alt_variance, float airspeed_variance)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_float(buf, 0, velocity_variance);
+ _mav_put_float(buf, 4, pos_horiz_variance);
+ _mav_put_float(buf, 8, pos_vert_variance);
+ _mav_put_float(buf, 12, compass_variance);
+ _mav_put_float(buf, 16, terrain_alt_variance);
+ _mav_put_uint16_t(buf, 20, flags);
+ _mav_put_float(buf, 22, airspeed_variance);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_EKF_STATUS_REPORT, buf, MAVLINK_MSG_ID_EKF_STATUS_REPORT_MIN_LEN, MAVLINK_MSG_ID_EKF_STATUS_REPORT_LEN, MAVLINK_MSG_ID_EKF_STATUS_REPORT_CRC);
+#else
+ mavlink_ekf_status_report_t *packet = (mavlink_ekf_status_report_t *)msgbuf;
+ packet->velocity_variance = velocity_variance;
+ packet->pos_horiz_variance = pos_horiz_variance;
+ packet->pos_vert_variance = pos_vert_variance;
+ packet->compass_variance = compass_variance;
+ packet->terrain_alt_variance = terrain_alt_variance;
+ packet->flags = flags;
+ packet->airspeed_variance = airspeed_variance;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_EKF_STATUS_REPORT, (const char *)packet, MAVLINK_MSG_ID_EKF_STATUS_REPORT_MIN_LEN, MAVLINK_MSG_ID_EKF_STATUS_REPORT_LEN, MAVLINK_MSG_ID_EKF_STATUS_REPORT_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE EKF_STATUS_REPORT UNPACKING
+
+
+/**
+ * @brief Get field flags from ekf_status_report message
+ *
+ * @return Flags.
+ */
+static inline uint16_t mavlink_msg_ekf_status_report_get_flags(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 20);
+}
+
+/**
+ * @brief Get field velocity_variance from ekf_status_report message
+ *
+ * @return Velocity variance.
+ */
+static inline float mavlink_msg_ekf_status_report_get_velocity_variance(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 0);
+}
+
+/**
+ * @brief Get field pos_horiz_variance from ekf_status_report message
+ *
+ * @return Horizontal Position variance.
+ */
+static inline float mavlink_msg_ekf_status_report_get_pos_horiz_variance(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 4);
+}
+
+/**
+ * @brief Get field pos_vert_variance from ekf_status_report message
+ *
+ * @return Vertical Position variance.
+ */
+static inline float mavlink_msg_ekf_status_report_get_pos_vert_variance(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 8);
+}
+
+/**
+ * @brief Get field compass_variance from ekf_status_report message
+ *
+ * @return Compass variance.
+ */
+static inline float mavlink_msg_ekf_status_report_get_compass_variance(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 12);
+}
+
+/**
+ * @brief Get field terrain_alt_variance from ekf_status_report message
+ *
+ * @return Terrain Altitude variance.
+ */
+static inline float mavlink_msg_ekf_status_report_get_terrain_alt_variance(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 16);
+}
+
+/**
+ * @brief Get field airspeed_variance from ekf_status_report message
+ *
+ * @return Airspeed variance.
+ */
+static inline float mavlink_msg_ekf_status_report_get_airspeed_variance(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 22);
+}
+
+/**
+ * @brief Decode a ekf_status_report message into a struct
+ *
+ * @param msg The message to decode
+ * @param ekf_status_report C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_ekf_status_report_decode(const mavlink_message_t* msg, mavlink_ekf_status_report_t* ekf_status_report)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ ekf_status_report->velocity_variance = mavlink_msg_ekf_status_report_get_velocity_variance(msg);
+ ekf_status_report->pos_horiz_variance = mavlink_msg_ekf_status_report_get_pos_horiz_variance(msg);
+ ekf_status_report->pos_vert_variance = mavlink_msg_ekf_status_report_get_pos_vert_variance(msg);
+ ekf_status_report->compass_variance = mavlink_msg_ekf_status_report_get_compass_variance(msg);
+ ekf_status_report->terrain_alt_variance = mavlink_msg_ekf_status_report_get_terrain_alt_variance(msg);
+ ekf_status_report->flags = mavlink_msg_ekf_status_report_get_flags(msg);
+ ekf_status_report->airspeed_variance = mavlink_msg_ekf_status_report_get_airspeed_variance(msg);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_EKF_STATUS_REPORT_LEN? msg->len : MAVLINK_MSG_ID_EKF_STATUS_REPORT_LEN;
+ memset(ekf_status_report, 0, MAVLINK_MSG_ID_EKF_STATUS_REPORT_LEN);
+ memcpy(ekf_status_report, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/ardupilotmega/mavlink_msg_esc_telemetry_13_to_16.h b/lib/main/MAVLink/ardupilotmega/mavlink_msg_esc_telemetry_13_to_16.h
new file mode 100644
index 00000000000..aef15ae744a
--- /dev/null
+++ b/lib/main/MAVLink/ardupilotmega/mavlink_msg_esc_telemetry_13_to_16.h
@@ -0,0 +1,405 @@
+#pragma once
+// MESSAGE ESC_TELEMETRY_13_TO_16 PACKING
+
+#define MAVLINK_MSG_ID_ESC_TELEMETRY_13_TO_16 11040
+
+
+typedef struct __mavlink_esc_telemetry_13_to_16_t {
+ uint16_t voltage[4]; /*< [cV] Voltage.*/
+ uint16_t current[4]; /*< [cA] Current.*/
+ uint16_t totalcurrent[4]; /*< [mAh] Total current.*/
+ uint16_t rpm[4]; /*< [rpm] RPM (eRPM).*/
+ uint16_t count[4]; /*< count of telemetry packets received (wraps at 65535).*/
+ uint8_t temperature[4]; /*< [degC] Temperature.*/
+} mavlink_esc_telemetry_13_to_16_t;
+
+#define MAVLINK_MSG_ID_ESC_TELEMETRY_13_TO_16_LEN 44
+#define MAVLINK_MSG_ID_ESC_TELEMETRY_13_TO_16_MIN_LEN 44
+#define MAVLINK_MSG_ID_11040_LEN 44
+#define MAVLINK_MSG_ID_11040_MIN_LEN 44
+
+#define MAVLINK_MSG_ID_ESC_TELEMETRY_13_TO_16_CRC 132
+#define MAVLINK_MSG_ID_11040_CRC 132
+
+#define MAVLINK_MSG_ESC_TELEMETRY_13_TO_16_FIELD_VOLTAGE_LEN 4
+#define MAVLINK_MSG_ESC_TELEMETRY_13_TO_16_FIELD_CURRENT_LEN 4
+#define MAVLINK_MSG_ESC_TELEMETRY_13_TO_16_FIELD_TOTALCURRENT_LEN 4
+#define MAVLINK_MSG_ESC_TELEMETRY_13_TO_16_FIELD_RPM_LEN 4
+#define MAVLINK_MSG_ESC_TELEMETRY_13_TO_16_FIELD_COUNT_LEN 4
+#define MAVLINK_MSG_ESC_TELEMETRY_13_TO_16_FIELD_TEMPERATURE_LEN 4
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_ESC_TELEMETRY_13_TO_16 { \
+ 11040, \
+ "ESC_TELEMETRY_13_TO_16", \
+ 6, \
+ { { "temperature", NULL, MAVLINK_TYPE_UINT8_T, 4, 40, offsetof(mavlink_esc_telemetry_13_to_16_t, temperature) }, \
+ { "voltage", NULL, MAVLINK_TYPE_UINT16_T, 4, 0, offsetof(mavlink_esc_telemetry_13_to_16_t, voltage) }, \
+ { "current", NULL, MAVLINK_TYPE_UINT16_T, 4, 8, offsetof(mavlink_esc_telemetry_13_to_16_t, current) }, \
+ { "totalcurrent", NULL, MAVLINK_TYPE_UINT16_T, 4, 16, offsetof(mavlink_esc_telemetry_13_to_16_t, totalcurrent) }, \
+ { "rpm", NULL, MAVLINK_TYPE_UINT16_T, 4, 24, offsetof(mavlink_esc_telemetry_13_to_16_t, rpm) }, \
+ { "count", NULL, MAVLINK_TYPE_UINT16_T, 4, 32, offsetof(mavlink_esc_telemetry_13_to_16_t, count) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_ESC_TELEMETRY_13_TO_16 { \
+ "ESC_TELEMETRY_13_TO_16", \
+ 6, \
+ { { "temperature", NULL, MAVLINK_TYPE_UINT8_T, 4, 40, offsetof(mavlink_esc_telemetry_13_to_16_t, temperature) }, \
+ { "voltage", NULL, MAVLINK_TYPE_UINT16_T, 4, 0, offsetof(mavlink_esc_telemetry_13_to_16_t, voltage) }, \
+ { "current", NULL, MAVLINK_TYPE_UINT16_T, 4, 8, offsetof(mavlink_esc_telemetry_13_to_16_t, current) }, \
+ { "totalcurrent", NULL, MAVLINK_TYPE_UINT16_T, 4, 16, offsetof(mavlink_esc_telemetry_13_to_16_t, totalcurrent) }, \
+ { "rpm", NULL, MAVLINK_TYPE_UINT16_T, 4, 24, offsetof(mavlink_esc_telemetry_13_to_16_t, rpm) }, \
+ { "count", NULL, MAVLINK_TYPE_UINT16_T, 4, 32, offsetof(mavlink_esc_telemetry_13_to_16_t, count) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a esc_telemetry_13_to_16 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 temperature [degC] Temperature.
+ * @param voltage [cV] Voltage.
+ * @param current [cA] Current.
+ * @param totalcurrent [mAh] Total current.
+ * @param rpm [rpm] RPM (eRPM).
+ * @param count count of telemetry packets received (wraps at 65535).
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_13_to_16_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ const uint8_t *temperature, const uint16_t *voltage, const uint16_t *current, const uint16_t *totalcurrent, const uint16_t *rpm, const uint16_t *count)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_ESC_TELEMETRY_13_TO_16_LEN];
+
+ _mav_put_uint16_t_array(buf, 0, voltage, 4);
+ _mav_put_uint16_t_array(buf, 8, current, 4);
+ _mav_put_uint16_t_array(buf, 16, totalcurrent, 4);
+ _mav_put_uint16_t_array(buf, 24, rpm, 4);
+ _mav_put_uint16_t_array(buf, 32, count, 4);
+ _mav_put_uint8_t_array(buf, 40, temperature, 4);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ESC_TELEMETRY_13_TO_16_LEN);
+#else
+ mavlink_esc_telemetry_13_to_16_t packet;
+
+ mav_array_assign_uint16_t(packet.voltage, voltage, 4);
+ mav_array_assign_uint16_t(packet.current, current, 4);
+ mav_array_assign_uint16_t(packet.totalcurrent, totalcurrent, 4);
+ mav_array_assign_uint16_t(packet.rpm, rpm, 4);
+ mav_array_assign_uint16_t(packet.count, count, 4);
+ mav_array_assign_uint8_t(packet.temperature, temperature, 4);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ESC_TELEMETRY_13_TO_16_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_ESC_TELEMETRY_13_TO_16;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ESC_TELEMETRY_13_TO_16_MIN_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_13_TO_16_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_13_TO_16_CRC);
+}
+
+/**
+ * @brief Pack a esc_telemetry_13_to_16 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 temperature [degC] Temperature.
+ * @param voltage [cV] Voltage.
+ * @param current [cA] Current.
+ * @param totalcurrent [mAh] Total current.
+ * @param rpm [rpm] RPM (eRPM).
+ * @param count count of telemetry packets received (wraps at 65535).
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_13_to_16_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ const uint8_t *temperature, const uint16_t *voltage, const uint16_t *current, const uint16_t *totalcurrent, const uint16_t *rpm, const uint16_t *count)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_ESC_TELEMETRY_13_TO_16_LEN];
+
+ _mav_put_uint16_t_array(buf, 0, voltage, 4);
+ _mav_put_uint16_t_array(buf, 8, current, 4);
+ _mav_put_uint16_t_array(buf, 16, totalcurrent, 4);
+ _mav_put_uint16_t_array(buf, 24, rpm, 4);
+ _mav_put_uint16_t_array(buf, 32, count, 4);
+ _mav_put_uint8_t_array(buf, 40, temperature, 4);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ESC_TELEMETRY_13_TO_16_LEN);
+#else
+ mavlink_esc_telemetry_13_to_16_t packet;
+
+ mav_array_memcpy(packet.voltage, voltage, sizeof(uint16_t)*4);
+ mav_array_memcpy(packet.current, current, sizeof(uint16_t)*4);
+ mav_array_memcpy(packet.totalcurrent, totalcurrent, sizeof(uint16_t)*4);
+ mav_array_memcpy(packet.rpm, rpm, sizeof(uint16_t)*4);
+ mav_array_memcpy(packet.count, count, sizeof(uint16_t)*4);
+ mav_array_memcpy(packet.temperature, temperature, sizeof(uint8_t)*4);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ESC_TELEMETRY_13_TO_16_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_ESC_TELEMETRY_13_TO_16;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_ESC_TELEMETRY_13_TO_16_MIN_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_13_TO_16_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_13_TO_16_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_ESC_TELEMETRY_13_TO_16_MIN_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_13_TO_16_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a esc_telemetry_13_to_16 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 temperature [degC] Temperature.
+ * @param voltage [cV] Voltage.
+ * @param current [cA] Current.
+ * @param totalcurrent [mAh] Total current.
+ * @param rpm [rpm] RPM (eRPM).
+ * @param count count of telemetry packets received (wraps at 65535).
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_13_to_16_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ const uint8_t *temperature,const uint16_t *voltage,const uint16_t *current,const uint16_t *totalcurrent,const uint16_t *rpm,const uint16_t *count)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_ESC_TELEMETRY_13_TO_16_LEN];
+
+ _mav_put_uint16_t_array(buf, 0, voltage, 4);
+ _mav_put_uint16_t_array(buf, 8, current, 4);
+ _mav_put_uint16_t_array(buf, 16, totalcurrent, 4);
+ _mav_put_uint16_t_array(buf, 24, rpm, 4);
+ _mav_put_uint16_t_array(buf, 32, count, 4);
+ _mav_put_uint8_t_array(buf, 40, temperature, 4);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ESC_TELEMETRY_13_TO_16_LEN);
+#else
+ mavlink_esc_telemetry_13_to_16_t packet;
+
+ mav_array_assign_uint16_t(packet.voltage, voltage, 4);
+ mav_array_assign_uint16_t(packet.current, current, 4);
+ mav_array_assign_uint16_t(packet.totalcurrent, totalcurrent, 4);
+ mav_array_assign_uint16_t(packet.rpm, rpm, 4);
+ mav_array_assign_uint16_t(packet.count, count, 4);
+ mav_array_assign_uint8_t(packet.temperature, temperature, 4);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ESC_TELEMETRY_13_TO_16_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_ESC_TELEMETRY_13_TO_16;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ESC_TELEMETRY_13_TO_16_MIN_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_13_TO_16_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_13_TO_16_CRC);
+}
+
+/**
+ * @brief Encode a esc_telemetry_13_to_16 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 esc_telemetry_13_to_16 C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_13_to_16_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_esc_telemetry_13_to_16_t* esc_telemetry_13_to_16)
+{
+ return mavlink_msg_esc_telemetry_13_to_16_pack(system_id, component_id, msg, esc_telemetry_13_to_16->temperature, esc_telemetry_13_to_16->voltage, esc_telemetry_13_to_16->current, esc_telemetry_13_to_16->totalcurrent, esc_telemetry_13_to_16->rpm, esc_telemetry_13_to_16->count);
+}
+
+/**
+ * @brief Encode a esc_telemetry_13_to_16 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 esc_telemetry_13_to_16 C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_13_to_16_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_esc_telemetry_13_to_16_t* esc_telemetry_13_to_16)
+{
+ return mavlink_msg_esc_telemetry_13_to_16_pack_chan(system_id, component_id, chan, msg, esc_telemetry_13_to_16->temperature, esc_telemetry_13_to_16->voltage, esc_telemetry_13_to_16->current, esc_telemetry_13_to_16->totalcurrent, esc_telemetry_13_to_16->rpm, esc_telemetry_13_to_16->count);
+}
+
+/**
+ * @brief Encode a esc_telemetry_13_to_16 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 esc_telemetry_13_to_16 C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_13_to_16_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_esc_telemetry_13_to_16_t* esc_telemetry_13_to_16)
+{
+ return mavlink_msg_esc_telemetry_13_to_16_pack_status(system_id, component_id, _status, msg, esc_telemetry_13_to_16->temperature, esc_telemetry_13_to_16->voltage, esc_telemetry_13_to_16->current, esc_telemetry_13_to_16->totalcurrent, esc_telemetry_13_to_16->rpm, esc_telemetry_13_to_16->count);
+}
+
+/**
+ * @brief Send a esc_telemetry_13_to_16 message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param temperature [degC] Temperature.
+ * @param voltage [cV] Voltage.
+ * @param current [cA] Current.
+ * @param totalcurrent [mAh] Total current.
+ * @param rpm [rpm] RPM (eRPM).
+ * @param count count of telemetry packets received (wraps at 65535).
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_esc_telemetry_13_to_16_send(mavlink_channel_t chan, const uint8_t *temperature, const uint16_t *voltage, const uint16_t *current, const uint16_t *totalcurrent, const uint16_t *rpm, const uint16_t *count)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_ESC_TELEMETRY_13_TO_16_LEN];
+
+ _mav_put_uint16_t_array(buf, 0, voltage, 4);
+ _mav_put_uint16_t_array(buf, 8, current, 4);
+ _mav_put_uint16_t_array(buf, 16, totalcurrent, 4);
+ _mav_put_uint16_t_array(buf, 24, rpm, 4);
+ _mav_put_uint16_t_array(buf, 32, count, 4);
+ _mav_put_uint8_t_array(buf, 40, temperature, 4);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESC_TELEMETRY_13_TO_16, buf, MAVLINK_MSG_ID_ESC_TELEMETRY_13_TO_16_MIN_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_13_TO_16_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_13_TO_16_CRC);
+#else
+ mavlink_esc_telemetry_13_to_16_t packet;
+
+ mav_array_assign_uint16_t(packet.voltage, voltage, 4);
+ mav_array_assign_uint16_t(packet.current, current, 4);
+ mav_array_assign_uint16_t(packet.totalcurrent, totalcurrent, 4);
+ mav_array_assign_uint16_t(packet.rpm, rpm, 4);
+ mav_array_assign_uint16_t(packet.count, count, 4);
+ mav_array_assign_uint8_t(packet.temperature, temperature, 4);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESC_TELEMETRY_13_TO_16, (const char *)&packet, MAVLINK_MSG_ID_ESC_TELEMETRY_13_TO_16_MIN_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_13_TO_16_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_13_TO_16_CRC);
+#endif
+}
+
+/**
+ * @brief Send a esc_telemetry_13_to_16 message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_esc_telemetry_13_to_16_send_struct(mavlink_channel_t chan, const mavlink_esc_telemetry_13_to_16_t* esc_telemetry_13_to_16)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_esc_telemetry_13_to_16_send(chan, esc_telemetry_13_to_16->temperature, esc_telemetry_13_to_16->voltage, esc_telemetry_13_to_16->current, esc_telemetry_13_to_16->totalcurrent, esc_telemetry_13_to_16->rpm, esc_telemetry_13_to_16->count);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESC_TELEMETRY_13_TO_16, (const char *)esc_telemetry_13_to_16, MAVLINK_MSG_ID_ESC_TELEMETRY_13_TO_16_MIN_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_13_TO_16_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_13_TO_16_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_ESC_TELEMETRY_13_TO_16_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_esc_telemetry_13_to_16_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, const uint8_t *temperature, const uint16_t *voltage, const uint16_t *current, const uint16_t *totalcurrent, const uint16_t *rpm, const uint16_t *count)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+
+ _mav_put_uint16_t_array(buf, 0, voltage, 4);
+ _mav_put_uint16_t_array(buf, 8, current, 4);
+ _mav_put_uint16_t_array(buf, 16, totalcurrent, 4);
+ _mav_put_uint16_t_array(buf, 24, rpm, 4);
+ _mav_put_uint16_t_array(buf, 32, count, 4);
+ _mav_put_uint8_t_array(buf, 40, temperature, 4);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESC_TELEMETRY_13_TO_16, buf, MAVLINK_MSG_ID_ESC_TELEMETRY_13_TO_16_MIN_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_13_TO_16_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_13_TO_16_CRC);
+#else
+ mavlink_esc_telemetry_13_to_16_t *packet = (mavlink_esc_telemetry_13_to_16_t *)msgbuf;
+
+ mav_array_assign_uint16_t(packet->voltage, voltage, 4);
+ mav_array_assign_uint16_t(packet->current, current, 4);
+ mav_array_assign_uint16_t(packet->totalcurrent, totalcurrent, 4);
+ mav_array_assign_uint16_t(packet->rpm, rpm, 4);
+ mav_array_assign_uint16_t(packet->count, count, 4);
+ mav_array_assign_uint8_t(packet->temperature, temperature, 4);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESC_TELEMETRY_13_TO_16, (const char *)packet, MAVLINK_MSG_ID_ESC_TELEMETRY_13_TO_16_MIN_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_13_TO_16_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_13_TO_16_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE ESC_TELEMETRY_13_TO_16 UNPACKING
+
+
+/**
+ * @brief Get field temperature from esc_telemetry_13_to_16 message
+ *
+ * @return [degC] Temperature.
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_13_to_16_get_temperature(const mavlink_message_t* msg, uint8_t *temperature)
+{
+ return _MAV_RETURN_uint8_t_array(msg, temperature, 4, 40);
+}
+
+/**
+ * @brief Get field voltage from esc_telemetry_13_to_16 message
+ *
+ * @return [cV] Voltage.
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_13_to_16_get_voltage(const mavlink_message_t* msg, uint16_t *voltage)
+{
+ return _MAV_RETURN_uint16_t_array(msg, voltage, 4, 0);
+}
+
+/**
+ * @brief Get field current from esc_telemetry_13_to_16 message
+ *
+ * @return [cA] Current.
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_13_to_16_get_current(const mavlink_message_t* msg, uint16_t *current)
+{
+ return _MAV_RETURN_uint16_t_array(msg, current, 4, 8);
+}
+
+/**
+ * @brief Get field totalcurrent from esc_telemetry_13_to_16 message
+ *
+ * @return [mAh] Total current.
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_13_to_16_get_totalcurrent(const mavlink_message_t* msg, uint16_t *totalcurrent)
+{
+ return _MAV_RETURN_uint16_t_array(msg, totalcurrent, 4, 16);
+}
+
+/**
+ * @brief Get field rpm from esc_telemetry_13_to_16 message
+ *
+ * @return [rpm] RPM (eRPM).
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_13_to_16_get_rpm(const mavlink_message_t* msg, uint16_t *rpm)
+{
+ return _MAV_RETURN_uint16_t_array(msg, rpm, 4, 24);
+}
+
+/**
+ * @brief Get field count from esc_telemetry_13_to_16 message
+ *
+ * @return count of telemetry packets received (wraps at 65535).
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_13_to_16_get_count(const mavlink_message_t* msg, uint16_t *count)
+{
+ return _MAV_RETURN_uint16_t_array(msg, count, 4, 32);
+}
+
+/**
+ * @brief Decode a esc_telemetry_13_to_16 message into a struct
+ *
+ * @param msg The message to decode
+ * @param esc_telemetry_13_to_16 C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_esc_telemetry_13_to_16_decode(const mavlink_message_t* msg, mavlink_esc_telemetry_13_to_16_t* esc_telemetry_13_to_16)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_esc_telemetry_13_to_16_get_voltage(msg, esc_telemetry_13_to_16->voltage);
+ mavlink_msg_esc_telemetry_13_to_16_get_current(msg, esc_telemetry_13_to_16->current);
+ mavlink_msg_esc_telemetry_13_to_16_get_totalcurrent(msg, esc_telemetry_13_to_16->totalcurrent);
+ mavlink_msg_esc_telemetry_13_to_16_get_rpm(msg, esc_telemetry_13_to_16->rpm);
+ mavlink_msg_esc_telemetry_13_to_16_get_count(msg, esc_telemetry_13_to_16->count);
+ mavlink_msg_esc_telemetry_13_to_16_get_temperature(msg, esc_telemetry_13_to_16->temperature);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_ESC_TELEMETRY_13_TO_16_LEN? msg->len : MAVLINK_MSG_ID_ESC_TELEMETRY_13_TO_16_LEN;
+ memset(esc_telemetry_13_to_16, 0, MAVLINK_MSG_ID_ESC_TELEMETRY_13_TO_16_LEN);
+ memcpy(esc_telemetry_13_to_16, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/ardupilotmega/mavlink_msg_esc_telemetry_17_to_20.h b/lib/main/MAVLink/ardupilotmega/mavlink_msg_esc_telemetry_17_to_20.h
new file mode 100644
index 00000000000..cd540ef1a5d
--- /dev/null
+++ b/lib/main/MAVLink/ardupilotmega/mavlink_msg_esc_telemetry_17_to_20.h
@@ -0,0 +1,405 @@
+#pragma once
+// MESSAGE ESC_TELEMETRY_17_TO_20 PACKING
+
+#define MAVLINK_MSG_ID_ESC_TELEMETRY_17_TO_20 11041
+
+
+typedef struct __mavlink_esc_telemetry_17_to_20_t {
+ uint16_t voltage[4]; /*< [cV] Voltage.*/
+ uint16_t current[4]; /*< [cA] Current.*/
+ uint16_t totalcurrent[4]; /*< [mAh] Total current.*/
+ uint16_t rpm[4]; /*< [rpm] RPM (eRPM).*/
+ uint16_t count[4]; /*< count of telemetry packets received (wraps at 65535).*/
+ uint8_t temperature[4]; /*< [degC] Temperature.*/
+} mavlink_esc_telemetry_17_to_20_t;
+
+#define MAVLINK_MSG_ID_ESC_TELEMETRY_17_TO_20_LEN 44
+#define MAVLINK_MSG_ID_ESC_TELEMETRY_17_TO_20_MIN_LEN 44
+#define MAVLINK_MSG_ID_11041_LEN 44
+#define MAVLINK_MSG_ID_11041_MIN_LEN 44
+
+#define MAVLINK_MSG_ID_ESC_TELEMETRY_17_TO_20_CRC 208
+#define MAVLINK_MSG_ID_11041_CRC 208
+
+#define MAVLINK_MSG_ESC_TELEMETRY_17_TO_20_FIELD_VOLTAGE_LEN 4
+#define MAVLINK_MSG_ESC_TELEMETRY_17_TO_20_FIELD_CURRENT_LEN 4
+#define MAVLINK_MSG_ESC_TELEMETRY_17_TO_20_FIELD_TOTALCURRENT_LEN 4
+#define MAVLINK_MSG_ESC_TELEMETRY_17_TO_20_FIELD_RPM_LEN 4
+#define MAVLINK_MSG_ESC_TELEMETRY_17_TO_20_FIELD_COUNT_LEN 4
+#define MAVLINK_MSG_ESC_TELEMETRY_17_TO_20_FIELD_TEMPERATURE_LEN 4
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_ESC_TELEMETRY_17_TO_20 { \
+ 11041, \
+ "ESC_TELEMETRY_17_TO_20", \
+ 6, \
+ { { "temperature", NULL, MAVLINK_TYPE_UINT8_T, 4, 40, offsetof(mavlink_esc_telemetry_17_to_20_t, temperature) }, \
+ { "voltage", NULL, MAVLINK_TYPE_UINT16_T, 4, 0, offsetof(mavlink_esc_telemetry_17_to_20_t, voltage) }, \
+ { "current", NULL, MAVLINK_TYPE_UINT16_T, 4, 8, offsetof(mavlink_esc_telemetry_17_to_20_t, current) }, \
+ { "totalcurrent", NULL, MAVLINK_TYPE_UINT16_T, 4, 16, offsetof(mavlink_esc_telemetry_17_to_20_t, totalcurrent) }, \
+ { "rpm", NULL, MAVLINK_TYPE_UINT16_T, 4, 24, offsetof(mavlink_esc_telemetry_17_to_20_t, rpm) }, \
+ { "count", NULL, MAVLINK_TYPE_UINT16_T, 4, 32, offsetof(mavlink_esc_telemetry_17_to_20_t, count) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_ESC_TELEMETRY_17_TO_20 { \
+ "ESC_TELEMETRY_17_TO_20", \
+ 6, \
+ { { "temperature", NULL, MAVLINK_TYPE_UINT8_T, 4, 40, offsetof(mavlink_esc_telemetry_17_to_20_t, temperature) }, \
+ { "voltage", NULL, MAVLINK_TYPE_UINT16_T, 4, 0, offsetof(mavlink_esc_telemetry_17_to_20_t, voltage) }, \
+ { "current", NULL, MAVLINK_TYPE_UINT16_T, 4, 8, offsetof(mavlink_esc_telemetry_17_to_20_t, current) }, \
+ { "totalcurrent", NULL, MAVLINK_TYPE_UINT16_T, 4, 16, offsetof(mavlink_esc_telemetry_17_to_20_t, totalcurrent) }, \
+ { "rpm", NULL, MAVLINK_TYPE_UINT16_T, 4, 24, offsetof(mavlink_esc_telemetry_17_to_20_t, rpm) }, \
+ { "count", NULL, MAVLINK_TYPE_UINT16_T, 4, 32, offsetof(mavlink_esc_telemetry_17_to_20_t, count) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a esc_telemetry_17_to_20 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 temperature [degC] Temperature.
+ * @param voltage [cV] Voltage.
+ * @param current [cA] Current.
+ * @param totalcurrent [mAh] Total current.
+ * @param rpm [rpm] RPM (eRPM).
+ * @param count count of telemetry packets received (wraps at 65535).
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_17_to_20_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ const uint8_t *temperature, const uint16_t *voltage, const uint16_t *current, const uint16_t *totalcurrent, const uint16_t *rpm, const uint16_t *count)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_ESC_TELEMETRY_17_TO_20_LEN];
+
+ _mav_put_uint16_t_array(buf, 0, voltage, 4);
+ _mav_put_uint16_t_array(buf, 8, current, 4);
+ _mav_put_uint16_t_array(buf, 16, totalcurrent, 4);
+ _mav_put_uint16_t_array(buf, 24, rpm, 4);
+ _mav_put_uint16_t_array(buf, 32, count, 4);
+ _mav_put_uint8_t_array(buf, 40, temperature, 4);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ESC_TELEMETRY_17_TO_20_LEN);
+#else
+ mavlink_esc_telemetry_17_to_20_t packet;
+
+ mav_array_assign_uint16_t(packet.voltage, voltage, 4);
+ mav_array_assign_uint16_t(packet.current, current, 4);
+ mav_array_assign_uint16_t(packet.totalcurrent, totalcurrent, 4);
+ mav_array_assign_uint16_t(packet.rpm, rpm, 4);
+ mav_array_assign_uint16_t(packet.count, count, 4);
+ mav_array_assign_uint8_t(packet.temperature, temperature, 4);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ESC_TELEMETRY_17_TO_20_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_ESC_TELEMETRY_17_TO_20;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ESC_TELEMETRY_17_TO_20_MIN_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_17_TO_20_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_17_TO_20_CRC);
+}
+
+/**
+ * @brief Pack a esc_telemetry_17_to_20 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 temperature [degC] Temperature.
+ * @param voltage [cV] Voltage.
+ * @param current [cA] Current.
+ * @param totalcurrent [mAh] Total current.
+ * @param rpm [rpm] RPM (eRPM).
+ * @param count count of telemetry packets received (wraps at 65535).
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_17_to_20_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ const uint8_t *temperature, const uint16_t *voltage, const uint16_t *current, const uint16_t *totalcurrent, const uint16_t *rpm, const uint16_t *count)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_ESC_TELEMETRY_17_TO_20_LEN];
+
+ _mav_put_uint16_t_array(buf, 0, voltage, 4);
+ _mav_put_uint16_t_array(buf, 8, current, 4);
+ _mav_put_uint16_t_array(buf, 16, totalcurrent, 4);
+ _mav_put_uint16_t_array(buf, 24, rpm, 4);
+ _mav_put_uint16_t_array(buf, 32, count, 4);
+ _mav_put_uint8_t_array(buf, 40, temperature, 4);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ESC_TELEMETRY_17_TO_20_LEN);
+#else
+ mavlink_esc_telemetry_17_to_20_t packet;
+
+ mav_array_memcpy(packet.voltage, voltage, sizeof(uint16_t)*4);
+ mav_array_memcpy(packet.current, current, sizeof(uint16_t)*4);
+ mav_array_memcpy(packet.totalcurrent, totalcurrent, sizeof(uint16_t)*4);
+ mav_array_memcpy(packet.rpm, rpm, sizeof(uint16_t)*4);
+ mav_array_memcpy(packet.count, count, sizeof(uint16_t)*4);
+ mav_array_memcpy(packet.temperature, temperature, sizeof(uint8_t)*4);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ESC_TELEMETRY_17_TO_20_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_ESC_TELEMETRY_17_TO_20;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_ESC_TELEMETRY_17_TO_20_MIN_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_17_TO_20_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_17_TO_20_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_ESC_TELEMETRY_17_TO_20_MIN_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_17_TO_20_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a esc_telemetry_17_to_20 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 temperature [degC] Temperature.
+ * @param voltage [cV] Voltage.
+ * @param current [cA] Current.
+ * @param totalcurrent [mAh] Total current.
+ * @param rpm [rpm] RPM (eRPM).
+ * @param count count of telemetry packets received (wraps at 65535).
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_17_to_20_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ const uint8_t *temperature,const uint16_t *voltage,const uint16_t *current,const uint16_t *totalcurrent,const uint16_t *rpm,const uint16_t *count)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_ESC_TELEMETRY_17_TO_20_LEN];
+
+ _mav_put_uint16_t_array(buf, 0, voltage, 4);
+ _mav_put_uint16_t_array(buf, 8, current, 4);
+ _mav_put_uint16_t_array(buf, 16, totalcurrent, 4);
+ _mav_put_uint16_t_array(buf, 24, rpm, 4);
+ _mav_put_uint16_t_array(buf, 32, count, 4);
+ _mav_put_uint8_t_array(buf, 40, temperature, 4);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ESC_TELEMETRY_17_TO_20_LEN);
+#else
+ mavlink_esc_telemetry_17_to_20_t packet;
+
+ mav_array_assign_uint16_t(packet.voltage, voltage, 4);
+ mav_array_assign_uint16_t(packet.current, current, 4);
+ mav_array_assign_uint16_t(packet.totalcurrent, totalcurrent, 4);
+ mav_array_assign_uint16_t(packet.rpm, rpm, 4);
+ mav_array_assign_uint16_t(packet.count, count, 4);
+ mav_array_assign_uint8_t(packet.temperature, temperature, 4);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ESC_TELEMETRY_17_TO_20_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_ESC_TELEMETRY_17_TO_20;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ESC_TELEMETRY_17_TO_20_MIN_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_17_TO_20_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_17_TO_20_CRC);
+}
+
+/**
+ * @brief Encode a esc_telemetry_17_to_20 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 esc_telemetry_17_to_20 C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_17_to_20_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_esc_telemetry_17_to_20_t* esc_telemetry_17_to_20)
+{
+ return mavlink_msg_esc_telemetry_17_to_20_pack(system_id, component_id, msg, esc_telemetry_17_to_20->temperature, esc_telemetry_17_to_20->voltage, esc_telemetry_17_to_20->current, esc_telemetry_17_to_20->totalcurrent, esc_telemetry_17_to_20->rpm, esc_telemetry_17_to_20->count);
+}
+
+/**
+ * @brief Encode a esc_telemetry_17_to_20 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 esc_telemetry_17_to_20 C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_17_to_20_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_esc_telemetry_17_to_20_t* esc_telemetry_17_to_20)
+{
+ return mavlink_msg_esc_telemetry_17_to_20_pack_chan(system_id, component_id, chan, msg, esc_telemetry_17_to_20->temperature, esc_telemetry_17_to_20->voltage, esc_telemetry_17_to_20->current, esc_telemetry_17_to_20->totalcurrent, esc_telemetry_17_to_20->rpm, esc_telemetry_17_to_20->count);
+}
+
+/**
+ * @brief Encode a esc_telemetry_17_to_20 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 esc_telemetry_17_to_20 C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_17_to_20_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_esc_telemetry_17_to_20_t* esc_telemetry_17_to_20)
+{
+ return mavlink_msg_esc_telemetry_17_to_20_pack_status(system_id, component_id, _status, msg, esc_telemetry_17_to_20->temperature, esc_telemetry_17_to_20->voltage, esc_telemetry_17_to_20->current, esc_telemetry_17_to_20->totalcurrent, esc_telemetry_17_to_20->rpm, esc_telemetry_17_to_20->count);
+}
+
+/**
+ * @brief Send a esc_telemetry_17_to_20 message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param temperature [degC] Temperature.
+ * @param voltage [cV] Voltage.
+ * @param current [cA] Current.
+ * @param totalcurrent [mAh] Total current.
+ * @param rpm [rpm] RPM (eRPM).
+ * @param count count of telemetry packets received (wraps at 65535).
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_esc_telemetry_17_to_20_send(mavlink_channel_t chan, const uint8_t *temperature, const uint16_t *voltage, const uint16_t *current, const uint16_t *totalcurrent, const uint16_t *rpm, const uint16_t *count)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_ESC_TELEMETRY_17_TO_20_LEN];
+
+ _mav_put_uint16_t_array(buf, 0, voltage, 4);
+ _mav_put_uint16_t_array(buf, 8, current, 4);
+ _mav_put_uint16_t_array(buf, 16, totalcurrent, 4);
+ _mav_put_uint16_t_array(buf, 24, rpm, 4);
+ _mav_put_uint16_t_array(buf, 32, count, 4);
+ _mav_put_uint8_t_array(buf, 40, temperature, 4);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESC_TELEMETRY_17_TO_20, buf, MAVLINK_MSG_ID_ESC_TELEMETRY_17_TO_20_MIN_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_17_TO_20_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_17_TO_20_CRC);
+#else
+ mavlink_esc_telemetry_17_to_20_t packet;
+
+ mav_array_assign_uint16_t(packet.voltage, voltage, 4);
+ mav_array_assign_uint16_t(packet.current, current, 4);
+ mav_array_assign_uint16_t(packet.totalcurrent, totalcurrent, 4);
+ mav_array_assign_uint16_t(packet.rpm, rpm, 4);
+ mav_array_assign_uint16_t(packet.count, count, 4);
+ mav_array_assign_uint8_t(packet.temperature, temperature, 4);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESC_TELEMETRY_17_TO_20, (const char *)&packet, MAVLINK_MSG_ID_ESC_TELEMETRY_17_TO_20_MIN_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_17_TO_20_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_17_TO_20_CRC);
+#endif
+}
+
+/**
+ * @brief Send a esc_telemetry_17_to_20 message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_esc_telemetry_17_to_20_send_struct(mavlink_channel_t chan, const mavlink_esc_telemetry_17_to_20_t* esc_telemetry_17_to_20)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_esc_telemetry_17_to_20_send(chan, esc_telemetry_17_to_20->temperature, esc_telemetry_17_to_20->voltage, esc_telemetry_17_to_20->current, esc_telemetry_17_to_20->totalcurrent, esc_telemetry_17_to_20->rpm, esc_telemetry_17_to_20->count);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESC_TELEMETRY_17_TO_20, (const char *)esc_telemetry_17_to_20, MAVLINK_MSG_ID_ESC_TELEMETRY_17_TO_20_MIN_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_17_TO_20_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_17_TO_20_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_ESC_TELEMETRY_17_TO_20_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_esc_telemetry_17_to_20_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, const uint8_t *temperature, const uint16_t *voltage, const uint16_t *current, const uint16_t *totalcurrent, const uint16_t *rpm, const uint16_t *count)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+
+ _mav_put_uint16_t_array(buf, 0, voltage, 4);
+ _mav_put_uint16_t_array(buf, 8, current, 4);
+ _mav_put_uint16_t_array(buf, 16, totalcurrent, 4);
+ _mav_put_uint16_t_array(buf, 24, rpm, 4);
+ _mav_put_uint16_t_array(buf, 32, count, 4);
+ _mav_put_uint8_t_array(buf, 40, temperature, 4);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESC_TELEMETRY_17_TO_20, buf, MAVLINK_MSG_ID_ESC_TELEMETRY_17_TO_20_MIN_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_17_TO_20_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_17_TO_20_CRC);
+#else
+ mavlink_esc_telemetry_17_to_20_t *packet = (mavlink_esc_telemetry_17_to_20_t *)msgbuf;
+
+ mav_array_assign_uint16_t(packet->voltage, voltage, 4);
+ mav_array_assign_uint16_t(packet->current, current, 4);
+ mav_array_assign_uint16_t(packet->totalcurrent, totalcurrent, 4);
+ mav_array_assign_uint16_t(packet->rpm, rpm, 4);
+ mav_array_assign_uint16_t(packet->count, count, 4);
+ mav_array_assign_uint8_t(packet->temperature, temperature, 4);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESC_TELEMETRY_17_TO_20, (const char *)packet, MAVLINK_MSG_ID_ESC_TELEMETRY_17_TO_20_MIN_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_17_TO_20_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_17_TO_20_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE ESC_TELEMETRY_17_TO_20 UNPACKING
+
+
+/**
+ * @brief Get field temperature from esc_telemetry_17_to_20 message
+ *
+ * @return [degC] Temperature.
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_17_to_20_get_temperature(const mavlink_message_t* msg, uint8_t *temperature)
+{
+ return _MAV_RETURN_uint8_t_array(msg, temperature, 4, 40);
+}
+
+/**
+ * @brief Get field voltage from esc_telemetry_17_to_20 message
+ *
+ * @return [cV] Voltage.
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_17_to_20_get_voltage(const mavlink_message_t* msg, uint16_t *voltage)
+{
+ return _MAV_RETURN_uint16_t_array(msg, voltage, 4, 0);
+}
+
+/**
+ * @brief Get field current from esc_telemetry_17_to_20 message
+ *
+ * @return [cA] Current.
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_17_to_20_get_current(const mavlink_message_t* msg, uint16_t *current)
+{
+ return _MAV_RETURN_uint16_t_array(msg, current, 4, 8);
+}
+
+/**
+ * @brief Get field totalcurrent from esc_telemetry_17_to_20 message
+ *
+ * @return [mAh] Total current.
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_17_to_20_get_totalcurrent(const mavlink_message_t* msg, uint16_t *totalcurrent)
+{
+ return _MAV_RETURN_uint16_t_array(msg, totalcurrent, 4, 16);
+}
+
+/**
+ * @brief Get field rpm from esc_telemetry_17_to_20 message
+ *
+ * @return [rpm] RPM (eRPM).
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_17_to_20_get_rpm(const mavlink_message_t* msg, uint16_t *rpm)
+{
+ return _MAV_RETURN_uint16_t_array(msg, rpm, 4, 24);
+}
+
+/**
+ * @brief Get field count from esc_telemetry_17_to_20 message
+ *
+ * @return count of telemetry packets received (wraps at 65535).
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_17_to_20_get_count(const mavlink_message_t* msg, uint16_t *count)
+{
+ return _MAV_RETURN_uint16_t_array(msg, count, 4, 32);
+}
+
+/**
+ * @brief Decode a esc_telemetry_17_to_20 message into a struct
+ *
+ * @param msg The message to decode
+ * @param esc_telemetry_17_to_20 C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_esc_telemetry_17_to_20_decode(const mavlink_message_t* msg, mavlink_esc_telemetry_17_to_20_t* esc_telemetry_17_to_20)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_esc_telemetry_17_to_20_get_voltage(msg, esc_telemetry_17_to_20->voltage);
+ mavlink_msg_esc_telemetry_17_to_20_get_current(msg, esc_telemetry_17_to_20->current);
+ mavlink_msg_esc_telemetry_17_to_20_get_totalcurrent(msg, esc_telemetry_17_to_20->totalcurrent);
+ mavlink_msg_esc_telemetry_17_to_20_get_rpm(msg, esc_telemetry_17_to_20->rpm);
+ mavlink_msg_esc_telemetry_17_to_20_get_count(msg, esc_telemetry_17_to_20->count);
+ mavlink_msg_esc_telemetry_17_to_20_get_temperature(msg, esc_telemetry_17_to_20->temperature);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_ESC_TELEMETRY_17_TO_20_LEN? msg->len : MAVLINK_MSG_ID_ESC_TELEMETRY_17_TO_20_LEN;
+ memset(esc_telemetry_17_to_20, 0, MAVLINK_MSG_ID_ESC_TELEMETRY_17_TO_20_LEN);
+ memcpy(esc_telemetry_17_to_20, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/ardupilotmega/mavlink_msg_esc_telemetry_1_to_4.h b/lib/main/MAVLink/ardupilotmega/mavlink_msg_esc_telemetry_1_to_4.h
new file mode 100644
index 00000000000..8b638a47a7a
--- /dev/null
+++ b/lib/main/MAVLink/ardupilotmega/mavlink_msg_esc_telemetry_1_to_4.h
@@ -0,0 +1,405 @@
+#pragma once
+// MESSAGE ESC_TELEMETRY_1_TO_4 PACKING
+
+#define MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4 11030
+
+
+typedef struct __mavlink_esc_telemetry_1_to_4_t {
+ uint16_t voltage[4]; /*< [cV] Voltage.*/
+ uint16_t current[4]; /*< [cA] Current.*/
+ uint16_t totalcurrent[4]; /*< [mAh] Total current.*/
+ uint16_t rpm[4]; /*< [rpm] RPM (eRPM).*/
+ uint16_t count[4]; /*< count of telemetry packets received (wraps at 65535).*/
+ uint8_t temperature[4]; /*< [degC] Temperature.*/
+} mavlink_esc_telemetry_1_to_4_t;
+
+#define MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_LEN 44
+#define MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_MIN_LEN 44
+#define MAVLINK_MSG_ID_11030_LEN 44
+#define MAVLINK_MSG_ID_11030_MIN_LEN 44
+
+#define MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_CRC 144
+#define MAVLINK_MSG_ID_11030_CRC 144
+
+#define MAVLINK_MSG_ESC_TELEMETRY_1_TO_4_FIELD_VOLTAGE_LEN 4
+#define MAVLINK_MSG_ESC_TELEMETRY_1_TO_4_FIELD_CURRENT_LEN 4
+#define MAVLINK_MSG_ESC_TELEMETRY_1_TO_4_FIELD_TOTALCURRENT_LEN 4
+#define MAVLINK_MSG_ESC_TELEMETRY_1_TO_4_FIELD_RPM_LEN 4
+#define MAVLINK_MSG_ESC_TELEMETRY_1_TO_4_FIELD_COUNT_LEN 4
+#define MAVLINK_MSG_ESC_TELEMETRY_1_TO_4_FIELD_TEMPERATURE_LEN 4
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_ESC_TELEMETRY_1_TO_4 { \
+ 11030, \
+ "ESC_TELEMETRY_1_TO_4", \
+ 6, \
+ { { "temperature", NULL, MAVLINK_TYPE_UINT8_T, 4, 40, offsetof(mavlink_esc_telemetry_1_to_4_t, temperature) }, \
+ { "voltage", NULL, MAVLINK_TYPE_UINT16_T, 4, 0, offsetof(mavlink_esc_telemetry_1_to_4_t, voltage) }, \
+ { "current", NULL, MAVLINK_TYPE_UINT16_T, 4, 8, offsetof(mavlink_esc_telemetry_1_to_4_t, current) }, \
+ { "totalcurrent", NULL, MAVLINK_TYPE_UINT16_T, 4, 16, offsetof(mavlink_esc_telemetry_1_to_4_t, totalcurrent) }, \
+ { "rpm", NULL, MAVLINK_TYPE_UINT16_T, 4, 24, offsetof(mavlink_esc_telemetry_1_to_4_t, rpm) }, \
+ { "count", NULL, MAVLINK_TYPE_UINT16_T, 4, 32, offsetof(mavlink_esc_telemetry_1_to_4_t, count) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_ESC_TELEMETRY_1_TO_4 { \
+ "ESC_TELEMETRY_1_TO_4", \
+ 6, \
+ { { "temperature", NULL, MAVLINK_TYPE_UINT8_T, 4, 40, offsetof(mavlink_esc_telemetry_1_to_4_t, temperature) }, \
+ { "voltage", NULL, MAVLINK_TYPE_UINT16_T, 4, 0, offsetof(mavlink_esc_telemetry_1_to_4_t, voltage) }, \
+ { "current", NULL, MAVLINK_TYPE_UINT16_T, 4, 8, offsetof(mavlink_esc_telemetry_1_to_4_t, current) }, \
+ { "totalcurrent", NULL, MAVLINK_TYPE_UINT16_T, 4, 16, offsetof(mavlink_esc_telemetry_1_to_4_t, totalcurrent) }, \
+ { "rpm", NULL, MAVLINK_TYPE_UINT16_T, 4, 24, offsetof(mavlink_esc_telemetry_1_to_4_t, rpm) }, \
+ { "count", NULL, MAVLINK_TYPE_UINT16_T, 4, 32, offsetof(mavlink_esc_telemetry_1_to_4_t, count) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a esc_telemetry_1_to_4 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 temperature [degC] Temperature.
+ * @param voltage [cV] Voltage.
+ * @param current [cA] Current.
+ * @param totalcurrent [mAh] Total current.
+ * @param rpm [rpm] RPM (eRPM).
+ * @param count count of telemetry packets received (wraps at 65535).
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_1_to_4_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ const uint8_t *temperature, const uint16_t *voltage, const uint16_t *current, const uint16_t *totalcurrent, const uint16_t *rpm, const uint16_t *count)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_LEN];
+
+ _mav_put_uint16_t_array(buf, 0, voltage, 4);
+ _mav_put_uint16_t_array(buf, 8, current, 4);
+ _mav_put_uint16_t_array(buf, 16, totalcurrent, 4);
+ _mav_put_uint16_t_array(buf, 24, rpm, 4);
+ _mav_put_uint16_t_array(buf, 32, count, 4);
+ _mav_put_uint8_t_array(buf, 40, temperature, 4);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_LEN);
+#else
+ mavlink_esc_telemetry_1_to_4_t packet;
+
+ mav_array_assign_uint16_t(packet.voltage, voltage, 4);
+ mav_array_assign_uint16_t(packet.current, current, 4);
+ mav_array_assign_uint16_t(packet.totalcurrent, totalcurrent, 4);
+ mav_array_assign_uint16_t(packet.rpm, rpm, 4);
+ mav_array_assign_uint16_t(packet.count, count, 4);
+ mav_array_assign_uint8_t(packet.temperature, temperature, 4);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_MIN_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_CRC);
+}
+
+/**
+ * @brief Pack a esc_telemetry_1_to_4 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 temperature [degC] Temperature.
+ * @param voltage [cV] Voltage.
+ * @param current [cA] Current.
+ * @param totalcurrent [mAh] Total current.
+ * @param rpm [rpm] RPM (eRPM).
+ * @param count count of telemetry packets received (wraps at 65535).
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_1_to_4_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ const uint8_t *temperature, const uint16_t *voltage, const uint16_t *current, const uint16_t *totalcurrent, const uint16_t *rpm, const uint16_t *count)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_LEN];
+
+ _mav_put_uint16_t_array(buf, 0, voltage, 4);
+ _mav_put_uint16_t_array(buf, 8, current, 4);
+ _mav_put_uint16_t_array(buf, 16, totalcurrent, 4);
+ _mav_put_uint16_t_array(buf, 24, rpm, 4);
+ _mav_put_uint16_t_array(buf, 32, count, 4);
+ _mav_put_uint8_t_array(buf, 40, temperature, 4);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_LEN);
+#else
+ mavlink_esc_telemetry_1_to_4_t packet;
+
+ mav_array_memcpy(packet.voltage, voltage, sizeof(uint16_t)*4);
+ mav_array_memcpy(packet.current, current, sizeof(uint16_t)*4);
+ mav_array_memcpy(packet.totalcurrent, totalcurrent, sizeof(uint16_t)*4);
+ mav_array_memcpy(packet.rpm, rpm, sizeof(uint16_t)*4);
+ mav_array_memcpy(packet.count, count, sizeof(uint16_t)*4);
+ mav_array_memcpy(packet.temperature, temperature, sizeof(uint8_t)*4);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_MIN_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_MIN_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a esc_telemetry_1_to_4 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 temperature [degC] Temperature.
+ * @param voltage [cV] Voltage.
+ * @param current [cA] Current.
+ * @param totalcurrent [mAh] Total current.
+ * @param rpm [rpm] RPM (eRPM).
+ * @param count count of telemetry packets received (wraps at 65535).
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_1_to_4_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ const uint8_t *temperature,const uint16_t *voltage,const uint16_t *current,const uint16_t *totalcurrent,const uint16_t *rpm,const uint16_t *count)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_LEN];
+
+ _mav_put_uint16_t_array(buf, 0, voltage, 4);
+ _mav_put_uint16_t_array(buf, 8, current, 4);
+ _mav_put_uint16_t_array(buf, 16, totalcurrent, 4);
+ _mav_put_uint16_t_array(buf, 24, rpm, 4);
+ _mav_put_uint16_t_array(buf, 32, count, 4);
+ _mav_put_uint8_t_array(buf, 40, temperature, 4);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_LEN);
+#else
+ mavlink_esc_telemetry_1_to_4_t packet;
+
+ mav_array_assign_uint16_t(packet.voltage, voltage, 4);
+ mav_array_assign_uint16_t(packet.current, current, 4);
+ mav_array_assign_uint16_t(packet.totalcurrent, totalcurrent, 4);
+ mav_array_assign_uint16_t(packet.rpm, rpm, 4);
+ mav_array_assign_uint16_t(packet.count, count, 4);
+ mav_array_assign_uint8_t(packet.temperature, temperature, 4);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_MIN_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_CRC);
+}
+
+/**
+ * @brief Encode a esc_telemetry_1_to_4 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 esc_telemetry_1_to_4 C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_1_to_4_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_esc_telemetry_1_to_4_t* esc_telemetry_1_to_4)
+{
+ return mavlink_msg_esc_telemetry_1_to_4_pack(system_id, component_id, msg, esc_telemetry_1_to_4->temperature, esc_telemetry_1_to_4->voltage, esc_telemetry_1_to_4->current, esc_telemetry_1_to_4->totalcurrent, esc_telemetry_1_to_4->rpm, esc_telemetry_1_to_4->count);
+}
+
+/**
+ * @brief Encode a esc_telemetry_1_to_4 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 esc_telemetry_1_to_4 C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_1_to_4_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_esc_telemetry_1_to_4_t* esc_telemetry_1_to_4)
+{
+ return mavlink_msg_esc_telemetry_1_to_4_pack_chan(system_id, component_id, chan, msg, esc_telemetry_1_to_4->temperature, esc_telemetry_1_to_4->voltage, esc_telemetry_1_to_4->current, esc_telemetry_1_to_4->totalcurrent, esc_telemetry_1_to_4->rpm, esc_telemetry_1_to_4->count);
+}
+
+/**
+ * @brief Encode a esc_telemetry_1_to_4 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 esc_telemetry_1_to_4 C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_1_to_4_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_esc_telemetry_1_to_4_t* esc_telemetry_1_to_4)
+{
+ return mavlink_msg_esc_telemetry_1_to_4_pack_status(system_id, component_id, _status, msg, esc_telemetry_1_to_4->temperature, esc_telemetry_1_to_4->voltage, esc_telemetry_1_to_4->current, esc_telemetry_1_to_4->totalcurrent, esc_telemetry_1_to_4->rpm, esc_telemetry_1_to_4->count);
+}
+
+/**
+ * @brief Send a esc_telemetry_1_to_4 message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param temperature [degC] Temperature.
+ * @param voltage [cV] Voltage.
+ * @param current [cA] Current.
+ * @param totalcurrent [mAh] Total current.
+ * @param rpm [rpm] RPM (eRPM).
+ * @param count count of telemetry packets received (wraps at 65535).
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_esc_telemetry_1_to_4_send(mavlink_channel_t chan, const uint8_t *temperature, const uint16_t *voltage, const uint16_t *current, const uint16_t *totalcurrent, const uint16_t *rpm, const uint16_t *count)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_LEN];
+
+ _mav_put_uint16_t_array(buf, 0, voltage, 4);
+ _mav_put_uint16_t_array(buf, 8, current, 4);
+ _mav_put_uint16_t_array(buf, 16, totalcurrent, 4);
+ _mav_put_uint16_t_array(buf, 24, rpm, 4);
+ _mav_put_uint16_t_array(buf, 32, count, 4);
+ _mav_put_uint8_t_array(buf, 40, temperature, 4);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4, buf, MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_MIN_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_CRC);
+#else
+ mavlink_esc_telemetry_1_to_4_t packet;
+
+ mav_array_assign_uint16_t(packet.voltage, voltage, 4);
+ mav_array_assign_uint16_t(packet.current, current, 4);
+ mav_array_assign_uint16_t(packet.totalcurrent, totalcurrent, 4);
+ mav_array_assign_uint16_t(packet.rpm, rpm, 4);
+ mav_array_assign_uint16_t(packet.count, count, 4);
+ mav_array_assign_uint8_t(packet.temperature, temperature, 4);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4, (const char *)&packet, MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_MIN_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_CRC);
+#endif
+}
+
+/**
+ * @brief Send a esc_telemetry_1_to_4 message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_esc_telemetry_1_to_4_send_struct(mavlink_channel_t chan, const mavlink_esc_telemetry_1_to_4_t* esc_telemetry_1_to_4)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_esc_telemetry_1_to_4_send(chan, esc_telemetry_1_to_4->temperature, esc_telemetry_1_to_4->voltage, esc_telemetry_1_to_4->current, esc_telemetry_1_to_4->totalcurrent, esc_telemetry_1_to_4->rpm, esc_telemetry_1_to_4->count);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4, (const char *)esc_telemetry_1_to_4, MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_MIN_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_esc_telemetry_1_to_4_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, const uint8_t *temperature, const uint16_t *voltage, const uint16_t *current, const uint16_t *totalcurrent, const uint16_t *rpm, const uint16_t *count)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+
+ _mav_put_uint16_t_array(buf, 0, voltage, 4);
+ _mav_put_uint16_t_array(buf, 8, current, 4);
+ _mav_put_uint16_t_array(buf, 16, totalcurrent, 4);
+ _mav_put_uint16_t_array(buf, 24, rpm, 4);
+ _mav_put_uint16_t_array(buf, 32, count, 4);
+ _mav_put_uint8_t_array(buf, 40, temperature, 4);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4, buf, MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_MIN_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_CRC);
+#else
+ mavlink_esc_telemetry_1_to_4_t *packet = (mavlink_esc_telemetry_1_to_4_t *)msgbuf;
+
+ mav_array_assign_uint16_t(packet->voltage, voltage, 4);
+ mav_array_assign_uint16_t(packet->current, current, 4);
+ mav_array_assign_uint16_t(packet->totalcurrent, totalcurrent, 4);
+ mav_array_assign_uint16_t(packet->rpm, rpm, 4);
+ mav_array_assign_uint16_t(packet->count, count, 4);
+ mav_array_assign_uint8_t(packet->temperature, temperature, 4);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4, (const char *)packet, MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_MIN_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE ESC_TELEMETRY_1_TO_4 UNPACKING
+
+
+/**
+ * @brief Get field temperature from esc_telemetry_1_to_4 message
+ *
+ * @return [degC] Temperature.
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_1_to_4_get_temperature(const mavlink_message_t* msg, uint8_t *temperature)
+{
+ return _MAV_RETURN_uint8_t_array(msg, temperature, 4, 40);
+}
+
+/**
+ * @brief Get field voltage from esc_telemetry_1_to_4 message
+ *
+ * @return [cV] Voltage.
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_1_to_4_get_voltage(const mavlink_message_t* msg, uint16_t *voltage)
+{
+ return _MAV_RETURN_uint16_t_array(msg, voltage, 4, 0);
+}
+
+/**
+ * @brief Get field current from esc_telemetry_1_to_4 message
+ *
+ * @return [cA] Current.
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_1_to_4_get_current(const mavlink_message_t* msg, uint16_t *current)
+{
+ return _MAV_RETURN_uint16_t_array(msg, current, 4, 8);
+}
+
+/**
+ * @brief Get field totalcurrent from esc_telemetry_1_to_4 message
+ *
+ * @return [mAh] Total current.
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_1_to_4_get_totalcurrent(const mavlink_message_t* msg, uint16_t *totalcurrent)
+{
+ return _MAV_RETURN_uint16_t_array(msg, totalcurrent, 4, 16);
+}
+
+/**
+ * @brief Get field rpm from esc_telemetry_1_to_4 message
+ *
+ * @return [rpm] RPM (eRPM).
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_1_to_4_get_rpm(const mavlink_message_t* msg, uint16_t *rpm)
+{
+ return _MAV_RETURN_uint16_t_array(msg, rpm, 4, 24);
+}
+
+/**
+ * @brief Get field count from esc_telemetry_1_to_4 message
+ *
+ * @return count of telemetry packets received (wraps at 65535).
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_1_to_4_get_count(const mavlink_message_t* msg, uint16_t *count)
+{
+ return _MAV_RETURN_uint16_t_array(msg, count, 4, 32);
+}
+
+/**
+ * @brief Decode a esc_telemetry_1_to_4 message into a struct
+ *
+ * @param msg The message to decode
+ * @param esc_telemetry_1_to_4 C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_esc_telemetry_1_to_4_decode(const mavlink_message_t* msg, mavlink_esc_telemetry_1_to_4_t* esc_telemetry_1_to_4)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_esc_telemetry_1_to_4_get_voltage(msg, esc_telemetry_1_to_4->voltage);
+ mavlink_msg_esc_telemetry_1_to_4_get_current(msg, esc_telemetry_1_to_4->current);
+ mavlink_msg_esc_telemetry_1_to_4_get_totalcurrent(msg, esc_telemetry_1_to_4->totalcurrent);
+ mavlink_msg_esc_telemetry_1_to_4_get_rpm(msg, esc_telemetry_1_to_4->rpm);
+ mavlink_msg_esc_telemetry_1_to_4_get_count(msg, esc_telemetry_1_to_4->count);
+ mavlink_msg_esc_telemetry_1_to_4_get_temperature(msg, esc_telemetry_1_to_4->temperature);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_LEN? msg->len : MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_LEN;
+ memset(esc_telemetry_1_to_4, 0, MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_LEN);
+ memcpy(esc_telemetry_1_to_4, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/ardupilotmega/mavlink_msg_esc_telemetry_21_to_24.h b/lib/main/MAVLink/ardupilotmega/mavlink_msg_esc_telemetry_21_to_24.h
new file mode 100644
index 00000000000..e87219835d5
--- /dev/null
+++ b/lib/main/MAVLink/ardupilotmega/mavlink_msg_esc_telemetry_21_to_24.h
@@ -0,0 +1,405 @@
+#pragma once
+// MESSAGE ESC_TELEMETRY_21_TO_24 PACKING
+
+#define MAVLINK_MSG_ID_ESC_TELEMETRY_21_TO_24 11042
+
+
+typedef struct __mavlink_esc_telemetry_21_to_24_t {
+ uint16_t voltage[4]; /*< [cV] Voltage.*/
+ uint16_t current[4]; /*< [cA] Current.*/
+ uint16_t totalcurrent[4]; /*< [mAh] Total current.*/
+ uint16_t rpm[4]; /*< [rpm] RPM (eRPM).*/
+ uint16_t count[4]; /*< count of telemetry packets received (wraps at 65535).*/
+ uint8_t temperature[4]; /*< [degC] Temperature.*/
+} mavlink_esc_telemetry_21_to_24_t;
+
+#define MAVLINK_MSG_ID_ESC_TELEMETRY_21_TO_24_LEN 44
+#define MAVLINK_MSG_ID_ESC_TELEMETRY_21_TO_24_MIN_LEN 44
+#define MAVLINK_MSG_ID_11042_LEN 44
+#define MAVLINK_MSG_ID_11042_MIN_LEN 44
+
+#define MAVLINK_MSG_ID_ESC_TELEMETRY_21_TO_24_CRC 201
+#define MAVLINK_MSG_ID_11042_CRC 201
+
+#define MAVLINK_MSG_ESC_TELEMETRY_21_TO_24_FIELD_VOLTAGE_LEN 4
+#define MAVLINK_MSG_ESC_TELEMETRY_21_TO_24_FIELD_CURRENT_LEN 4
+#define MAVLINK_MSG_ESC_TELEMETRY_21_TO_24_FIELD_TOTALCURRENT_LEN 4
+#define MAVLINK_MSG_ESC_TELEMETRY_21_TO_24_FIELD_RPM_LEN 4
+#define MAVLINK_MSG_ESC_TELEMETRY_21_TO_24_FIELD_COUNT_LEN 4
+#define MAVLINK_MSG_ESC_TELEMETRY_21_TO_24_FIELD_TEMPERATURE_LEN 4
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_ESC_TELEMETRY_21_TO_24 { \
+ 11042, \
+ "ESC_TELEMETRY_21_TO_24", \
+ 6, \
+ { { "temperature", NULL, MAVLINK_TYPE_UINT8_T, 4, 40, offsetof(mavlink_esc_telemetry_21_to_24_t, temperature) }, \
+ { "voltage", NULL, MAVLINK_TYPE_UINT16_T, 4, 0, offsetof(mavlink_esc_telemetry_21_to_24_t, voltage) }, \
+ { "current", NULL, MAVLINK_TYPE_UINT16_T, 4, 8, offsetof(mavlink_esc_telemetry_21_to_24_t, current) }, \
+ { "totalcurrent", NULL, MAVLINK_TYPE_UINT16_T, 4, 16, offsetof(mavlink_esc_telemetry_21_to_24_t, totalcurrent) }, \
+ { "rpm", NULL, MAVLINK_TYPE_UINT16_T, 4, 24, offsetof(mavlink_esc_telemetry_21_to_24_t, rpm) }, \
+ { "count", NULL, MAVLINK_TYPE_UINT16_T, 4, 32, offsetof(mavlink_esc_telemetry_21_to_24_t, count) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_ESC_TELEMETRY_21_TO_24 { \
+ "ESC_TELEMETRY_21_TO_24", \
+ 6, \
+ { { "temperature", NULL, MAVLINK_TYPE_UINT8_T, 4, 40, offsetof(mavlink_esc_telemetry_21_to_24_t, temperature) }, \
+ { "voltage", NULL, MAVLINK_TYPE_UINT16_T, 4, 0, offsetof(mavlink_esc_telemetry_21_to_24_t, voltage) }, \
+ { "current", NULL, MAVLINK_TYPE_UINT16_T, 4, 8, offsetof(mavlink_esc_telemetry_21_to_24_t, current) }, \
+ { "totalcurrent", NULL, MAVLINK_TYPE_UINT16_T, 4, 16, offsetof(mavlink_esc_telemetry_21_to_24_t, totalcurrent) }, \
+ { "rpm", NULL, MAVLINK_TYPE_UINT16_T, 4, 24, offsetof(mavlink_esc_telemetry_21_to_24_t, rpm) }, \
+ { "count", NULL, MAVLINK_TYPE_UINT16_T, 4, 32, offsetof(mavlink_esc_telemetry_21_to_24_t, count) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a esc_telemetry_21_to_24 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 temperature [degC] Temperature.
+ * @param voltage [cV] Voltage.
+ * @param current [cA] Current.
+ * @param totalcurrent [mAh] Total current.
+ * @param rpm [rpm] RPM (eRPM).
+ * @param count count of telemetry packets received (wraps at 65535).
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_21_to_24_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ const uint8_t *temperature, const uint16_t *voltage, const uint16_t *current, const uint16_t *totalcurrent, const uint16_t *rpm, const uint16_t *count)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_ESC_TELEMETRY_21_TO_24_LEN];
+
+ _mav_put_uint16_t_array(buf, 0, voltage, 4);
+ _mav_put_uint16_t_array(buf, 8, current, 4);
+ _mav_put_uint16_t_array(buf, 16, totalcurrent, 4);
+ _mav_put_uint16_t_array(buf, 24, rpm, 4);
+ _mav_put_uint16_t_array(buf, 32, count, 4);
+ _mav_put_uint8_t_array(buf, 40, temperature, 4);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ESC_TELEMETRY_21_TO_24_LEN);
+#else
+ mavlink_esc_telemetry_21_to_24_t packet;
+
+ mav_array_assign_uint16_t(packet.voltage, voltage, 4);
+ mav_array_assign_uint16_t(packet.current, current, 4);
+ mav_array_assign_uint16_t(packet.totalcurrent, totalcurrent, 4);
+ mav_array_assign_uint16_t(packet.rpm, rpm, 4);
+ mav_array_assign_uint16_t(packet.count, count, 4);
+ mav_array_assign_uint8_t(packet.temperature, temperature, 4);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ESC_TELEMETRY_21_TO_24_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_ESC_TELEMETRY_21_TO_24;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ESC_TELEMETRY_21_TO_24_MIN_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_21_TO_24_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_21_TO_24_CRC);
+}
+
+/**
+ * @brief Pack a esc_telemetry_21_to_24 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 temperature [degC] Temperature.
+ * @param voltage [cV] Voltage.
+ * @param current [cA] Current.
+ * @param totalcurrent [mAh] Total current.
+ * @param rpm [rpm] RPM (eRPM).
+ * @param count count of telemetry packets received (wraps at 65535).
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_21_to_24_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ const uint8_t *temperature, const uint16_t *voltage, const uint16_t *current, const uint16_t *totalcurrent, const uint16_t *rpm, const uint16_t *count)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_ESC_TELEMETRY_21_TO_24_LEN];
+
+ _mav_put_uint16_t_array(buf, 0, voltage, 4);
+ _mav_put_uint16_t_array(buf, 8, current, 4);
+ _mav_put_uint16_t_array(buf, 16, totalcurrent, 4);
+ _mav_put_uint16_t_array(buf, 24, rpm, 4);
+ _mav_put_uint16_t_array(buf, 32, count, 4);
+ _mav_put_uint8_t_array(buf, 40, temperature, 4);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ESC_TELEMETRY_21_TO_24_LEN);
+#else
+ mavlink_esc_telemetry_21_to_24_t packet;
+
+ mav_array_memcpy(packet.voltage, voltage, sizeof(uint16_t)*4);
+ mav_array_memcpy(packet.current, current, sizeof(uint16_t)*4);
+ mav_array_memcpy(packet.totalcurrent, totalcurrent, sizeof(uint16_t)*4);
+ mav_array_memcpy(packet.rpm, rpm, sizeof(uint16_t)*4);
+ mav_array_memcpy(packet.count, count, sizeof(uint16_t)*4);
+ mav_array_memcpy(packet.temperature, temperature, sizeof(uint8_t)*4);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ESC_TELEMETRY_21_TO_24_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_ESC_TELEMETRY_21_TO_24;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_ESC_TELEMETRY_21_TO_24_MIN_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_21_TO_24_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_21_TO_24_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_ESC_TELEMETRY_21_TO_24_MIN_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_21_TO_24_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a esc_telemetry_21_to_24 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 temperature [degC] Temperature.
+ * @param voltage [cV] Voltage.
+ * @param current [cA] Current.
+ * @param totalcurrent [mAh] Total current.
+ * @param rpm [rpm] RPM (eRPM).
+ * @param count count of telemetry packets received (wraps at 65535).
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_21_to_24_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ const uint8_t *temperature,const uint16_t *voltage,const uint16_t *current,const uint16_t *totalcurrent,const uint16_t *rpm,const uint16_t *count)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_ESC_TELEMETRY_21_TO_24_LEN];
+
+ _mav_put_uint16_t_array(buf, 0, voltage, 4);
+ _mav_put_uint16_t_array(buf, 8, current, 4);
+ _mav_put_uint16_t_array(buf, 16, totalcurrent, 4);
+ _mav_put_uint16_t_array(buf, 24, rpm, 4);
+ _mav_put_uint16_t_array(buf, 32, count, 4);
+ _mav_put_uint8_t_array(buf, 40, temperature, 4);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ESC_TELEMETRY_21_TO_24_LEN);
+#else
+ mavlink_esc_telemetry_21_to_24_t packet;
+
+ mav_array_assign_uint16_t(packet.voltage, voltage, 4);
+ mav_array_assign_uint16_t(packet.current, current, 4);
+ mav_array_assign_uint16_t(packet.totalcurrent, totalcurrent, 4);
+ mav_array_assign_uint16_t(packet.rpm, rpm, 4);
+ mav_array_assign_uint16_t(packet.count, count, 4);
+ mav_array_assign_uint8_t(packet.temperature, temperature, 4);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ESC_TELEMETRY_21_TO_24_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_ESC_TELEMETRY_21_TO_24;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ESC_TELEMETRY_21_TO_24_MIN_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_21_TO_24_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_21_TO_24_CRC);
+}
+
+/**
+ * @brief Encode a esc_telemetry_21_to_24 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 esc_telemetry_21_to_24 C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_21_to_24_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_esc_telemetry_21_to_24_t* esc_telemetry_21_to_24)
+{
+ return mavlink_msg_esc_telemetry_21_to_24_pack(system_id, component_id, msg, esc_telemetry_21_to_24->temperature, esc_telemetry_21_to_24->voltage, esc_telemetry_21_to_24->current, esc_telemetry_21_to_24->totalcurrent, esc_telemetry_21_to_24->rpm, esc_telemetry_21_to_24->count);
+}
+
+/**
+ * @brief Encode a esc_telemetry_21_to_24 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 esc_telemetry_21_to_24 C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_21_to_24_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_esc_telemetry_21_to_24_t* esc_telemetry_21_to_24)
+{
+ return mavlink_msg_esc_telemetry_21_to_24_pack_chan(system_id, component_id, chan, msg, esc_telemetry_21_to_24->temperature, esc_telemetry_21_to_24->voltage, esc_telemetry_21_to_24->current, esc_telemetry_21_to_24->totalcurrent, esc_telemetry_21_to_24->rpm, esc_telemetry_21_to_24->count);
+}
+
+/**
+ * @brief Encode a esc_telemetry_21_to_24 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 esc_telemetry_21_to_24 C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_21_to_24_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_esc_telemetry_21_to_24_t* esc_telemetry_21_to_24)
+{
+ return mavlink_msg_esc_telemetry_21_to_24_pack_status(system_id, component_id, _status, msg, esc_telemetry_21_to_24->temperature, esc_telemetry_21_to_24->voltage, esc_telemetry_21_to_24->current, esc_telemetry_21_to_24->totalcurrent, esc_telemetry_21_to_24->rpm, esc_telemetry_21_to_24->count);
+}
+
+/**
+ * @brief Send a esc_telemetry_21_to_24 message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param temperature [degC] Temperature.
+ * @param voltage [cV] Voltage.
+ * @param current [cA] Current.
+ * @param totalcurrent [mAh] Total current.
+ * @param rpm [rpm] RPM (eRPM).
+ * @param count count of telemetry packets received (wraps at 65535).
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_esc_telemetry_21_to_24_send(mavlink_channel_t chan, const uint8_t *temperature, const uint16_t *voltage, const uint16_t *current, const uint16_t *totalcurrent, const uint16_t *rpm, const uint16_t *count)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_ESC_TELEMETRY_21_TO_24_LEN];
+
+ _mav_put_uint16_t_array(buf, 0, voltage, 4);
+ _mav_put_uint16_t_array(buf, 8, current, 4);
+ _mav_put_uint16_t_array(buf, 16, totalcurrent, 4);
+ _mav_put_uint16_t_array(buf, 24, rpm, 4);
+ _mav_put_uint16_t_array(buf, 32, count, 4);
+ _mav_put_uint8_t_array(buf, 40, temperature, 4);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESC_TELEMETRY_21_TO_24, buf, MAVLINK_MSG_ID_ESC_TELEMETRY_21_TO_24_MIN_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_21_TO_24_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_21_TO_24_CRC);
+#else
+ mavlink_esc_telemetry_21_to_24_t packet;
+
+ mav_array_assign_uint16_t(packet.voltage, voltage, 4);
+ mav_array_assign_uint16_t(packet.current, current, 4);
+ mav_array_assign_uint16_t(packet.totalcurrent, totalcurrent, 4);
+ mav_array_assign_uint16_t(packet.rpm, rpm, 4);
+ mav_array_assign_uint16_t(packet.count, count, 4);
+ mav_array_assign_uint8_t(packet.temperature, temperature, 4);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESC_TELEMETRY_21_TO_24, (const char *)&packet, MAVLINK_MSG_ID_ESC_TELEMETRY_21_TO_24_MIN_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_21_TO_24_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_21_TO_24_CRC);
+#endif
+}
+
+/**
+ * @brief Send a esc_telemetry_21_to_24 message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_esc_telemetry_21_to_24_send_struct(mavlink_channel_t chan, const mavlink_esc_telemetry_21_to_24_t* esc_telemetry_21_to_24)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_esc_telemetry_21_to_24_send(chan, esc_telemetry_21_to_24->temperature, esc_telemetry_21_to_24->voltage, esc_telemetry_21_to_24->current, esc_telemetry_21_to_24->totalcurrent, esc_telemetry_21_to_24->rpm, esc_telemetry_21_to_24->count);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESC_TELEMETRY_21_TO_24, (const char *)esc_telemetry_21_to_24, MAVLINK_MSG_ID_ESC_TELEMETRY_21_TO_24_MIN_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_21_TO_24_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_21_TO_24_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_ESC_TELEMETRY_21_TO_24_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_esc_telemetry_21_to_24_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, const uint8_t *temperature, const uint16_t *voltage, const uint16_t *current, const uint16_t *totalcurrent, const uint16_t *rpm, const uint16_t *count)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+
+ _mav_put_uint16_t_array(buf, 0, voltage, 4);
+ _mav_put_uint16_t_array(buf, 8, current, 4);
+ _mav_put_uint16_t_array(buf, 16, totalcurrent, 4);
+ _mav_put_uint16_t_array(buf, 24, rpm, 4);
+ _mav_put_uint16_t_array(buf, 32, count, 4);
+ _mav_put_uint8_t_array(buf, 40, temperature, 4);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESC_TELEMETRY_21_TO_24, buf, MAVLINK_MSG_ID_ESC_TELEMETRY_21_TO_24_MIN_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_21_TO_24_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_21_TO_24_CRC);
+#else
+ mavlink_esc_telemetry_21_to_24_t *packet = (mavlink_esc_telemetry_21_to_24_t *)msgbuf;
+
+ mav_array_assign_uint16_t(packet->voltage, voltage, 4);
+ mav_array_assign_uint16_t(packet->current, current, 4);
+ mav_array_assign_uint16_t(packet->totalcurrent, totalcurrent, 4);
+ mav_array_assign_uint16_t(packet->rpm, rpm, 4);
+ mav_array_assign_uint16_t(packet->count, count, 4);
+ mav_array_assign_uint8_t(packet->temperature, temperature, 4);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESC_TELEMETRY_21_TO_24, (const char *)packet, MAVLINK_MSG_ID_ESC_TELEMETRY_21_TO_24_MIN_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_21_TO_24_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_21_TO_24_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE ESC_TELEMETRY_21_TO_24 UNPACKING
+
+
+/**
+ * @brief Get field temperature from esc_telemetry_21_to_24 message
+ *
+ * @return [degC] Temperature.
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_21_to_24_get_temperature(const mavlink_message_t* msg, uint8_t *temperature)
+{
+ return _MAV_RETURN_uint8_t_array(msg, temperature, 4, 40);
+}
+
+/**
+ * @brief Get field voltage from esc_telemetry_21_to_24 message
+ *
+ * @return [cV] Voltage.
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_21_to_24_get_voltage(const mavlink_message_t* msg, uint16_t *voltage)
+{
+ return _MAV_RETURN_uint16_t_array(msg, voltage, 4, 0);
+}
+
+/**
+ * @brief Get field current from esc_telemetry_21_to_24 message
+ *
+ * @return [cA] Current.
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_21_to_24_get_current(const mavlink_message_t* msg, uint16_t *current)
+{
+ return _MAV_RETURN_uint16_t_array(msg, current, 4, 8);
+}
+
+/**
+ * @brief Get field totalcurrent from esc_telemetry_21_to_24 message
+ *
+ * @return [mAh] Total current.
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_21_to_24_get_totalcurrent(const mavlink_message_t* msg, uint16_t *totalcurrent)
+{
+ return _MAV_RETURN_uint16_t_array(msg, totalcurrent, 4, 16);
+}
+
+/**
+ * @brief Get field rpm from esc_telemetry_21_to_24 message
+ *
+ * @return [rpm] RPM (eRPM).
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_21_to_24_get_rpm(const mavlink_message_t* msg, uint16_t *rpm)
+{
+ return _MAV_RETURN_uint16_t_array(msg, rpm, 4, 24);
+}
+
+/**
+ * @brief Get field count from esc_telemetry_21_to_24 message
+ *
+ * @return count of telemetry packets received (wraps at 65535).
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_21_to_24_get_count(const mavlink_message_t* msg, uint16_t *count)
+{
+ return _MAV_RETURN_uint16_t_array(msg, count, 4, 32);
+}
+
+/**
+ * @brief Decode a esc_telemetry_21_to_24 message into a struct
+ *
+ * @param msg The message to decode
+ * @param esc_telemetry_21_to_24 C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_esc_telemetry_21_to_24_decode(const mavlink_message_t* msg, mavlink_esc_telemetry_21_to_24_t* esc_telemetry_21_to_24)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_esc_telemetry_21_to_24_get_voltage(msg, esc_telemetry_21_to_24->voltage);
+ mavlink_msg_esc_telemetry_21_to_24_get_current(msg, esc_telemetry_21_to_24->current);
+ mavlink_msg_esc_telemetry_21_to_24_get_totalcurrent(msg, esc_telemetry_21_to_24->totalcurrent);
+ mavlink_msg_esc_telemetry_21_to_24_get_rpm(msg, esc_telemetry_21_to_24->rpm);
+ mavlink_msg_esc_telemetry_21_to_24_get_count(msg, esc_telemetry_21_to_24->count);
+ mavlink_msg_esc_telemetry_21_to_24_get_temperature(msg, esc_telemetry_21_to_24->temperature);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_ESC_TELEMETRY_21_TO_24_LEN? msg->len : MAVLINK_MSG_ID_ESC_TELEMETRY_21_TO_24_LEN;
+ memset(esc_telemetry_21_to_24, 0, MAVLINK_MSG_ID_ESC_TELEMETRY_21_TO_24_LEN);
+ memcpy(esc_telemetry_21_to_24, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/ardupilotmega/mavlink_msg_esc_telemetry_25_to_28.h b/lib/main/MAVLink/ardupilotmega/mavlink_msg_esc_telemetry_25_to_28.h
new file mode 100644
index 00000000000..193d0974ec6
--- /dev/null
+++ b/lib/main/MAVLink/ardupilotmega/mavlink_msg_esc_telemetry_25_to_28.h
@@ -0,0 +1,405 @@
+#pragma once
+// MESSAGE ESC_TELEMETRY_25_TO_28 PACKING
+
+#define MAVLINK_MSG_ID_ESC_TELEMETRY_25_TO_28 11043
+
+
+typedef struct __mavlink_esc_telemetry_25_to_28_t {
+ uint16_t voltage[4]; /*< [cV] Voltage.*/
+ uint16_t current[4]; /*< [cA] Current.*/
+ uint16_t totalcurrent[4]; /*< [mAh] Total current.*/
+ uint16_t rpm[4]; /*< [rpm] RPM (eRPM).*/
+ uint16_t count[4]; /*< count of telemetry packets received (wraps at 65535).*/
+ uint8_t temperature[4]; /*< [degC] Temperature.*/
+} mavlink_esc_telemetry_25_to_28_t;
+
+#define MAVLINK_MSG_ID_ESC_TELEMETRY_25_TO_28_LEN 44
+#define MAVLINK_MSG_ID_ESC_TELEMETRY_25_TO_28_MIN_LEN 44
+#define MAVLINK_MSG_ID_11043_LEN 44
+#define MAVLINK_MSG_ID_11043_MIN_LEN 44
+
+#define MAVLINK_MSG_ID_ESC_TELEMETRY_25_TO_28_CRC 193
+#define MAVLINK_MSG_ID_11043_CRC 193
+
+#define MAVLINK_MSG_ESC_TELEMETRY_25_TO_28_FIELD_VOLTAGE_LEN 4
+#define MAVLINK_MSG_ESC_TELEMETRY_25_TO_28_FIELD_CURRENT_LEN 4
+#define MAVLINK_MSG_ESC_TELEMETRY_25_TO_28_FIELD_TOTALCURRENT_LEN 4
+#define MAVLINK_MSG_ESC_TELEMETRY_25_TO_28_FIELD_RPM_LEN 4
+#define MAVLINK_MSG_ESC_TELEMETRY_25_TO_28_FIELD_COUNT_LEN 4
+#define MAVLINK_MSG_ESC_TELEMETRY_25_TO_28_FIELD_TEMPERATURE_LEN 4
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_ESC_TELEMETRY_25_TO_28 { \
+ 11043, \
+ "ESC_TELEMETRY_25_TO_28", \
+ 6, \
+ { { "temperature", NULL, MAVLINK_TYPE_UINT8_T, 4, 40, offsetof(mavlink_esc_telemetry_25_to_28_t, temperature) }, \
+ { "voltage", NULL, MAVLINK_TYPE_UINT16_T, 4, 0, offsetof(mavlink_esc_telemetry_25_to_28_t, voltage) }, \
+ { "current", NULL, MAVLINK_TYPE_UINT16_T, 4, 8, offsetof(mavlink_esc_telemetry_25_to_28_t, current) }, \
+ { "totalcurrent", NULL, MAVLINK_TYPE_UINT16_T, 4, 16, offsetof(mavlink_esc_telemetry_25_to_28_t, totalcurrent) }, \
+ { "rpm", NULL, MAVLINK_TYPE_UINT16_T, 4, 24, offsetof(mavlink_esc_telemetry_25_to_28_t, rpm) }, \
+ { "count", NULL, MAVLINK_TYPE_UINT16_T, 4, 32, offsetof(mavlink_esc_telemetry_25_to_28_t, count) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_ESC_TELEMETRY_25_TO_28 { \
+ "ESC_TELEMETRY_25_TO_28", \
+ 6, \
+ { { "temperature", NULL, MAVLINK_TYPE_UINT8_T, 4, 40, offsetof(mavlink_esc_telemetry_25_to_28_t, temperature) }, \
+ { "voltage", NULL, MAVLINK_TYPE_UINT16_T, 4, 0, offsetof(mavlink_esc_telemetry_25_to_28_t, voltage) }, \
+ { "current", NULL, MAVLINK_TYPE_UINT16_T, 4, 8, offsetof(mavlink_esc_telemetry_25_to_28_t, current) }, \
+ { "totalcurrent", NULL, MAVLINK_TYPE_UINT16_T, 4, 16, offsetof(mavlink_esc_telemetry_25_to_28_t, totalcurrent) }, \
+ { "rpm", NULL, MAVLINK_TYPE_UINT16_T, 4, 24, offsetof(mavlink_esc_telemetry_25_to_28_t, rpm) }, \
+ { "count", NULL, MAVLINK_TYPE_UINT16_T, 4, 32, offsetof(mavlink_esc_telemetry_25_to_28_t, count) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a esc_telemetry_25_to_28 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 temperature [degC] Temperature.
+ * @param voltage [cV] Voltage.
+ * @param current [cA] Current.
+ * @param totalcurrent [mAh] Total current.
+ * @param rpm [rpm] RPM (eRPM).
+ * @param count count of telemetry packets received (wraps at 65535).
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_25_to_28_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ const uint8_t *temperature, const uint16_t *voltage, const uint16_t *current, const uint16_t *totalcurrent, const uint16_t *rpm, const uint16_t *count)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_ESC_TELEMETRY_25_TO_28_LEN];
+
+ _mav_put_uint16_t_array(buf, 0, voltage, 4);
+ _mav_put_uint16_t_array(buf, 8, current, 4);
+ _mav_put_uint16_t_array(buf, 16, totalcurrent, 4);
+ _mav_put_uint16_t_array(buf, 24, rpm, 4);
+ _mav_put_uint16_t_array(buf, 32, count, 4);
+ _mav_put_uint8_t_array(buf, 40, temperature, 4);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ESC_TELEMETRY_25_TO_28_LEN);
+#else
+ mavlink_esc_telemetry_25_to_28_t packet;
+
+ mav_array_assign_uint16_t(packet.voltage, voltage, 4);
+ mav_array_assign_uint16_t(packet.current, current, 4);
+ mav_array_assign_uint16_t(packet.totalcurrent, totalcurrent, 4);
+ mav_array_assign_uint16_t(packet.rpm, rpm, 4);
+ mav_array_assign_uint16_t(packet.count, count, 4);
+ mav_array_assign_uint8_t(packet.temperature, temperature, 4);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ESC_TELEMETRY_25_TO_28_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_ESC_TELEMETRY_25_TO_28;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ESC_TELEMETRY_25_TO_28_MIN_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_25_TO_28_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_25_TO_28_CRC);
+}
+
+/**
+ * @brief Pack a esc_telemetry_25_to_28 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 temperature [degC] Temperature.
+ * @param voltage [cV] Voltage.
+ * @param current [cA] Current.
+ * @param totalcurrent [mAh] Total current.
+ * @param rpm [rpm] RPM (eRPM).
+ * @param count count of telemetry packets received (wraps at 65535).
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_25_to_28_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ const uint8_t *temperature, const uint16_t *voltage, const uint16_t *current, const uint16_t *totalcurrent, const uint16_t *rpm, const uint16_t *count)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_ESC_TELEMETRY_25_TO_28_LEN];
+
+ _mav_put_uint16_t_array(buf, 0, voltage, 4);
+ _mav_put_uint16_t_array(buf, 8, current, 4);
+ _mav_put_uint16_t_array(buf, 16, totalcurrent, 4);
+ _mav_put_uint16_t_array(buf, 24, rpm, 4);
+ _mav_put_uint16_t_array(buf, 32, count, 4);
+ _mav_put_uint8_t_array(buf, 40, temperature, 4);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ESC_TELEMETRY_25_TO_28_LEN);
+#else
+ mavlink_esc_telemetry_25_to_28_t packet;
+
+ mav_array_memcpy(packet.voltage, voltage, sizeof(uint16_t)*4);
+ mav_array_memcpy(packet.current, current, sizeof(uint16_t)*4);
+ mav_array_memcpy(packet.totalcurrent, totalcurrent, sizeof(uint16_t)*4);
+ mav_array_memcpy(packet.rpm, rpm, sizeof(uint16_t)*4);
+ mav_array_memcpy(packet.count, count, sizeof(uint16_t)*4);
+ mav_array_memcpy(packet.temperature, temperature, sizeof(uint8_t)*4);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ESC_TELEMETRY_25_TO_28_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_ESC_TELEMETRY_25_TO_28;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_ESC_TELEMETRY_25_TO_28_MIN_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_25_TO_28_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_25_TO_28_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_ESC_TELEMETRY_25_TO_28_MIN_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_25_TO_28_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a esc_telemetry_25_to_28 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 temperature [degC] Temperature.
+ * @param voltage [cV] Voltage.
+ * @param current [cA] Current.
+ * @param totalcurrent [mAh] Total current.
+ * @param rpm [rpm] RPM (eRPM).
+ * @param count count of telemetry packets received (wraps at 65535).
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_25_to_28_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ const uint8_t *temperature,const uint16_t *voltage,const uint16_t *current,const uint16_t *totalcurrent,const uint16_t *rpm,const uint16_t *count)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_ESC_TELEMETRY_25_TO_28_LEN];
+
+ _mav_put_uint16_t_array(buf, 0, voltage, 4);
+ _mav_put_uint16_t_array(buf, 8, current, 4);
+ _mav_put_uint16_t_array(buf, 16, totalcurrent, 4);
+ _mav_put_uint16_t_array(buf, 24, rpm, 4);
+ _mav_put_uint16_t_array(buf, 32, count, 4);
+ _mav_put_uint8_t_array(buf, 40, temperature, 4);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ESC_TELEMETRY_25_TO_28_LEN);
+#else
+ mavlink_esc_telemetry_25_to_28_t packet;
+
+ mav_array_assign_uint16_t(packet.voltage, voltage, 4);
+ mav_array_assign_uint16_t(packet.current, current, 4);
+ mav_array_assign_uint16_t(packet.totalcurrent, totalcurrent, 4);
+ mav_array_assign_uint16_t(packet.rpm, rpm, 4);
+ mav_array_assign_uint16_t(packet.count, count, 4);
+ mav_array_assign_uint8_t(packet.temperature, temperature, 4);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ESC_TELEMETRY_25_TO_28_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_ESC_TELEMETRY_25_TO_28;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ESC_TELEMETRY_25_TO_28_MIN_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_25_TO_28_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_25_TO_28_CRC);
+}
+
+/**
+ * @brief Encode a esc_telemetry_25_to_28 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 esc_telemetry_25_to_28 C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_25_to_28_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_esc_telemetry_25_to_28_t* esc_telemetry_25_to_28)
+{
+ return mavlink_msg_esc_telemetry_25_to_28_pack(system_id, component_id, msg, esc_telemetry_25_to_28->temperature, esc_telemetry_25_to_28->voltage, esc_telemetry_25_to_28->current, esc_telemetry_25_to_28->totalcurrent, esc_telemetry_25_to_28->rpm, esc_telemetry_25_to_28->count);
+}
+
+/**
+ * @brief Encode a esc_telemetry_25_to_28 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 esc_telemetry_25_to_28 C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_25_to_28_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_esc_telemetry_25_to_28_t* esc_telemetry_25_to_28)
+{
+ return mavlink_msg_esc_telemetry_25_to_28_pack_chan(system_id, component_id, chan, msg, esc_telemetry_25_to_28->temperature, esc_telemetry_25_to_28->voltage, esc_telemetry_25_to_28->current, esc_telemetry_25_to_28->totalcurrent, esc_telemetry_25_to_28->rpm, esc_telemetry_25_to_28->count);
+}
+
+/**
+ * @brief Encode a esc_telemetry_25_to_28 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 esc_telemetry_25_to_28 C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_25_to_28_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_esc_telemetry_25_to_28_t* esc_telemetry_25_to_28)
+{
+ return mavlink_msg_esc_telemetry_25_to_28_pack_status(system_id, component_id, _status, msg, esc_telemetry_25_to_28->temperature, esc_telemetry_25_to_28->voltage, esc_telemetry_25_to_28->current, esc_telemetry_25_to_28->totalcurrent, esc_telemetry_25_to_28->rpm, esc_telemetry_25_to_28->count);
+}
+
+/**
+ * @brief Send a esc_telemetry_25_to_28 message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param temperature [degC] Temperature.
+ * @param voltage [cV] Voltage.
+ * @param current [cA] Current.
+ * @param totalcurrent [mAh] Total current.
+ * @param rpm [rpm] RPM (eRPM).
+ * @param count count of telemetry packets received (wraps at 65535).
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_esc_telemetry_25_to_28_send(mavlink_channel_t chan, const uint8_t *temperature, const uint16_t *voltage, const uint16_t *current, const uint16_t *totalcurrent, const uint16_t *rpm, const uint16_t *count)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_ESC_TELEMETRY_25_TO_28_LEN];
+
+ _mav_put_uint16_t_array(buf, 0, voltage, 4);
+ _mav_put_uint16_t_array(buf, 8, current, 4);
+ _mav_put_uint16_t_array(buf, 16, totalcurrent, 4);
+ _mav_put_uint16_t_array(buf, 24, rpm, 4);
+ _mav_put_uint16_t_array(buf, 32, count, 4);
+ _mav_put_uint8_t_array(buf, 40, temperature, 4);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESC_TELEMETRY_25_TO_28, buf, MAVLINK_MSG_ID_ESC_TELEMETRY_25_TO_28_MIN_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_25_TO_28_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_25_TO_28_CRC);
+#else
+ mavlink_esc_telemetry_25_to_28_t packet;
+
+ mav_array_assign_uint16_t(packet.voltage, voltage, 4);
+ mav_array_assign_uint16_t(packet.current, current, 4);
+ mav_array_assign_uint16_t(packet.totalcurrent, totalcurrent, 4);
+ mav_array_assign_uint16_t(packet.rpm, rpm, 4);
+ mav_array_assign_uint16_t(packet.count, count, 4);
+ mav_array_assign_uint8_t(packet.temperature, temperature, 4);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESC_TELEMETRY_25_TO_28, (const char *)&packet, MAVLINK_MSG_ID_ESC_TELEMETRY_25_TO_28_MIN_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_25_TO_28_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_25_TO_28_CRC);
+#endif
+}
+
+/**
+ * @brief Send a esc_telemetry_25_to_28 message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_esc_telemetry_25_to_28_send_struct(mavlink_channel_t chan, const mavlink_esc_telemetry_25_to_28_t* esc_telemetry_25_to_28)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_esc_telemetry_25_to_28_send(chan, esc_telemetry_25_to_28->temperature, esc_telemetry_25_to_28->voltage, esc_telemetry_25_to_28->current, esc_telemetry_25_to_28->totalcurrent, esc_telemetry_25_to_28->rpm, esc_telemetry_25_to_28->count);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESC_TELEMETRY_25_TO_28, (const char *)esc_telemetry_25_to_28, MAVLINK_MSG_ID_ESC_TELEMETRY_25_TO_28_MIN_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_25_TO_28_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_25_TO_28_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_ESC_TELEMETRY_25_TO_28_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_esc_telemetry_25_to_28_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, const uint8_t *temperature, const uint16_t *voltage, const uint16_t *current, const uint16_t *totalcurrent, const uint16_t *rpm, const uint16_t *count)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+
+ _mav_put_uint16_t_array(buf, 0, voltage, 4);
+ _mav_put_uint16_t_array(buf, 8, current, 4);
+ _mav_put_uint16_t_array(buf, 16, totalcurrent, 4);
+ _mav_put_uint16_t_array(buf, 24, rpm, 4);
+ _mav_put_uint16_t_array(buf, 32, count, 4);
+ _mav_put_uint8_t_array(buf, 40, temperature, 4);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESC_TELEMETRY_25_TO_28, buf, MAVLINK_MSG_ID_ESC_TELEMETRY_25_TO_28_MIN_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_25_TO_28_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_25_TO_28_CRC);
+#else
+ mavlink_esc_telemetry_25_to_28_t *packet = (mavlink_esc_telemetry_25_to_28_t *)msgbuf;
+
+ mav_array_assign_uint16_t(packet->voltage, voltage, 4);
+ mav_array_assign_uint16_t(packet->current, current, 4);
+ mav_array_assign_uint16_t(packet->totalcurrent, totalcurrent, 4);
+ mav_array_assign_uint16_t(packet->rpm, rpm, 4);
+ mav_array_assign_uint16_t(packet->count, count, 4);
+ mav_array_assign_uint8_t(packet->temperature, temperature, 4);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESC_TELEMETRY_25_TO_28, (const char *)packet, MAVLINK_MSG_ID_ESC_TELEMETRY_25_TO_28_MIN_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_25_TO_28_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_25_TO_28_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE ESC_TELEMETRY_25_TO_28 UNPACKING
+
+
+/**
+ * @brief Get field temperature from esc_telemetry_25_to_28 message
+ *
+ * @return [degC] Temperature.
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_25_to_28_get_temperature(const mavlink_message_t* msg, uint8_t *temperature)
+{
+ return _MAV_RETURN_uint8_t_array(msg, temperature, 4, 40);
+}
+
+/**
+ * @brief Get field voltage from esc_telemetry_25_to_28 message
+ *
+ * @return [cV] Voltage.
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_25_to_28_get_voltage(const mavlink_message_t* msg, uint16_t *voltage)
+{
+ return _MAV_RETURN_uint16_t_array(msg, voltage, 4, 0);
+}
+
+/**
+ * @brief Get field current from esc_telemetry_25_to_28 message
+ *
+ * @return [cA] Current.
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_25_to_28_get_current(const mavlink_message_t* msg, uint16_t *current)
+{
+ return _MAV_RETURN_uint16_t_array(msg, current, 4, 8);
+}
+
+/**
+ * @brief Get field totalcurrent from esc_telemetry_25_to_28 message
+ *
+ * @return [mAh] Total current.
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_25_to_28_get_totalcurrent(const mavlink_message_t* msg, uint16_t *totalcurrent)
+{
+ return _MAV_RETURN_uint16_t_array(msg, totalcurrent, 4, 16);
+}
+
+/**
+ * @brief Get field rpm from esc_telemetry_25_to_28 message
+ *
+ * @return [rpm] RPM (eRPM).
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_25_to_28_get_rpm(const mavlink_message_t* msg, uint16_t *rpm)
+{
+ return _MAV_RETURN_uint16_t_array(msg, rpm, 4, 24);
+}
+
+/**
+ * @brief Get field count from esc_telemetry_25_to_28 message
+ *
+ * @return count of telemetry packets received (wraps at 65535).
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_25_to_28_get_count(const mavlink_message_t* msg, uint16_t *count)
+{
+ return _MAV_RETURN_uint16_t_array(msg, count, 4, 32);
+}
+
+/**
+ * @brief Decode a esc_telemetry_25_to_28 message into a struct
+ *
+ * @param msg The message to decode
+ * @param esc_telemetry_25_to_28 C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_esc_telemetry_25_to_28_decode(const mavlink_message_t* msg, mavlink_esc_telemetry_25_to_28_t* esc_telemetry_25_to_28)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_esc_telemetry_25_to_28_get_voltage(msg, esc_telemetry_25_to_28->voltage);
+ mavlink_msg_esc_telemetry_25_to_28_get_current(msg, esc_telemetry_25_to_28->current);
+ mavlink_msg_esc_telemetry_25_to_28_get_totalcurrent(msg, esc_telemetry_25_to_28->totalcurrent);
+ mavlink_msg_esc_telemetry_25_to_28_get_rpm(msg, esc_telemetry_25_to_28->rpm);
+ mavlink_msg_esc_telemetry_25_to_28_get_count(msg, esc_telemetry_25_to_28->count);
+ mavlink_msg_esc_telemetry_25_to_28_get_temperature(msg, esc_telemetry_25_to_28->temperature);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_ESC_TELEMETRY_25_TO_28_LEN? msg->len : MAVLINK_MSG_ID_ESC_TELEMETRY_25_TO_28_LEN;
+ memset(esc_telemetry_25_to_28, 0, MAVLINK_MSG_ID_ESC_TELEMETRY_25_TO_28_LEN);
+ memcpy(esc_telemetry_25_to_28, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/ardupilotmega/mavlink_msg_esc_telemetry_29_to_32.h b/lib/main/MAVLink/ardupilotmega/mavlink_msg_esc_telemetry_29_to_32.h
new file mode 100644
index 00000000000..178c6f4d0d1
--- /dev/null
+++ b/lib/main/MAVLink/ardupilotmega/mavlink_msg_esc_telemetry_29_to_32.h
@@ -0,0 +1,405 @@
+#pragma once
+// MESSAGE ESC_TELEMETRY_29_TO_32 PACKING
+
+#define MAVLINK_MSG_ID_ESC_TELEMETRY_29_TO_32 11044
+
+
+typedef struct __mavlink_esc_telemetry_29_to_32_t {
+ uint16_t voltage[4]; /*< [cV] Voltage.*/
+ uint16_t current[4]; /*< [cA] Current.*/
+ uint16_t totalcurrent[4]; /*< [mAh] Total current.*/
+ uint16_t rpm[4]; /*< [rpm] RPM (eRPM).*/
+ uint16_t count[4]; /*< count of telemetry packets received (wraps at 65535).*/
+ uint8_t temperature[4]; /*< [degC] Temperature.*/
+} mavlink_esc_telemetry_29_to_32_t;
+
+#define MAVLINK_MSG_ID_ESC_TELEMETRY_29_TO_32_LEN 44
+#define MAVLINK_MSG_ID_ESC_TELEMETRY_29_TO_32_MIN_LEN 44
+#define MAVLINK_MSG_ID_11044_LEN 44
+#define MAVLINK_MSG_ID_11044_MIN_LEN 44
+
+#define MAVLINK_MSG_ID_ESC_TELEMETRY_29_TO_32_CRC 189
+#define MAVLINK_MSG_ID_11044_CRC 189
+
+#define MAVLINK_MSG_ESC_TELEMETRY_29_TO_32_FIELD_VOLTAGE_LEN 4
+#define MAVLINK_MSG_ESC_TELEMETRY_29_TO_32_FIELD_CURRENT_LEN 4
+#define MAVLINK_MSG_ESC_TELEMETRY_29_TO_32_FIELD_TOTALCURRENT_LEN 4
+#define MAVLINK_MSG_ESC_TELEMETRY_29_TO_32_FIELD_RPM_LEN 4
+#define MAVLINK_MSG_ESC_TELEMETRY_29_TO_32_FIELD_COUNT_LEN 4
+#define MAVLINK_MSG_ESC_TELEMETRY_29_TO_32_FIELD_TEMPERATURE_LEN 4
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_ESC_TELEMETRY_29_TO_32 { \
+ 11044, \
+ "ESC_TELEMETRY_29_TO_32", \
+ 6, \
+ { { "temperature", NULL, MAVLINK_TYPE_UINT8_T, 4, 40, offsetof(mavlink_esc_telemetry_29_to_32_t, temperature) }, \
+ { "voltage", NULL, MAVLINK_TYPE_UINT16_T, 4, 0, offsetof(mavlink_esc_telemetry_29_to_32_t, voltage) }, \
+ { "current", NULL, MAVLINK_TYPE_UINT16_T, 4, 8, offsetof(mavlink_esc_telemetry_29_to_32_t, current) }, \
+ { "totalcurrent", NULL, MAVLINK_TYPE_UINT16_T, 4, 16, offsetof(mavlink_esc_telemetry_29_to_32_t, totalcurrent) }, \
+ { "rpm", NULL, MAVLINK_TYPE_UINT16_T, 4, 24, offsetof(mavlink_esc_telemetry_29_to_32_t, rpm) }, \
+ { "count", NULL, MAVLINK_TYPE_UINT16_T, 4, 32, offsetof(mavlink_esc_telemetry_29_to_32_t, count) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_ESC_TELEMETRY_29_TO_32 { \
+ "ESC_TELEMETRY_29_TO_32", \
+ 6, \
+ { { "temperature", NULL, MAVLINK_TYPE_UINT8_T, 4, 40, offsetof(mavlink_esc_telemetry_29_to_32_t, temperature) }, \
+ { "voltage", NULL, MAVLINK_TYPE_UINT16_T, 4, 0, offsetof(mavlink_esc_telemetry_29_to_32_t, voltage) }, \
+ { "current", NULL, MAVLINK_TYPE_UINT16_T, 4, 8, offsetof(mavlink_esc_telemetry_29_to_32_t, current) }, \
+ { "totalcurrent", NULL, MAVLINK_TYPE_UINT16_T, 4, 16, offsetof(mavlink_esc_telemetry_29_to_32_t, totalcurrent) }, \
+ { "rpm", NULL, MAVLINK_TYPE_UINT16_T, 4, 24, offsetof(mavlink_esc_telemetry_29_to_32_t, rpm) }, \
+ { "count", NULL, MAVLINK_TYPE_UINT16_T, 4, 32, offsetof(mavlink_esc_telemetry_29_to_32_t, count) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a esc_telemetry_29_to_32 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 temperature [degC] Temperature.
+ * @param voltage [cV] Voltage.
+ * @param current [cA] Current.
+ * @param totalcurrent [mAh] Total current.
+ * @param rpm [rpm] RPM (eRPM).
+ * @param count count of telemetry packets received (wraps at 65535).
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_29_to_32_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ const uint8_t *temperature, const uint16_t *voltage, const uint16_t *current, const uint16_t *totalcurrent, const uint16_t *rpm, const uint16_t *count)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_ESC_TELEMETRY_29_TO_32_LEN];
+
+ _mav_put_uint16_t_array(buf, 0, voltage, 4);
+ _mav_put_uint16_t_array(buf, 8, current, 4);
+ _mav_put_uint16_t_array(buf, 16, totalcurrent, 4);
+ _mav_put_uint16_t_array(buf, 24, rpm, 4);
+ _mav_put_uint16_t_array(buf, 32, count, 4);
+ _mav_put_uint8_t_array(buf, 40, temperature, 4);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ESC_TELEMETRY_29_TO_32_LEN);
+#else
+ mavlink_esc_telemetry_29_to_32_t packet;
+
+ mav_array_assign_uint16_t(packet.voltage, voltage, 4);
+ mav_array_assign_uint16_t(packet.current, current, 4);
+ mav_array_assign_uint16_t(packet.totalcurrent, totalcurrent, 4);
+ mav_array_assign_uint16_t(packet.rpm, rpm, 4);
+ mav_array_assign_uint16_t(packet.count, count, 4);
+ mav_array_assign_uint8_t(packet.temperature, temperature, 4);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ESC_TELEMETRY_29_TO_32_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_ESC_TELEMETRY_29_TO_32;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ESC_TELEMETRY_29_TO_32_MIN_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_29_TO_32_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_29_TO_32_CRC);
+}
+
+/**
+ * @brief Pack a esc_telemetry_29_to_32 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 temperature [degC] Temperature.
+ * @param voltage [cV] Voltage.
+ * @param current [cA] Current.
+ * @param totalcurrent [mAh] Total current.
+ * @param rpm [rpm] RPM (eRPM).
+ * @param count count of telemetry packets received (wraps at 65535).
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_29_to_32_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ const uint8_t *temperature, const uint16_t *voltage, const uint16_t *current, const uint16_t *totalcurrent, const uint16_t *rpm, const uint16_t *count)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_ESC_TELEMETRY_29_TO_32_LEN];
+
+ _mav_put_uint16_t_array(buf, 0, voltage, 4);
+ _mav_put_uint16_t_array(buf, 8, current, 4);
+ _mav_put_uint16_t_array(buf, 16, totalcurrent, 4);
+ _mav_put_uint16_t_array(buf, 24, rpm, 4);
+ _mav_put_uint16_t_array(buf, 32, count, 4);
+ _mav_put_uint8_t_array(buf, 40, temperature, 4);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ESC_TELEMETRY_29_TO_32_LEN);
+#else
+ mavlink_esc_telemetry_29_to_32_t packet;
+
+ mav_array_memcpy(packet.voltage, voltage, sizeof(uint16_t)*4);
+ mav_array_memcpy(packet.current, current, sizeof(uint16_t)*4);
+ mav_array_memcpy(packet.totalcurrent, totalcurrent, sizeof(uint16_t)*4);
+ mav_array_memcpy(packet.rpm, rpm, sizeof(uint16_t)*4);
+ mav_array_memcpy(packet.count, count, sizeof(uint16_t)*4);
+ mav_array_memcpy(packet.temperature, temperature, sizeof(uint8_t)*4);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ESC_TELEMETRY_29_TO_32_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_ESC_TELEMETRY_29_TO_32;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_ESC_TELEMETRY_29_TO_32_MIN_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_29_TO_32_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_29_TO_32_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_ESC_TELEMETRY_29_TO_32_MIN_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_29_TO_32_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a esc_telemetry_29_to_32 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 temperature [degC] Temperature.
+ * @param voltage [cV] Voltage.
+ * @param current [cA] Current.
+ * @param totalcurrent [mAh] Total current.
+ * @param rpm [rpm] RPM (eRPM).
+ * @param count count of telemetry packets received (wraps at 65535).
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_29_to_32_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ const uint8_t *temperature,const uint16_t *voltage,const uint16_t *current,const uint16_t *totalcurrent,const uint16_t *rpm,const uint16_t *count)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_ESC_TELEMETRY_29_TO_32_LEN];
+
+ _mav_put_uint16_t_array(buf, 0, voltage, 4);
+ _mav_put_uint16_t_array(buf, 8, current, 4);
+ _mav_put_uint16_t_array(buf, 16, totalcurrent, 4);
+ _mav_put_uint16_t_array(buf, 24, rpm, 4);
+ _mav_put_uint16_t_array(buf, 32, count, 4);
+ _mav_put_uint8_t_array(buf, 40, temperature, 4);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ESC_TELEMETRY_29_TO_32_LEN);
+#else
+ mavlink_esc_telemetry_29_to_32_t packet;
+
+ mav_array_assign_uint16_t(packet.voltage, voltage, 4);
+ mav_array_assign_uint16_t(packet.current, current, 4);
+ mav_array_assign_uint16_t(packet.totalcurrent, totalcurrent, 4);
+ mav_array_assign_uint16_t(packet.rpm, rpm, 4);
+ mav_array_assign_uint16_t(packet.count, count, 4);
+ mav_array_assign_uint8_t(packet.temperature, temperature, 4);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ESC_TELEMETRY_29_TO_32_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_ESC_TELEMETRY_29_TO_32;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ESC_TELEMETRY_29_TO_32_MIN_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_29_TO_32_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_29_TO_32_CRC);
+}
+
+/**
+ * @brief Encode a esc_telemetry_29_to_32 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 esc_telemetry_29_to_32 C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_29_to_32_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_esc_telemetry_29_to_32_t* esc_telemetry_29_to_32)
+{
+ return mavlink_msg_esc_telemetry_29_to_32_pack(system_id, component_id, msg, esc_telemetry_29_to_32->temperature, esc_telemetry_29_to_32->voltage, esc_telemetry_29_to_32->current, esc_telemetry_29_to_32->totalcurrent, esc_telemetry_29_to_32->rpm, esc_telemetry_29_to_32->count);
+}
+
+/**
+ * @brief Encode a esc_telemetry_29_to_32 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 esc_telemetry_29_to_32 C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_29_to_32_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_esc_telemetry_29_to_32_t* esc_telemetry_29_to_32)
+{
+ return mavlink_msg_esc_telemetry_29_to_32_pack_chan(system_id, component_id, chan, msg, esc_telemetry_29_to_32->temperature, esc_telemetry_29_to_32->voltage, esc_telemetry_29_to_32->current, esc_telemetry_29_to_32->totalcurrent, esc_telemetry_29_to_32->rpm, esc_telemetry_29_to_32->count);
+}
+
+/**
+ * @brief Encode a esc_telemetry_29_to_32 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 esc_telemetry_29_to_32 C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_29_to_32_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_esc_telemetry_29_to_32_t* esc_telemetry_29_to_32)
+{
+ return mavlink_msg_esc_telemetry_29_to_32_pack_status(system_id, component_id, _status, msg, esc_telemetry_29_to_32->temperature, esc_telemetry_29_to_32->voltage, esc_telemetry_29_to_32->current, esc_telemetry_29_to_32->totalcurrent, esc_telemetry_29_to_32->rpm, esc_telemetry_29_to_32->count);
+}
+
+/**
+ * @brief Send a esc_telemetry_29_to_32 message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param temperature [degC] Temperature.
+ * @param voltage [cV] Voltage.
+ * @param current [cA] Current.
+ * @param totalcurrent [mAh] Total current.
+ * @param rpm [rpm] RPM (eRPM).
+ * @param count count of telemetry packets received (wraps at 65535).
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_esc_telemetry_29_to_32_send(mavlink_channel_t chan, const uint8_t *temperature, const uint16_t *voltage, const uint16_t *current, const uint16_t *totalcurrent, const uint16_t *rpm, const uint16_t *count)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_ESC_TELEMETRY_29_TO_32_LEN];
+
+ _mav_put_uint16_t_array(buf, 0, voltage, 4);
+ _mav_put_uint16_t_array(buf, 8, current, 4);
+ _mav_put_uint16_t_array(buf, 16, totalcurrent, 4);
+ _mav_put_uint16_t_array(buf, 24, rpm, 4);
+ _mav_put_uint16_t_array(buf, 32, count, 4);
+ _mav_put_uint8_t_array(buf, 40, temperature, 4);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESC_TELEMETRY_29_TO_32, buf, MAVLINK_MSG_ID_ESC_TELEMETRY_29_TO_32_MIN_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_29_TO_32_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_29_TO_32_CRC);
+#else
+ mavlink_esc_telemetry_29_to_32_t packet;
+
+ mav_array_assign_uint16_t(packet.voltage, voltage, 4);
+ mav_array_assign_uint16_t(packet.current, current, 4);
+ mav_array_assign_uint16_t(packet.totalcurrent, totalcurrent, 4);
+ mav_array_assign_uint16_t(packet.rpm, rpm, 4);
+ mav_array_assign_uint16_t(packet.count, count, 4);
+ mav_array_assign_uint8_t(packet.temperature, temperature, 4);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESC_TELEMETRY_29_TO_32, (const char *)&packet, MAVLINK_MSG_ID_ESC_TELEMETRY_29_TO_32_MIN_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_29_TO_32_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_29_TO_32_CRC);
+#endif
+}
+
+/**
+ * @brief Send a esc_telemetry_29_to_32 message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_esc_telemetry_29_to_32_send_struct(mavlink_channel_t chan, const mavlink_esc_telemetry_29_to_32_t* esc_telemetry_29_to_32)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_esc_telemetry_29_to_32_send(chan, esc_telemetry_29_to_32->temperature, esc_telemetry_29_to_32->voltage, esc_telemetry_29_to_32->current, esc_telemetry_29_to_32->totalcurrent, esc_telemetry_29_to_32->rpm, esc_telemetry_29_to_32->count);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESC_TELEMETRY_29_TO_32, (const char *)esc_telemetry_29_to_32, MAVLINK_MSG_ID_ESC_TELEMETRY_29_TO_32_MIN_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_29_TO_32_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_29_TO_32_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_ESC_TELEMETRY_29_TO_32_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_esc_telemetry_29_to_32_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, const uint8_t *temperature, const uint16_t *voltage, const uint16_t *current, const uint16_t *totalcurrent, const uint16_t *rpm, const uint16_t *count)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+
+ _mav_put_uint16_t_array(buf, 0, voltage, 4);
+ _mav_put_uint16_t_array(buf, 8, current, 4);
+ _mav_put_uint16_t_array(buf, 16, totalcurrent, 4);
+ _mav_put_uint16_t_array(buf, 24, rpm, 4);
+ _mav_put_uint16_t_array(buf, 32, count, 4);
+ _mav_put_uint8_t_array(buf, 40, temperature, 4);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESC_TELEMETRY_29_TO_32, buf, MAVLINK_MSG_ID_ESC_TELEMETRY_29_TO_32_MIN_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_29_TO_32_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_29_TO_32_CRC);
+#else
+ mavlink_esc_telemetry_29_to_32_t *packet = (mavlink_esc_telemetry_29_to_32_t *)msgbuf;
+
+ mav_array_assign_uint16_t(packet->voltage, voltage, 4);
+ mav_array_assign_uint16_t(packet->current, current, 4);
+ mav_array_assign_uint16_t(packet->totalcurrent, totalcurrent, 4);
+ mav_array_assign_uint16_t(packet->rpm, rpm, 4);
+ mav_array_assign_uint16_t(packet->count, count, 4);
+ mav_array_assign_uint8_t(packet->temperature, temperature, 4);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESC_TELEMETRY_29_TO_32, (const char *)packet, MAVLINK_MSG_ID_ESC_TELEMETRY_29_TO_32_MIN_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_29_TO_32_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_29_TO_32_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE ESC_TELEMETRY_29_TO_32 UNPACKING
+
+
+/**
+ * @brief Get field temperature from esc_telemetry_29_to_32 message
+ *
+ * @return [degC] Temperature.
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_29_to_32_get_temperature(const mavlink_message_t* msg, uint8_t *temperature)
+{
+ return _MAV_RETURN_uint8_t_array(msg, temperature, 4, 40);
+}
+
+/**
+ * @brief Get field voltage from esc_telemetry_29_to_32 message
+ *
+ * @return [cV] Voltage.
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_29_to_32_get_voltage(const mavlink_message_t* msg, uint16_t *voltage)
+{
+ return _MAV_RETURN_uint16_t_array(msg, voltage, 4, 0);
+}
+
+/**
+ * @brief Get field current from esc_telemetry_29_to_32 message
+ *
+ * @return [cA] Current.
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_29_to_32_get_current(const mavlink_message_t* msg, uint16_t *current)
+{
+ return _MAV_RETURN_uint16_t_array(msg, current, 4, 8);
+}
+
+/**
+ * @brief Get field totalcurrent from esc_telemetry_29_to_32 message
+ *
+ * @return [mAh] Total current.
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_29_to_32_get_totalcurrent(const mavlink_message_t* msg, uint16_t *totalcurrent)
+{
+ return _MAV_RETURN_uint16_t_array(msg, totalcurrent, 4, 16);
+}
+
+/**
+ * @brief Get field rpm from esc_telemetry_29_to_32 message
+ *
+ * @return [rpm] RPM (eRPM).
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_29_to_32_get_rpm(const mavlink_message_t* msg, uint16_t *rpm)
+{
+ return _MAV_RETURN_uint16_t_array(msg, rpm, 4, 24);
+}
+
+/**
+ * @brief Get field count from esc_telemetry_29_to_32 message
+ *
+ * @return count of telemetry packets received (wraps at 65535).
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_29_to_32_get_count(const mavlink_message_t* msg, uint16_t *count)
+{
+ return _MAV_RETURN_uint16_t_array(msg, count, 4, 32);
+}
+
+/**
+ * @brief Decode a esc_telemetry_29_to_32 message into a struct
+ *
+ * @param msg The message to decode
+ * @param esc_telemetry_29_to_32 C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_esc_telemetry_29_to_32_decode(const mavlink_message_t* msg, mavlink_esc_telemetry_29_to_32_t* esc_telemetry_29_to_32)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_esc_telemetry_29_to_32_get_voltage(msg, esc_telemetry_29_to_32->voltage);
+ mavlink_msg_esc_telemetry_29_to_32_get_current(msg, esc_telemetry_29_to_32->current);
+ mavlink_msg_esc_telemetry_29_to_32_get_totalcurrent(msg, esc_telemetry_29_to_32->totalcurrent);
+ mavlink_msg_esc_telemetry_29_to_32_get_rpm(msg, esc_telemetry_29_to_32->rpm);
+ mavlink_msg_esc_telemetry_29_to_32_get_count(msg, esc_telemetry_29_to_32->count);
+ mavlink_msg_esc_telemetry_29_to_32_get_temperature(msg, esc_telemetry_29_to_32->temperature);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_ESC_TELEMETRY_29_TO_32_LEN? msg->len : MAVLINK_MSG_ID_ESC_TELEMETRY_29_TO_32_LEN;
+ memset(esc_telemetry_29_to_32, 0, MAVLINK_MSG_ID_ESC_TELEMETRY_29_TO_32_LEN);
+ memcpy(esc_telemetry_29_to_32, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/ardupilotmega/mavlink_msg_esc_telemetry_5_to_8.h b/lib/main/MAVLink/ardupilotmega/mavlink_msg_esc_telemetry_5_to_8.h
new file mode 100644
index 00000000000..343955b59b4
--- /dev/null
+++ b/lib/main/MAVLink/ardupilotmega/mavlink_msg_esc_telemetry_5_to_8.h
@@ -0,0 +1,405 @@
+#pragma once
+// MESSAGE ESC_TELEMETRY_5_TO_8 PACKING
+
+#define MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8 11031
+
+
+typedef struct __mavlink_esc_telemetry_5_to_8_t {
+ uint16_t voltage[4]; /*< [cV] Voltage.*/
+ uint16_t current[4]; /*< [cA] Current.*/
+ uint16_t totalcurrent[4]; /*< [mAh] Total current.*/
+ uint16_t rpm[4]; /*< [rpm] RPM (eRPM).*/
+ uint16_t count[4]; /*< count of telemetry packets received (wraps at 65535).*/
+ uint8_t temperature[4]; /*< [degC] Temperature.*/
+} mavlink_esc_telemetry_5_to_8_t;
+
+#define MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8_LEN 44
+#define MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8_MIN_LEN 44
+#define MAVLINK_MSG_ID_11031_LEN 44
+#define MAVLINK_MSG_ID_11031_MIN_LEN 44
+
+#define MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8_CRC 133
+#define MAVLINK_MSG_ID_11031_CRC 133
+
+#define MAVLINK_MSG_ESC_TELEMETRY_5_TO_8_FIELD_VOLTAGE_LEN 4
+#define MAVLINK_MSG_ESC_TELEMETRY_5_TO_8_FIELD_CURRENT_LEN 4
+#define MAVLINK_MSG_ESC_TELEMETRY_5_TO_8_FIELD_TOTALCURRENT_LEN 4
+#define MAVLINK_MSG_ESC_TELEMETRY_5_TO_8_FIELD_RPM_LEN 4
+#define MAVLINK_MSG_ESC_TELEMETRY_5_TO_8_FIELD_COUNT_LEN 4
+#define MAVLINK_MSG_ESC_TELEMETRY_5_TO_8_FIELD_TEMPERATURE_LEN 4
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_ESC_TELEMETRY_5_TO_8 { \
+ 11031, \
+ "ESC_TELEMETRY_5_TO_8", \
+ 6, \
+ { { "temperature", NULL, MAVLINK_TYPE_UINT8_T, 4, 40, offsetof(mavlink_esc_telemetry_5_to_8_t, temperature) }, \
+ { "voltage", NULL, MAVLINK_TYPE_UINT16_T, 4, 0, offsetof(mavlink_esc_telemetry_5_to_8_t, voltage) }, \
+ { "current", NULL, MAVLINK_TYPE_UINT16_T, 4, 8, offsetof(mavlink_esc_telemetry_5_to_8_t, current) }, \
+ { "totalcurrent", NULL, MAVLINK_TYPE_UINT16_T, 4, 16, offsetof(mavlink_esc_telemetry_5_to_8_t, totalcurrent) }, \
+ { "rpm", NULL, MAVLINK_TYPE_UINT16_T, 4, 24, offsetof(mavlink_esc_telemetry_5_to_8_t, rpm) }, \
+ { "count", NULL, MAVLINK_TYPE_UINT16_T, 4, 32, offsetof(mavlink_esc_telemetry_5_to_8_t, count) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_ESC_TELEMETRY_5_TO_8 { \
+ "ESC_TELEMETRY_5_TO_8", \
+ 6, \
+ { { "temperature", NULL, MAVLINK_TYPE_UINT8_T, 4, 40, offsetof(mavlink_esc_telemetry_5_to_8_t, temperature) }, \
+ { "voltage", NULL, MAVLINK_TYPE_UINT16_T, 4, 0, offsetof(mavlink_esc_telemetry_5_to_8_t, voltage) }, \
+ { "current", NULL, MAVLINK_TYPE_UINT16_T, 4, 8, offsetof(mavlink_esc_telemetry_5_to_8_t, current) }, \
+ { "totalcurrent", NULL, MAVLINK_TYPE_UINT16_T, 4, 16, offsetof(mavlink_esc_telemetry_5_to_8_t, totalcurrent) }, \
+ { "rpm", NULL, MAVLINK_TYPE_UINT16_T, 4, 24, offsetof(mavlink_esc_telemetry_5_to_8_t, rpm) }, \
+ { "count", NULL, MAVLINK_TYPE_UINT16_T, 4, 32, offsetof(mavlink_esc_telemetry_5_to_8_t, count) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a esc_telemetry_5_to_8 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 temperature [degC] Temperature.
+ * @param voltage [cV] Voltage.
+ * @param current [cA] Current.
+ * @param totalcurrent [mAh] Total current.
+ * @param rpm [rpm] RPM (eRPM).
+ * @param count count of telemetry packets received (wraps at 65535).
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_5_to_8_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ const uint8_t *temperature, const uint16_t *voltage, const uint16_t *current, const uint16_t *totalcurrent, const uint16_t *rpm, const uint16_t *count)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8_LEN];
+
+ _mav_put_uint16_t_array(buf, 0, voltage, 4);
+ _mav_put_uint16_t_array(buf, 8, current, 4);
+ _mav_put_uint16_t_array(buf, 16, totalcurrent, 4);
+ _mav_put_uint16_t_array(buf, 24, rpm, 4);
+ _mav_put_uint16_t_array(buf, 32, count, 4);
+ _mav_put_uint8_t_array(buf, 40, temperature, 4);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8_LEN);
+#else
+ mavlink_esc_telemetry_5_to_8_t packet;
+
+ mav_array_assign_uint16_t(packet.voltage, voltage, 4);
+ mav_array_assign_uint16_t(packet.current, current, 4);
+ mav_array_assign_uint16_t(packet.totalcurrent, totalcurrent, 4);
+ mav_array_assign_uint16_t(packet.rpm, rpm, 4);
+ mav_array_assign_uint16_t(packet.count, count, 4);
+ mav_array_assign_uint8_t(packet.temperature, temperature, 4);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8_MIN_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8_CRC);
+}
+
+/**
+ * @brief Pack a esc_telemetry_5_to_8 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 temperature [degC] Temperature.
+ * @param voltage [cV] Voltage.
+ * @param current [cA] Current.
+ * @param totalcurrent [mAh] Total current.
+ * @param rpm [rpm] RPM (eRPM).
+ * @param count count of telemetry packets received (wraps at 65535).
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_5_to_8_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ const uint8_t *temperature, const uint16_t *voltage, const uint16_t *current, const uint16_t *totalcurrent, const uint16_t *rpm, const uint16_t *count)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8_LEN];
+
+ _mav_put_uint16_t_array(buf, 0, voltage, 4);
+ _mav_put_uint16_t_array(buf, 8, current, 4);
+ _mav_put_uint16_t_array(buf, 16, totalcurrent, 4);
+ _mav_put_uint16_t_array(buf, 24, rpm, 4);
+ _mav_put_uint16_t_array(buf, 32, count, 4);
+ _mav_put_uint8_t_array(buf, 40, temperature, 4);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8_LEN);
+#else
+ mavlink_esc_telemetry_5_to_8_t packet;
+
+ mav_array_memcpy(packet.voltage, voltage, sizeof(uint16_t)*4);
+ mav_array_memcpy(packet.current, current, sizeof(uint16_t)*4);
+ mav_array_memcpy(packet.totalcurrent, totalcurrent, sizeof(uint16_t)*4);
+ mav_array_memcpy(packet.rpm, rpm, sizeof(uint16_t)*4);
+ mav_array_memcpy(packet.count, count, sizeof(uint16_t)*4);
+ mav_array_memcpy(packet.temperature, temperature, sizeof(uint8_t)*4);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8_MIN_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8_MIN_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a esc_telemetry_5_to_8 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 temperature [degC] Temperature.
+ * @param voltage [cV] Voltage.
+ * @param current [cA] Current.
+ * @param totalcurrent [mAh] Total current.
+ * @param rpm [rpm] RPM (eRPM).
+ * @param count count of telemetry packets received (wraps at 65535).
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_5_to_8_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ const uint8_t *temperature,const uint16_t *voltage,const uint16_t *current,const uint16_t *totalcurrent,const uint16_t *rpm,const uint16_t *count)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8_LEN];
+
+ _mav_put_uint16_t_array(buf, 0, voltage, 4);
+ _mav_put_uint16_t_array(buf, 8, current, 4);
+ _mav_put_uint16_t_array(buf, 16, totalcurrent, 4);
+ _mav_put_uint16_t_array(buf, 24, rpm, 4);
+ _mav_put_uint16_t_array(buf, 32, count, 4);
+ _mav_put_uint8_t_array(buf, 40, temperature, 4);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8_LEN);
+#else
+ mavlink_esc_telemetry_5_to_8_t packet;
+
+ mav_array_assign_uint16_t(packet.voltage, voltage, 4);
+ mav_array_assign_uint16_t(packet.current, current, 4);
+ mav_array_assign_uint16_t(packet.totalcurrent, totalcurrent, 4);
+ mav_array_assign_uint16_t(packet.rpm, rpm, 4);
+ mav_array_assign_uint16_t(packet.count, count, 4);
+ mav_array_assign_uint8_t(packet.temperature, temperature, 4);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8_MIN_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8_CRC);
+}
+
+/**
+ * @brief Encode a esc_telemetry_5_to_8 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 esc_telemetry_5_to_8 C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_5_to_8_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_esc_telemetry_5_to_8_t* esc_telemetry_5_to_8)
+{
+ return mavlink_msg_esc_telemetry_5_to_8_pack(system_id, component_id, msg, esc_telemetry_5_to_8->temperature, esc_telemetry_5_to_8->voltage, esc_telemetry_5_to_8->current, esc_telemetry_5_to_8->totalcurrent, esc_telemetry_5_to_8->rpm, esc_telemetry_5_to_8->count);
+}
+
+/**
+ * @brief Encode a esc_telemetry_5_to_8 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 esc_telemetry_5_to_8 C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_5_to_8_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_esc_telemetry_5_to_8_t* esc_telemetry_5_to_8)
+{
+ return mavlink_msg_esc_telemetry_5_to_8_pack_chan(system_id, component_id, chan, msg, esc_telemetry_5_to_8->temperature, esc_telemetry_5_to_8->voltage, esc_telemetry_5_to_8->current, esc_telemetry_5_to_8->totalcurrent, esc_telemetry_5_to_8->rpm, esc_telemetry_5_to_8->count);
+}
+
+/**
+ * @brief Encode a esc_telemetry_5_to_8 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 esc_telemetry_5_to_8 C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_5_to_8_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_esc_telemetry_5_to_8_t* esc_telemetry_5_to_8)
+{
+ return mavlink_msg_esc_telemetry_5_to_8_pack_status(system_id, component_id, _status, msg, esc_telemetry_5_to_8->temperature, esc_telemetry_5_to_8->voltage, esc_telemetry_5_to_8->current, esc_telemetry_5_to_8->totalcurrent, esc_telemetry_5_to_8->rpm, esc_telemetry_5_to_8->count);
+}
+
+/**
+ * @brief Send a esc_telemetry_5_to_8 message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param temperature [degC] Temperature.
+ * @param voltage [cV] Voltage.
+ * @param current [cA] Current.
+ * @param totalcurrent [mAh] Total current.
+ * @param rpm [rpm] RPM (eRPM).
+ * @param count count of telemetry packets received (wraps at 65535).
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_esc_telemetry_5_to_8_send(mavlink_channel_t chan, const uint8_t *temperature, const uint16_t *voltage, const uint16_t *current, const uint16_t *totalcurrent, const uint16_t *rpm, const uint16_t *count)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8_LEN];
+
+ _mav_put_uint16_t_array(buf, 0, voltage, 4);
+ _mav_put_uint16_t_array(buf, 8, current, 4);
+ _mav_put_uint16_t_array(buf, 16, totalcurrent, 4);
+ _mav_put_uint16_t_array(buf, 24, rpm, 4);
+ _mav_put_uint16_t_array(buf, 32, count, 4);
+ _mav_put_uint8_t_array(buf, 40, temperature, 4);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8, buf, MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8_MIN_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8_CRC);
+#else
+ mavlink_esc_telemetry_5_to_8_t packet;
+
+ mav_array_assign_uint16_t(packet.voltage, voltage, 4);
+ mav_array_assign_uint16_t(packet.current, current, 4);
+ mav_array_assign_uint16_t(packet.totalcurrent, totalcurrent, 4);
+ mav_array_assign_uint16_t(packet.rpm, rpm, 4);
+ mav_array_assign_uint16_t(packet.count, count, 4);
+ mav_array_assign_uint8_t(packet.temperature, temperature, 4);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8, (const char *)&packet, MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8_MIN_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8_CRC);
+#endif
+}
+
+/**
+ * @brief Send a esc_telemetry_5_to_8 message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_esc_telemetry_5_to_8_send_struct(mavlink_channel_t chan, const mavlink_esc_telemetry_5_to_8_t* esc_telemetry_5_to_8)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_esc_telemetry_5_to_8_send(chan, esc_telemetry_5_to_8->temperature, esc_telemetry_5_to_8->voltage, esc_telemetry_5_to_8->current, esc_telemetry_5_to_8->totalcurrent, esc_telemetry_5_to_8->rpm, esc_telemetry_5_to_8->count);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8, (const char *)esc_telemetry_5_to_8, MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8_MIN_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_esc_telemetry_5_to_8_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, const uint8_t *temperature, const uint16_t *voltage, const uint16_t *current, const uint16_t *totalcurrent, const uint16_t *rpm, const uint16_t *count)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+
+ _mav_put_uint16_t_array(buf, 0, voltage, 4);
+ _mav_put_uint16_t_array(buf, 8, current, 4);
+ _mav_put_uint16_t_array(buf, 16, totalcurrent, 4);
+ _mav_put_uint16_t_array(buf, 24, rpm, 4);
+ _mav_put_uint16_t_array(buf, 32, count, 4);
+ _mav_put_uint8_t_array(buf, 40, temperature, 4);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8, buf, MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8_MIN_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8_CRC);
+#else
+ mavlink_esc_telemetry_5_to_8_t *packet = (mavlink_esc_telemetry_5_to_8_t *)msgbuf;
+
+ mav_array_assign_uint16_t(packet->voltage, voltage, 4);
+ mav_array_assign_uint16_t(packet->current, current, 4);
+ mav_array_assign_uint16_t(packet->totalcurrent, totalcurrent, 4);
+ mav_array_assign_uint16_t(packet->rpm, rpm, 4);
+ mav_array_assign_uint16_t(packet->count, count, 4);
+ mav_array_assign_uint8_t(packet->temperature, temperature, 4);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8, (const char *)packet, MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8_MIN_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE ESC_TELEMETRY_5_TO_8 UNPACKING
+
+
+/**
+ * @brief Get field temperature from esc_telemetry_5_to_8 message
+ *
+ * @return [degC] Temperature.
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_5_to_8_get_temperature(const mavlink_message_t* msg, uint8_t *temperature)
+{
+ return _MAV_RETURN_uint8_t_array(msg, temperature, 4, 40);
+}
+
+/**
+ * @brief Get field voltage from esc_telemetry_5_to_8 message
+ *
+ * @return [cV] Voltage.
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_5_to_8_get_voltage(const mavlink_message_t* msg, uint16_t *voltage)
+{
+ return _MAV_RETURN_uint16_t_array(msg, voltage, 4, 0);
+}
+
+/**
+ * @brief Get field current from esc_telemetry_5_to_8 message
+ *
+ * @return [cA] Current.
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_5_to_8_get_current(const mavlink_message_t* msg, uint16_t *current)
+{
+ return _MAV_RETURN_uint16_t_array(msg, current, 4, 8);
+}
+
+/**
+ * @brief Get field totalcurrent from esc_telemetry_5_to_8 message
+ *
+ * @return [mAh] Total current.
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_5_to_8_get_totalcurrent(const mavlink_message_t* msg, uint16_t *totalcurrent)
+{
+ return _MAV_RETURN_uint16_t_array(msg, totalcurrent, 4, 16);
+}
+
+/**
+ * @brief Get field rpm from esc_telemetry_5_to_8 message
+ *
+ * @return [rpm] RPM (eRPM).
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_5_to_8_get_rpm(const mavlink_message_t* msg, uint16_t *rpm)
+{
+ return _MAV_RETURN_uint16_t_array(msg, rpm, 4, 24);
+}
+
+/**
+ * @brief Get field count from esc_telemetry_5_to_8 message
+ *
+ * @return count of telemetry packets received (wraps at 65535).
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_5_to_8_get_count(const mavlink_message_t* msg, uint16_t *count)
+{
+ return _MAV_RETURN_uint16_t_array(msg, count, 4, 32);
+}
+
+/**
+ * @brief Decode a esc_telemetry_5_to_8 message into a struct
+ *
+ * @param msg The message to decode
+ * @param esc_telemetry_5_to_8 C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_esc_telemetry_5_to_8_decode(const mavlink_message_t* msg, mavlink_esc_telemetry_5_to_8_t* esc_telemetry_5_to_8)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_esc_telemetry_5_to_8_get_voltage(msg, esc_telemetry_5_to_8->voltage);
+ mavlink_msg_esc_telemetry_5_to_8_get_current(msg, esc_telemetry_5_to_8->current);
+ mavlink_msg_esc_telemetry_5_to_8_get_totalcurrent(msg, esc_telemetry_5_to_8->totalcurrent);
+ mavlink_msg_esc_telemetry_5_to_8_get_rpm(msg, esc_telemetry_5_to_8->rpm);
+ mavlink_msg_esc_telemetry_5_to_8_get_count(msg, esc_telemetry_5_to_8->count);
+ mavlink_msg_esc_telemetry_5_to_8_get_temperature(msg, esc_telemetry_5_to_8->temperature);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8_LEN? msg->len : MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8_LEN;
+ memset(esc_telemetry_5_to_8, 0, MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8_LEN);
+ memcpy(esc_telemetry_5_to_8, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/ardupilotmega/mavlink_msg_esc_telemetry_9_to_12.h b/lib/main/MAVLink/ardupilotmega/mavlink_msg_esc_telemetry_9_to_12.h
new file mode 100644
index 00000000000..52c1d4e8f3d
--- /dev/null
+++ b/lib/main/MAVLink/ardupilotmega/mavlink_msg_esc_telemetry_9_to_12.h
@@ -0,0 +1,405 @@
+#pragma once
+// MESSAGE ESC_TELEMETRY_9_TO_12 PACKING
+
+#define MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12 11032
+
+
+typedef struct __mavlink_esc_telemetry_9_to_12_t {
+ uint16_t voltage[4]; /*< [cV] Voltage.*/
+ uint16_t current[4]; /*< [cA] Current.*/
+ uint16_t totalcurrent[4]; /*< [mAh] Total current.*/
+ uint16_t rpm[4]; /*< [rpm] RPM (eRPM).*/
+ uint16_t count[4]; /*< count of telemetry packets received (wraps at 65535).*/
+ uint8_t temperature[4]; /*< [degC] Temperature.*/
+} mavlink_esc_telemetry_9_to_12_t;
+
+#define MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12_LEN 44
+#define MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12_MIN_LEN 44
+#define MAVLINK_MSG_ID_11032_LEN 44
+#define MAVLINK_MSG_ID_11032_MIN_LEN 44
+
+#define MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12_CRC 85
+#define MAVLINK_MSG_ID_11032_CRC 85
+
+#define MAVLINK_MSG_ESC_TELEMETRY_9_TO_12_FIELD_VOLTAGE_LEN 4
+#define MAVLINK_MSG_ESC_TELEMETRY_9_TO_12_FIELD_CURRENT_LEN 4
+#define MAVLINK_MSG_ESC_TELEMETRY_9_TO_12_FIELD_TOTALCURRENT_LEN 4
+#define MAVLINK_MSG_ESC_TELEMETRY_9_TO_12_FIELD_RPM_LEN 4
+#define MAVLINK_MSG_ESC_TELEMETRY_9_TO_12_FIELD_COUNT_LEN 4
+#define MAVLINK_MSG_ESC_TELEMETRY_9_TO_12_FIELD_TEMPERATURE_LEN 4
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_ESC_TELEMETRY_9_TO_12 { \
+ 11032, \
+ "ESC_TELEMETRY_9_TO_12", \
+ 6, \
+ { { "temperature", NULL, MAVLINK_TYPE_UINT8_T, 4, 40, offsetof(mavlink_esc_telemetry_9_to_12_t, temperature) }, \
+ { "voltage", NULL, MAVLINK_TYPE_UINT16_T, 4, 0, offsetof(mavlink_esc_telemetry_9_to_12_t, voltage) }, \
+ { "current", NULL, MAVLINK_TYPE_UINT16_T, 4, 8, offsetof(mavlink_esc_telemetry_9_to_12_t, current) }, \
+ { "totalcurrent", NULL, MAVLINK_TYPE_UINT16_T, 4, 16, offsetof(mavlink_esc_telemetry_9_to_12_t, totalcurrent) }, \
+ { "rpm", NULL, MAVLINK_TYPE_UINT16_T, 4, 24, offsetof(mavlink_esc_telemetry_9_to_12_t, rpm) }, \
+ { "count", NULL, MAVLINK_TYPE_UINT16_T, 4, 32, offsetof(mavlink_esc_telemetry_9_to_12_t, count) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_ESC_TELEMETRY_9_TO_12 { \
+ "ESC_TELEMETRY_9_TO_12", \
+ 6, \
+ { { "temperature", NULL, MAVLINK_TYPE_UINT8_T, 4, 40, offsetof(mavlink_esc_telemetry_9_to_12_t, temperature) }, \
+ { "voltage", NULL, MAVLINK_TYPE_UINT16_T, 4, 0, offsetof(mavlink_esc_telemetry_9_to_12_t, voltage) }, \
+ { "current", NULL, MAVLINK_TYPE_UINT16_T, 4, 8, offsetof(mavlink_esc_telemetry_9_to_12_t, current) }, \
+ { "totalcurrent", NULL, MAVLINK_TYPE_UINT16_T, 4, 16, offsetof(mavlink_esc_telemetry_9_to_12_t, totalcurrent) }, \
+ { "rpm", NULL, MAVLINK_TYPE_UINT16_T, 4, 24, offsetof(mavlink_esc_telemetry_9_to_12_t, rpm) }, \
+ { "count", NULL, MAVLINK_TYPE_UINT16_T, 4, 32, offsetof(mavlink_esc_telemetry_9_to_12_t, count) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a esc_telemetry_9_to_12 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 temperature [degC] Temperature.
+ * @param voltage [cV] Voltage.
+ * @param current [cA] Current.
+ * @param totalcurrent [mAh] Total current.
+ * @param rpm [rpm] RPM (eRPM).
+ * @param count count of telemetry packets received (wraps at 65535).
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_9_to_12_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ const uint8_t *temperature, const uint16_t *voltage, const uint16_t *current, const uint16_t *totalcurrent, const uint16_t *rpm, const uint16_t *count)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12_LEN];
+
+ _mav_put_uint16_t_array(buf, 0, voltage, 4);
+ _mav_put_uint16_t_array(buf, 8, current, 4);
+ _mav_put_uint16_t_array(buf, 16, totalcurrent, 4);
+ _mav_put_uint16_t_array(buf, 24, rpm, 4);
+ _mav_put_uint16_t_array(buf, 32, count, 4);
+ _mav_put_uint8_t_array(buf, 40, temperature, 4);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12_LEN);
+#else
+ mavlink_esc_telemetry_9_to_12_t packet;
+
+ mav_array_assign_uint16_t(packet.voltage, voltage, 4);
+ mav_array_assign_uint16_t(packet.current, current, 4);
+ mav_array_assign_uint16_t(packet.totalcurrent, totalcurrent, 4);
+ mav_array_assign_uint16_t(packet.rpm, rpm, 4);
+ mav_array_assign_uint16_t(packet.count, count, 4);
+ mav_array_assign_uint8_t(packet.temperature, temperature, 4);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12_MIN_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12_CRC);
+}
+
+/**
+ * @brief Pack a esc_telemetry_9_to_12 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 temperature [degC] Temperature.
+ * @param voltage [cV] Voltage.
+ * @param current [cA] Current.
+ * @param totalcurrent [mAh] Total current.
+ * @param rpm [rpm] RPM (eRPM).
+ * @param count count of telemetry packets received (wraps at 65535).
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_9_to_12_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ const uint8_t *temperature, const uint16_t *voltage, const uint16_t *current, const uint16_t *totalcurrent, const uint16_t *rpm, const uint16_t *count)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12_LEN];
+
+ _mav_put_uint16_t_array(buf, 0, voltage, 4);
+ _mav_put_uint16_t_array(buf, 8, current, 4);
+ _mav_put_uint16_t_array(buf, 16, totalcurrent, 4);
+ _mav_put_uint16_t_array(buf, 24, rpm, 4);
+ _mav_put_uint16_t_array(buf, 32, count, 4);
+ _mav_put_uint8_t_array(buf, 40, temperature, 4);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12_LEN);
+#else
+ mavlink_esc_telemetry_9_to_12_t packet;
+
+ mav_array_memcpy(packet.voltage, voltage, sizeof(uint16_t)*4);
+ mav_array_memcpy(packet.current, current, sizeof(uint16_t)*4);
+ mav_array_memcpy(packet.totalcurrent, totalcurrent, sizeof(uint16_t)*4);
+ mav_array_memcpy(packet.rpm, rpm, sizeof(uint16_t)*4);
+ mav_array_memcpy(packet.count, count, sizeof(uint16_t)*4);
+ mav_array_memcpy(packet.temperature, temperature, sizeof(uint8_t)*4);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12_MIN_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12_MIN_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a esc_telemetry_9_to_12 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 temperature [degC] Temperature.
+ * @param voltage [cV] Voltage.
+ * @param current [cA] Current.
+ * @param totalcurrent [mAh] Total current.
+ * @param rpm [rpm] RPM (eRPM).
+ * @param count count of telemetry packets received (wraps at 65535).
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_9_to_12_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ const uint8_t *temperature,const uint16_t *voltage,const uint16_t *current,const uint16_t *totalcurrent,const uint16_t *rpm,const uint16_t *count)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12_LEN];
+
+ _mav_put_uint16_t_array(buf, 0, voltage, 4);
+ _mav_put_uint16_t_array(buf, 8, current, 4);
+ _mav_put_uint16_t_array(buf, 16, totalcurrent, 4);
+ _mav_put_uint16_t_array(buf, 24, rpm, 4);
+ _mav_put_uint16_t_array(buf, 32, count, 4);
+ _mav_put_uint8_t_array(buf, 40, temperature, 4);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12_LEN);
+#else
+ mavlink_esc_telemetry_9_to_12_t packet;
+
+ mav_array_assign_uint16_t(packet.voltage, voltage, 4);
+ mav_array_assign_uint16_t(packet.current, current, 4);
+ mav_array_assign_uint16_t(packet.totalcurrent, totalcurrent, 4);
+ mav_array_assign_uint16_t(packet.rpm, rpm, 4);
+ mav_array_assign_uint16_t(packet.count, count, 4);
+ mav_array_assign_uint8_t(packet.temperature, temperature, 4);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12_MIN_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12_CRC);
+}
+
+/**
+ * @brief Encode a esc_telemetry_9_to_12 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 esc_telemetry_9_to_12 C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_9_to_12_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_esc_telemetry_9_to_12_t* esc_telemetry_9_to_12)
+{
+ return mavlink_msg_esc_telemetry_9_to_12_pack(system_id, component_id, msg, esc_telemetry_9_to_12->temperature, esc_telemetry_9_to_12->voltage, esc_telemetry_9_to_12->current, esc_telemetry_9_to_12->totalcurrent, esc_telemetry_9_to_12->rpm, esc_telemetry_9_to_12->count);
+}
+
+/**
+ * @brief Encode a esc_telemetry_9_to_12 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 esc_telemetry_9_to_12 C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_9_to_12_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_esc_telemetry_9_to_12_t* esc_telemetry_9_to_12)
+{
+ return mavlink_msg_esc_telemetry_9_to_12_pack_chan(system_id, component_id, chan, msg, esc_telemetry_9_to_12->temperature, esc_telemetry_9_to_12->voltage, esc_telemetry_9_to_12->current, esc_telemetry_9_to_12->totalcurrent, esc_telemetry_9_to_12->rpm, esc_telemetry_9_to_12->count);
+}
+
+/**
+ * @brief Encode a esc_telemetry_9_to_12 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 esc_telemetry_9_to_12 C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_9_to_12_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_esc_telemetry_9_to_12_t* esc_telemetry_9_to_12)
+{
+ return mavlink_msg_esc_telemetry_9_to_12_pack_status(system_id, component_id, _status, msg, esc_telemetry_9_to_12->temperature, esc_telemetry_9_to_12->voltage, esc_telemetry_9_to_12->current, esc_telemetry_9_to_12->totalcurrent, esc_telemetry_9_to_12->rpm, esc_telemetry_9_to_12->count);
+}
+
+/**
+ * @brief Send a esc_telemetry_9_to_12 message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param temperature [degC] Temperature.
+ * @param voltage [cV] Voltage.
+ * @param current [cA] Current.
+ * @param totalcurrent [mAh] Total current.
+ * @param rpm [rpm] RPM (eRPM).
+ * @param count count of telemetry packets received (wraps at 65535).
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_esc_telemetry_9_to_12_send(mavlink_channel_t chan, const uint8_t *temperature, const uint16_t *voltage, const uint16_t *current, const uint16_t *totalcurrent, const uint16_t *rpm, const uint16_t *count)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12_LEN];
+
+ _mav_put_uint16_t_array(buf, 0, voltage, 4);
+ _mav_put_uint16_t_array(buf, 8, current, 4);
+ _mav_put_uint16_t_array(buf, 16, totalcurrent, 4);
+ _mav_put_uint16_t_array(buf, 24, rpm, 4);
+ _mav_put_uint16_t_array(buf, 32, count, 4);
+ _mav_put_uint8_t_array(buf, 40, temperature, 4);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12, buf, MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12_MIN_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12_CRC);
+#else
+ mavlink_esc_telemetry_9_to_12_t packet;
+
+ mav_array_assign_uint16_t(packet.voltage, voltage, 4);
+ mav_array_assign_uint16_t(packet.current, current, 4);
+ mav_array_assign_uint16_t(packet.totalcurrent, totalcurrent, 4);
+ mav_array_assign_uint16_t(packet.rpm, rpm, 4);
+ mav_array_assign_uint16_t(packet.count, count, 4);
+ mav_array_assign_uint8_t(packet.temperature, temperature, 4);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12, (const char *)&packet, MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12_MIN_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12_CRC);
+#endif
+}
+
+/**
+ * @brief Send a esc_telemetry_9_to_12 message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_esc_telemetry_9_to_12_send_struct(mavlink_channel_t chan, const mavlink_esc_telemetry_9_to_12_t* esc_telemetry_9_to_12)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_esc_telemetry_9_to_12_send(chan, esc_telemetry_9_to_12->temperature, esc_telemetry_9_to_12->voltage, esc_telemetry_9_to_12->current, esc_telemetry_9_to_12->totalcurrent, esc_telemetry_9_to_12->rpm, esc_telemetry_9_to_12->count);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12, (const char *)esc_telemetry_9_to_12, MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12_MIN_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_esc_telemetry_9_to_12_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, const uint8_t *temperature, const uint16_t *voltage, const uint16_t *current, const uint16_t *totalcurrent, const uint16_t *rpm, const uint16_t *count)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+
+ _mav_put_uint16_t_array(buf, 0, voltage, 4);
+ _mav_put_uint16_t_array(buf, 8, current, 4);
+ _mav_put_uint16_t_array(buf, 16, totalcurrent, 4);
+ _mav_put_uint16_t_array(buf, 24, rpm, 4);
+ _mav_put_uint16_t_array(buf, 32, count, 4);
+ _mav_put_uint8_t_array(buf, 40, temperature, 4);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12, buf, MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12_MIN_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12_CRC);
+#else
+ mavlink_esc_telemetry_9_to_12_t *packet = (mavlink_esc_telemetry_9_to_12_t *)msgbuf;
+
+ mav_array_assign_uint16_t(packet->voltage, voltage, 4);
+ mav_array_assign_uint16_t(packet->current, current, 4);
+ mav_array_assign_uint16_t(packet->totalcurrent, totalcurrent, 4);
+ mav_array_assign_uint16_t(packet->rpm, rpm, 4);
+ mav_array_assign_uint16_t(packet->count, count, 4);
+ mav_array_assign_uint8_t(packet->temperature, temperature, 4);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12, (const char *)packet, MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12_MIN_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12_LEN, MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE ESC_TELEMETRY_9_TO_12 UNPACKING
+
+
+/**
+ * @brief Get field temperature from esc_telemetry_9_to_12 message
+ *
+ * @return [degC] Temperature.
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_9_to_12_get_temperature(const mavlink_message_t* msg, uint8_t *temperature)
+{
+ return _MAV_RETURN_uint8_t_array(msg, temperature, 4, 40);
+}
+
+/**
+ * @brief Get field voltage from esc_telemetry_9_to_12 message
+ *
+ * @return [cV] Voltage.
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_9_to_12_get_voltage(const mavlink_message_t* msg, uint16_t *voltage)
+{
+ return _MAV_RETURN_uint16_t_array(msg, voltage, 4, 0);
+}
+
+/**
+ * @brief Get field current from esc_telemetry_9_to_12 message
+ *
+ * @return [cA] Current.
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_9_to_12_get_current(const mavlink_message_t* msg, uint16_t *current)
+{
+ return _MAV_RETURN_uint16_t_array(msg, current, 4, 8);
+}
+
+/**
+ * @brief Get field totalcurrent from esc_telemetry_9_to_12 message
+ *
+ * @return [mAh] Total current.
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_9_to_12_get_totalcurrent(const mavlink_message_t* msg, uint16_t *totalcurrent)
+{
+ return _MAV_RETURN_uint16_t_array(msg, totalcurrent, 4, 16);
+}
+
+/**
+ * @brief Get field rpm from esc_telemetry_9_to_12 message
+ *
+ * @return [rpm] RPM (eRPM).
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_9_to_12_get_rpm(const mavlink_message_t* msg, uint16_t *rpm)
+{
+ return _MAV_RETURN_uint16_t_array(msg, rpm, 4, 24);
+}
+
+/**
+ * @brief Get field count from esc_telemetry_9_to_12 message
+ *
+ * @return count of telemetry packets received (wraps at 65535).
+ */
+static inline uint16_t mavlink_msg_esc_telemetry_9_to_12_get_count(const mavlink_message_t* msg, uint16_t *count)
+{
+ return _MAV_RETURN_uint16_t_array(msg, count, 4, 32);
+}
+
+/**
+ * @brief Decode a esc_telemetry_9_to_12 message into a struct
+ *
+ * @param msg The message to decode
+ * @param esc_telemetry_9_to_12 C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_esc_telemetry_9_to_12_decode(const mavlink_message_t* msg, mavlink_esc_telemetry_9_to_12_t* esc_telemetry_9_to_12)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_esc_telemetry_9_to_12_get_voltage(msg, esc_telemetry_9_to_12->voltage);
+ mavlink_msg_esc_telemetry_9_to_12_get_current(msg, esc_telemetry_9_to_12->current);
+ mavlink_msg_esc_telemetry_9_to_12_get_totalcurrent(msg, esc_telemetry_9_to_12->totalcurrent);
+ mavlink_msg_esc_telemetry_9_to_12_get_rpm(msg, esc_telemetry_9_to_12->rpm);
+ mavlink_msg_esc_telemetry_9_to_12_get_count(msg, esc_telemetry_9_to_12->count);
+ mavlink_msg_esc_telemetry_9_to_12_get_temperature(msg, esc_telemetry_9_to_12->temperature);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12_LEN? msg->len : MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12_LEN;
+ memset(esc_telemetry_9_to_12, 0, MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12_LEN);
+ memcpy(esc_telemetry_9_to_12, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/ardupilotmega/mavlink_msg_fence_fetch_point.h b/lib/main/MAVLink/ardupilotmega/mavlink_msg_fence_fetch_point.h
new file mode 100644
index 00000000000..81448155c8b
--- /dev/null
+++ b/lib/main/MAVLink/ardupilotmega/mavlink_msg_fence_fetch_point.h
@@ -0,0 +1,316 @@
+#pragma once
+// MESSAGE FENCE_FETCH_POINT PACKING
+
+#define MAVLINK_MSG_ID_FENCE_FETCH_POINT 161
+
+
+typedef struct __mavlink_fence_fetch_point_t {
+ uint8_t target_system; /*< System ID.*/
+ uint8_t target_component; /*< Component ID.*/
+ uint8_t idx; /*< Point index (first point is 1, 0 is for return point).*/
+} mavlink_fence_fetch_point_t;
+
+#define MAVLINK_MSG_ID_FENCE_FETCH_POINT_LEN 3
+#define MAVLINK_MSG_ID_FENCE_FETCH_POINT_MIN_LEN 3
+#define MAVLINK_MSG_ID_161_LEN 3
+#define MAVLINK_MSG_ID_161_MIN_LEN 3
+
+#define MAVLINK_MSG_ID_FENCE_FETCH_POINT_CRC 68
+#define MAVLINK_MSG_ID_161_CRC 68
+
+
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_FENCE_FETCH_POINT { \
+ 161, \
+ "FENCE_FETCH_POINT", \
+ 3, \
+ { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_fence_fetch_point_t, target_system) }, \
+ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_fence_fetch_point_t, target_component) }, \
+ { "idx", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_fence_fetch_point_t, idx) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_FENCE_FETCH_POINT { \
+ "FENCE_FETCH_POINT", \
+ 3, \
+ { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_fence_fetch_point_t, target_system) }, \
+ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_fence_fetch_point_t, target_component) }, \
+ { "idx", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_fence_fetch_point_t, idx) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a fence_fetch_point 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 target_system System ID.
+ * @param target_component Component ID.
+ * @param idx Point index (first point is 1, 0 is for return point).
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_fence_fetch_point_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint8_t target_system, uint8_t target_component, uint8_t idx)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_FENCE_FETCH_POINT_LEN];
+ _mav_put_uint8_t(buf, 0, target_system);
+ _mav_put_uint8_t(buf, 1, target_component);
+ _mav_put_uint8_t(buf, 2, idx);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FENCE_FETCH_POINT_LEN);
+#else
+ mavlink_fence_fetch_point_t packet;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.idx = idx;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FENCE_FETCH_POINT_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_FENCE_FETCH_POINT;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FENCE_FETCH_POINT_MIN_LEN, MAVLINK_MSG_ID_FENCE_FETCH_POINT_LEN, MAVLINK_MSG_ID_FENCE_FETCH_POINT_CRC);
+}
+
+/**
+ * @brief Pack a fence_fetch_point 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 target_system System ID.
+ * @param target_component Component ID.
+ * @param idx Point index (first point is 1, 0 is for return point).
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_fence_fetch_point_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ uint8_t target_system, uint8_t target_component, uint8_t idx)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_FENCE_FETCH_POINT_LEN];
+ _mav_put_uint8_t(buf, 0, target_system);
+ _mav_put_uint8_t(buf, 1, target_component);
+ _mav_put_uint8_t(buf, 2, idx);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FENCE_FETCH_POINT_LEN);
+#else
+ mavlink_fence_fetch_point_t packet;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.idx = idx;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FENCE_FETCH_POINT_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_FENCE_FETCH_POINT;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_FENCE_FETCH_POINT_MIN_LEN, MAVLINK_MSG_ID_FENCE_FETCH_POINT_LEN, MAVLINK_MSG_ID_FENCE_FETCH_POINT_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_FENCE_FETCH_POINT_MIN_LEN, MAVLINK_MSG_ID_FENCE_FETCH_POINT_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a fence_fetch_point 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 target_system System ID.
+ * @param target_component Component ID.
+ * @param idx Point index (first point is 1, 0 is for return point).
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_fence_fetch_point_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint8_t target_system,uint8_t target_component,uint8_t idx)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_FENCE_FETCH_POINT_LEN];
+ _mav_put_uint8_t(buf, 0, target_system);
+ _mav_put_uint8_t(buf, 1, target_component);
+ _mav_put_uint8_t(buf, 2, idx);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FENCE_FETCH_POINT_LEN);
+#else
+ mavlink_fence_fetch_point_t packet;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.idx = idx;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FENCE_FETCH_POINT_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_FENCE_FETCH_POINT;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FENCE_FETCH_POINT_MIN_LEN, MAVLINK_MSG_ID_FENCE_FETCH_POINT_LEN, MAVLINK_MSG_ID_FENCE_FETCH_POINT_CRC);
+}
+
+/**
+ * @brief Encode a fence_fetch_point 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 fence_fetch_point C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_fence_fetch_point_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_fence_fetch_point_t* fence_fetch_point)
+{
+ return mavlink_msg_fence_fetch_point_pack(system_id, component_id, msg, fence_fetch_point->target_system, fence_fetch_point->target_component, fence_fetch_point->idx);
+}
+
+/**
+ * @brief Encode a fence_fetch_point 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 fence_fetch_point C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_fence_fetch_point_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_fence_fetch_point_t* fence_fetch_point)
+{
+ return mavlink_msg_fence_fetch_point_pack_chan(system_id, component_id, chan, msg, fence_fetch_point->target_system, fence_fetch_point->target_component, fence_fetch_point->idx);
+}
+
+/**
+ * @brief Encode a fence_fetch_point 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 fence_fetch_point C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_fence_fetch_point_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_fence_fetch_point_t* fence_fetch_point)
+{
+ return mavlink_msg_fence_fetch_point_pack_status(system_id, component_id, _status, msg, fence_fetch_point->target_system, fence_fetch_point->target_component, fence_fetch_point->idx);
+}
+
+/**
+ * @brief Send a fence_fetch_point message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param target_system System ID.
+ * @param target_component Component ID.
+ * @param idx Point index (first point is 1, 0 is for return point).
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_fence_fetch_point_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t idx)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_FENCE_FETCH_POINT_LEN];
+ _mav_put_uint8_t(buf, 0, target_system);
+ _mav_put_uint8_t(buf, 1, target_component);
+ _mav_put_uint8_t(buf, 2, idx);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_FETCH_POINT, buf, MAVLINK_MSG_ID_FENCE_FETCH_POINT_MIN_LEN, MAVLINK_MSG_ID_FENCE_FETCH_POINT_LEN, MAVLINK_MSG_ID_FENCE_FETCH_POINT_CRC);
+#else
+ mavlink_fence_fetch_point_t packet;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.idx = idx;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_FETCH_POINT, (const char *)&packet, MAVLINK_MSG_ID_FENCE_FETCH_POINT_MIN_LEN, MAVLINK_MSG_ID_FENCE_FETCH_POINT_LEN, MAVLINK_MSG_ID_FENCE_FETCH_POINT_CRC);
+#endif
+}
+
+/**
+ * @brief Send a fence_fetch_point message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_fence_fetch_point_send_struct(mavlink_channel_t chan, const mavlink_fence_fetch_point_t* fence_fetch_point)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_fence_fetch_point_send(chan, fence_fetch_point->target_system, fence_fetch_point->target_component, fence_fetch_point->idx);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_FETCH_POINT, (const char *)fence_fetch_point, MAVLINK_MSG_ID_FENCE_FETCH_POINT_MIN_LEN, MAVLINK_MSG_ID_FENCE_FETCH_POINT_LEN, MAVLINK_MSG_ID_FENCE_FETCH_POINT_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_FENCE_FETCH_POINT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_fence_fetch_point_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t idx)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint8_t(buf, 0, target_system);
+ _mav_put_uint8_t(buf, 1, target_component);
+ _mav_put_uint8_t(buf, 2, idx);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_FETCH_POINT, buf, MAVLINK_MSG_ID_FENCE_FETCH_POINT_MIN_LEN, MAVLINK_MSG_ID_FENCE_FETCH_POINT_LEN, MAVLINK_MSG_ID_FENCE_FETCH_POINT_CRC);
+#else
+ mavlink_fence_fetch_point_t *packet = (mavlink_fence_fetch_point_t *)msgbuf;
+ packet->target_system = target_system;
+ packet->target_component = target_component;
+ packet->idx = idx;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_FETCH_POINT, (const char *)packet, MAVLINK_MSG_ID_FENCE_FETCH_POINT_MIN_LEN, MAVLINK_MSG_ID_FENCE_FETCH_POINT_LEN, MAVLINK_MSG_ID_FENCE_FETCH_POINT_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE FENCE_FETCH_POINT UNPACKING
+
+
+/**
+ * @brief Get field target_system from fence_fetch_point message
+ *
+ * @return System ID.
+ */
+static inline uint8_t mavlink_msg_fence_fetch_point_get_target_system(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 0);
+}
+
+/**
+ * @brief Get field target_component from fence_fetch_point message
+ *
+ * @return Component ID.
+ */
+static inline uint8_t mavlink_msg_fence_fetch_point_get_target_component(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 1);
+}
+
+/**
+ * @brief Get field idx from fence_fetch_point message
+ *
+ * @return Point index (first point is 1, 0 is for return point).
+ */
+static inline uint8_t mavlink_msg_fence_fetch_point_get_idx(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 2);
+}
+
+/**
+ * @brief Decode a fence_fetch_point message into a struct
+ *
+ * @param msg The message to decode
+ * @param fence_fetch_point C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_fence_fetch_point_decode(const mavlink_message_t* msg, mavlink_fence_fetch_point_t* fence_fetch_point)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ fence_fetch_point->target_system = mavlink_msg_fence_fetch_point_get_target_system(msg);
+ fence_fetch_point->target_component = mavlink_msg_fence_fetch_point_get_target_component(msg);
+ fence_fetch_point->idx = mavlink_msg_fence_fetch_point_get_idx(msg);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_FENCE_FETCH_POINT_LEN? msg->len : MAVLINK_MSG_ID_FENCE_FETCH_POINT_LEN;
+ memset(fence_fetch_point, 0, MAVLINK_MSG_ID_FENCE_FETCH_POINT_LEN);
+ memcpy(fence_fetch_point, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/ardupilotmega/mavlink_msg_fence_point.h b/lib/main/MAVLink/ardupilotmega/mavlink_msg_fence_point.h
new file mode 100644
index 00000000000..e94c100ea74
--- /dev/null
+++ b/lib/main/MAVLink/ardupilotmega/mavlink_msg_fence_point.h
@@ -0,0 +1,400 @@
+#pragma once
+// MESSAGE FENCE_POINT PACKING
+
+#define MAVLINK_MSG_ID_FENCE_POINT 160
+
+
+typedef struct __mavlink_fence_point_t {
+ float lat; /*< [deg] Latitude of point.*/
+ float lng; /*< [deg] Longitude of point.*/
+ uint8_t target_system; /*< System ID.*/
+ uint8_t target_component; /*< Component ID.*/
+ uint8_t idx; /*< Point index (first point is 1, 0 is for return point).*/
+ uint8_t count; /*< Total number of points (for sanity checking).*/
+} mavlink_fence_point_t;
+
+#define MAVLINK_MSG_ID_FENCE_POINT_LEN 12
+#define MAVLINK_MSG_ID_FENCE_POINT_MIN_LEN 12
+#define MAVLINK_MSG_ID_160_LEN 12
+#define MAVLINK_MSG_ID_160_MIN_LEN 12
+
+#define MAVLINK_MSG_ID_FENCE_POINT_CRC 78
+#define MAVLINK_MSG_ID_160_CRC 78
+
+
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_FENCE_POINT { \
+ 160, \
+ "FENCE_POINT", \
+ 6, \
+ { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_fence_point_t, target_system) }, \
+ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_fence_point_t, target_component) }, \
+ { "idx", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_fence_point_t, idx) }, \
+ { "count", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_fence_point_t, count) }, \
+ { "lat", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_fence_point_t, lat) }, \
+ { "lng", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_fence_point_t, lng) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_FENCE_POINT { \
+ "FENCE_POINT", \
+ 6, \
+ { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_fence_point_t, target_system) }, \
+ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_fence_point_t, target_component) }, \
+ { "idx", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_fence_point_t, idx) }, \
+ { "count", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_fence_point_t, count) }, \
+ { "lat", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_fence_point_t, lat) }, \
+ { "lng", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_fence_point_t, lng) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a fence_point 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 target_system System ID.
+ * @param target_component Component ID.
+ * @param idx Point index (first point is 1, 0 is for return point).
+ * @param count Total number of points (for sanity checking).
+ * @param lat [deg] Latitude of point.
+ * @param lng [deg] Longitude of point.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_fence_point_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint8_t target_system, uint8_t target_component, uint8_t idx, uint8_t count, float lat, float lng)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_FENCE_POINT_LEN];
+ _mav_put_float(buf, 0, lat);
+ _mav_put_float(buf, 4, lng);
+ _mav_put_uint8_t(buf, 8, target_system);
+ _mav_put_uint8_t(buf, 9, target_component);
+ _mav_put_uint8_t(buf, 10, idx);
+ _mav_put_uint8_t(buf, 11, count);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FENCE_POINT_LEN);
+#else
+ mavlink_fence_point_t packet;
+ packet.lat = lat;
+ packet.lng = lng;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.idx = idx;
+ packet.count = count;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FENCE_POINT_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_FENCE_POINT;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FENCE_POINT_MIN_LEN, MAVLINK_MSG_ID_FENCE_POINT_LEN, MAVLINK_MSG_ID_FENCE_POINT_CRC);
+}
+
+/**
+ * @brief Pack a fence_point 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 target_system System ID.
+ * @param target_component Component ID.
+ * @param idx Point index (first point is 1, 0 is for return point).
+ * @param count Total number of points (for sanity checking).
+ * @param lat [deg] Latitude of point.
+ * @param lng [deg] Longitude of point.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_fence_point_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ uint8_t target_system, uint8_t target_component, uint8_t idx, uint8_t count, float lat, float lng)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_FENCE_POINT_LEN];
+ _mav_put_float(buf, 0, lat);
+ _mav_put_float(buf, 4, lng);
+ _mav_put_uint8_t(buf, 8, target_system);
+ _mav_put_uint8_t(buf, 9, target_component);
+ _mav_put_uint8_t(buf, 10, idx);
+ _mav_put_uint8_t(buf, 11, count);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FENCE_POINT_LEN);
+#else
+ mavlink_fence_point_t packet;
+ packet.lat = lat;
+ packet.lng = lng;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.idx = idx;
+ packet.count = count;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FENCE_POINT_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_FENCE_POINT;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_FENCE_POINT_MIN_LEN, MAVLINK_MSG_ID_FENCE_POINT_LEN, MAVLINK_MSG_ID_FENCE_POINT_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_FENCE_POINT_MIN_LEN, MAVLINK_MSG_ID_FENCE_POINT_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a fence_point 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 target_system System ID.
+ * @param target_component Component ID.
+ * @param idx Point index (first point is 1, 0 is for return point).
+ * @param count Total number of points (for sanity checking).
+ * @param lat [deg] Latitude of point.
+ * @param lng [deg] Longitude of point.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_fence_point_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint8_t target_system,uint8_t target_component,uint8_t idx,uint8_t count,float lat,float lng)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_FENCE_POINT_LEN];
+ _mav_put_float(buf, 0, lat);
+ _mav_put_float(buf, 4, lng);
+ _mav_put_uint8_t(buf, 8, target_system);
+ _mav_put_uint8_t(buf, 9, target_component);
+ _mav_put_uint8_t(buf, 10, idx);
+ _mav_put_uint8_t(buf, 11, count);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FENCE_POINT_LEN);
+#else
+ mavlink_fence_point_t packet;
+ packet.lat = lat;
+ packet.lng = lng;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.idx = idx;
+ packet.count = count;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FENCE_POINT_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_FENCE_POINT;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FENCE_POINT_MIN_LEN, MAVLINK_MSG_ID_FENCE_POINT_LEN, MAVLINK_MSG_ID_FENCE_POINT_CRC);
+}
+
+/**
+ * @brief Encode a fence_point 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 fence_point C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_fence_point_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_fence_point_t* fence_point)
+{
+ return mavlink_msg_fence_point_pack(system_id, component_id, msg, fence_point->target_system, fence_point->target_component, fence_point->idx, fence_point->count, fence_point->lat, fence_point->lng);
+}
+
+/**
+ * @brief Encode a fence_point 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 fence_point C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_fence_point_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_fence_point_t* fence_point)
+{
+ return mavlink_msg_fence_point_pack_chan(system_id, component_id, chan, msg, fence_point->target_system, fence_point->target_component, fence_point->idx, fence_point->count, fence_point->lat, fence_point->lng);
+}
+
+/**
+ * @brief Encode a fence_point 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 fence_point C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_fence_point_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_fence_point_t* fence_point)
+{
+ return mavlink_msg_fence_point_pack_status(system_id, component_id, _status, msg, fence_point->target_system, fence_point->target_component, fence_point->idx, fence_point->count, fence_point->lat, fence_point->lng);
+}
+
+/**
+ * @brief Send a fence_point message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param target_system System ID.
+ * @param target_component Component ID.
+ * @param idx Point index (first point is 1, 0 is for return point).
+ * @param count Total number of points (for sanity checking).
+ * @param lat [deg] Latitude of point.
+ * @param lng [deg] Longitude of point.
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_fence_point_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t idx, uint8_t count, float lat, float lng)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_FENCE_POINT_LEN];
+ _mav_put_float(buf, 0, lat);
+ _mav_put_float(buf, 4, lng);
+ _mav_put_uint8_t(buf, 8, target_system);
+ _mav_put_uint8_t(buf, 9, target_component);
+ _mav_put_uint8_t(buf, 10, idx);
+ _mav_put_uint8_t(buf, 11, count);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_POINT, buf, MAVLINK_MSG_ID_FENCE_POINT_MIN_LEN, MAVLINK_MSG_ID_FENCE_POINT_LEN, MAVLINK_MSG_ID_FENCE_POINT_CRC);
+#else
+ mavlink_fence_point_t packet;
+ packet.lat = lat;
+ packet.lng = lng;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.idx = idx;
+ packet.count = count;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_POINT, (const char *)&packet, MAVLINK_MSG_ID_FENCE_POINT_MIN_LEN, MAVLINK_MSG_ID_FENCE_POINT_LEN, MAVLINK_MSG_ID_FENCE_POINT_CRC);
+#endif
+}
+
+/**
+ * @brief Send a fence_point message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_fence_point_send_struct(mavlink_channel_t chan, const mavlink_fence_point_t* fence_point)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_fence_point_send(chan, fence_point->target_system, fence_point->target_component, fence_point->idx, fence_point->count, fence_point->lat, fence_point->lng);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_POINT, (const char *)fence_point, MAVLINK_MSG_ID_FENCE_POINT_MIN_LEN, MAVLINK_MSG_ID_FENCE_POINT_LEN, MAVLINK_MSG_ID_FENCE_POINT_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_FENCE_POINT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_fence_point_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t idx, uint8_t count, float lat, float lng)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_float(buf, 0, lat);
+ _mav_put_float(buf, 4, lng);
+ _mav_put_uint8_t(buf, 8, target_system);
+ _mav_put_uint8_t(buf, 9, target_component);
+ _mav_put_uint8_t(buf, 10, idx);
+ _mav_put_uint8_t(buf, 11, count);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_POINT, buf, MAVLINK_MSG_ID_FENCE_POINT_MIN_LEN, MAVLINK_MSG_ID_FENCE_POINT_LEN, MAVLINK_MSG_ID_FENCE_POINT_CRC);
+#else
+ mavlink_fence_point_t *packet = (mavlink_fence_point_t *)msgbuf;
+ packet->lat = lat;
+ packet->lng = lng;
+ packet->target_system = target_system;
+ packet->target_component = target_component;
+ packet->idx = idx;
+ packet->count = count;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_POINT, (const char *)packet, MAVLINK_MSG_ID_FENCE_POINT_MIN_LEN, MAVLINK_MSG_ID_FENCE_POINT_LEN, MAVLINK_MSG_ID_FENCE_POINT_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE FENCE_POINT UNPACKING
+
+
+/**
+ * @brief Get field target_system from fence_point message
+ *
+ * @return System ID.
+ */
+static inline uint8_t mavlink_msg_fence_point_get_target_system(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 8);
+}
+
+/**
+ * @brief Get field target_component from fence_point message
+ *
+ * @return Component ID.
+ */
+static inline uint8_t mavlink_msg_fence_point_get_target_component(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 9);
+}
+
+/**
+ * @brief Get field idx from fence_point message
+ *
+ * @return Point index (first point is 1, 0 is for return point).
+ */
+static inline uint8_t mavlink_msg_fence_point_get_idx(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 10);
+}
+
+/**
+ * @brief Get field count from fence_point message
+ *
+ * @return Total number of points (for sanity checking).
+ */
+static inline uint8_t mavlink_msg_fence_point_get_count(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 11);
+}
+
+/**
+ * @brief Get field lat from fence_point message
+ *
+ * @return [deg] Latitude of point.
+ */
+static inline float mavlink_msg_fence_point_get_lat(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 0);
+}
+
+/**
+ * @brief Get field lng from fence_point message
+ *
+ * @return [deg] Longitude of point.
+ */
+static inline float mavlink_msg_fence_point_get_lng(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 4);
+}
+
+/**
+ * @brief Decode a fence_point message into a struct
+ *
+ * @param msg The message to decode
+ * @param fence_point C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_fence_point_decode(const mavlink_message_t* msg, mavlink_fence_point_t* fence_point)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ fence_point->lat = mavlink_msg_fence_point_get_lat(msg);
+ fence_point->lng = mavlink_msg_fence_point_get_lng(msg);
+ fence_point->target_system = mavlink_msg_fence_point_get_target_system(msg);
+ fence_point->target_component = mavlink_msg_fence_point_get_target_component(msg);
+ fence_point->idx = mavlink_msg_fence_point_get_idx(msg);
+ fence_point->count = mavlink_msg_fence_point_get_count(msg);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_FENCE_POINT_LEN? msg->len : MAVLINK_MSG_ID_FENCE_POINT_LEN;
+ memset(fence_point, 0, MAVLINK_MSG_ID_FENCE_POINT_LEN);
+ memcpy(fence_point, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/ardupilotmega/mavlink_msg_gimbal_control.h b/lib/main/MAVLink/ardupilotmega/mavlink_msg_gimbal_control.h
new file mode 100644
index 00000000000..48ca185052f
--- /dev/null
+++ b/lib/main/MAVLink/ardupilotmega/mavlink_msg_gimbal_control.h
@@ -0,0 +1,372 @@
+#pragma once
+// MESSAGE GIMBAL_CONTROL PACKING
+
+#define MAVLINK_MSG_ID_GIMBAL_CONTROL 201
+
+
+typedef struct __mavlink_gimbal_control_t {
+ float demanded_rate_x; /*< [rad/s] Demanded angular rate X.*/
+ float demanded_rate_y; /*< [rad/s] Demanded angular rate Y.*/
+ float demanded_rate_z; /*< [rad/s] Demanded angular rate Z.*/
+ uint8_t target_system; /*< System ID.*/
+ uint8_t target_component; /*< Component ID.*/
+} mavlink_gimbal_control_t;
+
+#define MAVLINK_MSG_ID_GIMBAL_CONTROL_LEN 14
+#define MAVLINK_MSG_ID_GIMBAL_CONTROL_MIN_LEN 14
+#define MAVLINK_MSG_ID_201_LEN 14
+#define MAVLINK_MSG_ID_201_MIN_LEN 14
+
+#define MAVLINK_MSG_ID_GIMBAL_CONTROL_CRC 205
+#define MAVLINK_MSG_ID_201_CRC 205
+
+
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_GIMBAL_CONTROL { \
+ 201, \
+ "GIMBAL_CONTROL", \
+ 5, \
+ { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_gimbal_control_t, target_system) }, \
+ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_gimbal_control_t, target_component) }, \
+ { "demanded_rate_x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_gimbal_control_t, demanded_rate_x) }, \
+ { "demanded_rate_y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_gimbal_control_t, demanded_rate_y) }, \
+ { "demanded_rate_z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_gimbal_control_t, demanded_rate_z) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_GIMBAL_CONTROL { \
+ "GIMBAL_CONTROL", \
+ 5, \
+ { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_gimbal_control_t, target_system) }, \
+ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_gimbal_control_t, target_component) }, \
+ { "demanded_rate_x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_gimbal_control_t, demanded_rate_x) }, \
+ { "demanded_rate_y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_gimbal_control_t, demanded_rate_y) }, \
+ { "demanded_rate_z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_gimbal_control_t, demanded_rate_z) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a gimbal_control 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 target_system System ID.
+ * @param target_component Component ID.
+ * @param demanded_rate_x [rad/s] Demanded angular rate X.
+ * @param demanded_rate_y [rad/s] Demanded angular rate Y.
+ * @param demanded_rate_z [rad/s] Demanded angular rate Z.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_gimbal_control_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint8_t target_system, uint8_t target_component, float demanded_rate_x, float demanded_rate_y, float demanded_rate_z)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_GIMBAL_CONTROL_LEN];
+ _mav_put_float(buf, 0, demanded_rate_x);
+ _mav_put_float(buf, 4, demanded_rate_y);
+ _mav_put_float(buf, 8, demanded_rate_z);
+ _mav_put_uint8_t(buf, 12, target_system);
+ _mav_put_uint8_t(buf, 13, target_component);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GIMBAL_CONTROL_LEN);
+#else
+ mavlink_gimbal_control_t packet;
+ packet.demanded_rate_x = demanded_rate_x;
+ packet.demanded_rate_y = demanded_rate_y;
+ packet.demanded_rate_z = demanded_rate_z;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GIMBAL_CONTROL_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_GIMBAL_CONTROL;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GIMBAL_CONTROL_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_CONTROL_LEN, MAVLINK_MSG_ID_GIMBAL_CONTROL_CRC);
+}
+
+/**
+ * @brief Pack a gimbal_control 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 target_system System ID.
+ * @param target_component Component ID.
+ * @param demanded_rate_x [rad/s] Demanded angular rate X.
+ * @param demanded_rate_y [rad/s] Demanded angular rate Y.
+ * @param demanded_rate_z [rad/s] Demanded angular rate Z.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_gimbal_control_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ uint8_t target_system, uint8_t target_component, float demanded_rate_x, float demanded_rate_y, float demanded_rate_z)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_GIMBAL_CONTROL_LEN];
+ _mav_put_float(buf, 0, demanded_rate_x);
+ _mav_put_float(buf, 4, demanded_rate_y);
+ _mav_put_float(buf, 8, demanded_rate_z);
+ _mav_put_uint8_t(buf, 12, target_system);
+ _mav_put_uint8_t(buf, 13, target_component);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GIMBAL_CONTROL_LEN);
+#else
+ mavlink_gimbal_control_t packet;
+ packet.demanded_rate_x = demanded_rate_x;
+ packet.demanded_rate_y = demanded_rate_y;
+ packet.demanded_rate_z = demanded_rate_z;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GIMBAL_CONTROL_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_GIMBAL_CONTROL;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_GIMBAL_CONTROL_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_CONTROL_LEN, MAVLINK_MSG_ID_GIMBAL_CONTROL_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_GIMBAL_CONTROL_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_CONTROL_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a gimbal_control 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 target_system System ID.
+ * @param target_component Component ID.
+ * @param demanded_rate_x [rad/s] Demanded angular rate X.
+ * @param demanded_rate_y [rad/s] Demanded angular rate Y.
+ * @param demanded_rate_z [rad/s] Demanded angular rate Z.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_gimbal_control_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint8_t target_system,uint8_t target_component,float demanded_rate_x,float demanded_rate_y,float demanded_rate_z)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_GIMBAL_CONTROL_LEN];
+ _mav_put_float(buf, 0, demanded_rate_x);
+ _mav_put_float(buf, 4, demanded_rate_y);
+ _mav_put_float(buf, 8, demanded_rate_z);
+ _mav_put_uint8_t(buf, 12, target_system);
+ _mav_put_uint8_t(buf, 13, target_component);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GIMBAL_CONTROL_LEN);
+#else
+ mavlink_gimbal_control_t packet;
+ packet.demanded_rate_x = demanded_rate_x;
+ packet.demanded_rate_y = demanded_rate_y;
+ packet.demanded_rate_z = demanded_rate_z;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GIMBAL_CONTROL_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_GIMBAL_CONTROL;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GIMBAL_CONTROL_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_CONTROL_LEN, MAVLINK_MSG_ID_GIMBAL_CONTROL_CRC);
+}
+
+/**
+ * @brief Encode a gimbal_control 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 gimbal_control C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_gimbal_control_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gimbal_control_t* gimbal_control)
+{
+ return mavlink_msg_gimbal_control_pack(system_id, component_id, msg, gimbal_control->target_system, gimbal_control->target_component, gimbal_control->demanded_rate_x, gimbal_control->demanded_rate_y, gimbal_control->demanded_rate_z);
+}
+
+/**
+ * @brief Encode a gimbal_control 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 gimbal_control C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_gimbal_control_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gimbal_control_t* gimbal_control)
+{
+ return mavlink_msg_gimbal_control_pack_chan(system_id, component_id, chan, msg, gimbal_control->target_system, gimbal_control->target_component, gimbal_control->demanded_rate_x, gimbal_control->demanded_rate_y, gimbal_control->demanded_rate_z);
+}
+
+/**
+ * @brief Encode a gimbal_control 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 gimbal_control C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_gimbal_control_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_gimbal_control_t* gimbal_control)
+{
+ return mavlink_msg_gimbal_control_pack_status(system_id, component_id, _status, msg, gimbal_control->target_system, gimbal_control->target_component, gimbal_control->demanded_rate_x, gimbal_control->demanded_rate_y, gimbal_control->demanded_rate_z);
+}
+
+/**
+ * @brief Send a gimbal_control message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param target_system System ID.
+ * @param target_component Component ID.
+ * @param demanded_rate_x [rad/s] Demanded angular rate X.
+ * @param demanded_rate_y [rad/s] Demanded angular rate Y.
+ * @param demanded_rate_z [rad/s] Demanded angular rate Z.
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_gimbal_control_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, float demanded_rate_x, float demanded_rate_y, float demanded_rate_z)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_GIMBAL_CONTROL_LEN];
+ _mav_put_float(buf, 0, demanded_rate_x);
+ _mav_put_float(buf, 4, demanded_rate_y);
+ _mav_put_float(buf, 8, demanded_rate_z);
+ _mav_put_uint8_t(buf, 12, target_system);
+ _mav_put_uint8_t(buf, 13, target_component);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_CONTROL, buf, MAVLINK_MSG_ID_GIMBAL_CONTROL_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_CONTROL_LEN, MAVLINK_MSG_ID_GIMBAL_CONTROL_CRC);
+#else
+ mavlink_gimbal_control_t packet;
+ packet.demanded_rate_x = demanded_rate_x;
+ packet.demanded_rate_y = demanded_rate_y;
+ packet.demanded_rate_z = demanded_rate_z;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_CONTROL, (const char *)&packet, MAVLINK_MSG_ID_GIMBAL_CONTROL_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_CONTROL_LEN, MAVLINK_MSG_ID_GIMBAL_CONTROL_CRC);
+#endif
+}
+
+/**
+ * @brief Send a gimbal_control message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_gimbal_control_send_struct(mavlink_channel_t chan, const mavlink_gimbal_control_t* gimbal_control)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_gimbal_control_send(chan, gimbal_control->target_system, gimbal_control->target_component, gimbal_control->demanded_rate_x, gimbal_control->demanded_rate_y, gimbal_control->demanded_rate_z);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_CONTROL, (const char *)gimbal_control, MAVLINK_MSG_ID_GIMBAL_CONTROL_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_CONTROL_LEN, MAVLINK_MSG_ID_GIMBAL_CONTROL_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_GIMBAL_CONTROL_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_gimbal_control_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, float demanded_rate_x, float demanded_rate_y, float demanded_rate_z)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_float(buf, 0, demanded_rate_x);
+ _mav_put_float(buf, 4, demanded_rate_y);
+ _mav_put_float(buf, 8, demanded_rate_z);
+ _mav_put_uint8_t(buf, 12, target_system);
+ _mav_put_uint8_t(buf, 13, target_component);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_CONTROL, buf, MAVLINK_MSG_ID_GIMBAL_CONTROL_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_CONTROL_LEN, MAVLINK_MSG_ID_GIMBAL_CONTROL_CRC);
+#else
+ mavlink_gimbal_control_t *packet = (mavlink_gimbal_control_t *)msgbuf;
+ packet->demanded_rate_x = demanded_rate_x;
+ packet->demanded_rate_y = demanded_rate_y;
+ packet->demanded_rate_z = demanded_rate_z;
+ packet->target_system = target_system;
+ packet->target_component = target_component;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_CONTROL, (const char *)packet, MAVLINK_MSG_ID_GIMBAL_CONTROL_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_CONTROL_LEN, MAVLINK_MSG_ID_GIMBAL_CONTROL_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE GIMBAL_CONTROL UNPACKING
+
+
+/**
+ * @brief Get field target_system from gimbal_control message
+ *
+ * @return System ID.
+ */
+static inline uint8_t mavlink_msg_gimbal_control_get_target_system(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 12);
+}
+
+/**
+ * @brief Get field target_component from gimbal_control message
+ *
+ * @return Component ID.
+ */
+static inline uint8_t mavlink_msg_gimbal_control_get_target_component(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 13);
+}
+
+/**
+ * @brief Get field demanded_rate_x from gimbal_control message
+ *
+ * @return [rad/s] Demanded angular rate X.
+ */
+static inline float mavlink_msg_gimbal_control_get_demanded_rate_x(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 0);
+}
+
+/**
+ * @brief Get field demanded_rate_y from gimbal_control message
+ *
+ * @return [rad/s] Demanded angular rate Y.
+ */
+static inline float mavlink_msg_gimbal_control_get_demanded_rate_y(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 4);
+}
+
+/**
+ * @brief Get field demanded_rate_z from gimbal_control message
+ *
+ * @return [rad/s] Demanded angular rate Z.
+ */
+static inline float mavlink_msg_gimbal_control_get_demanded_rate_z(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 8);
+}
+
+/**
+ * @brief Decode a gimbal_control message into a struct
+ *
+ * @param msg The message to decode
+ * @param gimbal_control C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_gimbal_control_decode(const mavlink_message_t* msg, mavlink_gimbal_control_t* gimbal_control)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ gimbal_control->demanded_rate_x = mavlink_msg_gimbal_control_get_demanded_rate_x(msg);
+ gimbal_control->demanded_rate_y = mavlink_msg_gimbal_control_get_demanded_rate_y(msg);
+ gimbal_control->demanded_rate_z = mavlink_msg_gimbal_control_get_demanded_rate_z(msg);
+ gimbal_control->target_system = mavlink_msg_gimbal_control_get_target_system(msg);
+ gimbal_control->target_component = mavlink_msg_gimbal_control_get_target_component(msg);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_GIMBAL_CONTROL_LEN? msg->len : MAVLINK_MSG_ID_GIMBAL_CONTROL_LEN;
+ memset(gimbal_control, 0, MAVLINK_MSG_ID_GIMBAL_CONTROL_LEN);
+ memcpy(gimbal_control, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/ardupilotmega/mavlink_msg_gimbal_report.h b/lib/main/MAVLink/ardupilotmega/mavlink_msg_gimbal_report.h
new file mode 100644
index 00000000000..d731f3bf7a6
--- /dev/null
+++ b/lib/main/MAVLink/ardupilotmega/mavlink_msg_gimbal_report.h
@@ -0,0 +1,568 @@
+#pragma once
+// MESSAGE GIMBAL_REPORT PACKING
+
+#define MAVLINK_MSG_ID_GIMBAL_REPORT 200
+
+
+typedef struct __mavlink_gimbal_report_t {
+ float delta_time; /*< [s] Time since last update.*/
+ float delta_angle_x; /*< [rad] Delta angle X.*/
+ float delta_angle_y; /*< [rad] Delta angle Y.*/
+ float delta_angle_z; /*< [rad] Delta angle X.*/
+ float delta_velocity_x; /*< [m/s] Delta velocity X.*/
+ float delta_velocity_y; /*< [m/s] Delta velocity Y.*/
+ float delta_velocity_z; /*< [m/s] Delta velocity Z.*/
+ float joint_roll; /*< [rad] Joint ROLL.*/
+ float joint_el; /*< [rad] Joint EL.*/
+ float joint_az; /*< [rad] Joint AZ.*/
+ uint8_t target_system; /*< System ID.*/
+ uint8_t target_component; /*< Component ID.*/
+} mavlink_gimbal_report_t;
+
+#define MAVLINK_MSG_ID_GIMBAL_REPORT_LEN 42
+#define MAVLINK_MSG_ID_GIMBAL_REPORT_MIN_LEN 42
+#define MAVLINK_MSG_ID_200_LEN 42
+#define MAVLINK_MSG_ID_200_MIN_LEN 42
+
+#define MAVLINK_MSG_ID_GIMBAL_REPORT_CRC 134
+#define MAVLINK_MSG_ID_200_CRC 134
+
+
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_GIMBAL_REPORT { \
+ 200, \
+ "GIMBAL_REPORT", \
+ 12, \
+ { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 40, offsetof(mavlink_gimbal_report_t, target_system) }, \
+ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 41, offsetof(mavlink_gimbal_report_t, target_component) }, \
+ { "delta_time", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_gimbal_report_t, delta_time) }, \
+ { "delta_angle_x", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_gimbal_report_t, delta_angle_x) }, \
+ { "delta_angle_y", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_gimbal_report_t, delta_angle_y) }, \
+ { "delta_angle_z", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_gimbal_report_t, delta_angle_z) }, \
+ { "delta_velocity_x", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_gimbal_report_t, delta_velocity_x) }, \
+ { "delta_velocity_y", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_gimbal_report_t, delta_velocity_y) }, \
+ { "delta_velocity_z", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_gimbal_report_t, delta_velocity_z) }, \
+ { "joint_roll", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_gimbal_report_t, joint_roll) }, \
+ { "joint_el", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_gimbal_report_t, joint_el) }, \
+ { "joint_az", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_gimbal_report_t, joint_az) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_GIMBAL_REPORT { \
+ "GIMBAL_REPORT", \
+ 12, \
+ { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 40, offsetof(mavlink_gimbal_report_t, target_system) }, \
+ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 41, offsetof(mavlink_gimbal_report_t, target_component) }, \
+ { "delta_time", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_gimbal_report_t, delta_time) }, \
+ { "delta_angle_x", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_gimbal_report_t, delta_angle_x) }, \
+ { "delta_angle_y", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_gimbal_report_t, delta_angle_y) }, \
+ { "delta_angle_z", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_gimbal_report_t, delta_angle_z) }, \
+ { "delta_velocity_x", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_gimbal_report_t, delta_velocity_x) }, \
+ { "delta_velocity_y", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_gimbal_report_t, delta_velocity_y) }, \
+ { "delta_velocity_z", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_gimbal_report_t, delta_velocity_z) }, \
+ { "joint_roll", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_gimbal_report_t, joint_roll) }, \
+ { "joint_el", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_gimbal_report_t, joint_el) }, \
+ { "joint_az", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_gimbal_report_t, joint_az) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a gimbal_report 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 target_system System ID.
+ * @param target_component Component ID.
+ * @param delta_time [s] Time since last update.
+ * @param delta_angle_x [rad] Delta angle X.
+ * @param delta_angle_y [rad] Delta angle Y.
+ * @param delta_angle_z [rad] Delta angle X.
+ * @param delta_velocity_x [m/s] Delta velocity X.
+ * @param delta_velocity_y [m/s] Delta velocity Y.
+ * @param delta_velocity_z [m/s] Delta velocity Z.
+ * @param joint_roll [rad] Joint ROLL.
+ * @param joint_el [rad] Joint EL.
+ * @param joint_az [rad] Joint AZ.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_gimbal_report_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint8_t target_system, uint8_t target_component, float delta_time, float delta_angle_x, float delta_angle_y, float delta_angle_z, float delta_velocity_x, float delta_velocity_y, float delta_velocity_z, float joint_roll, float joint_el, float joint_az)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_GIMBAL_REPORT_LEN];
+ _mav_put_float(buf, 0, delta_time);
+ _mav_put_float(buf, 4, delta_angle_x);
+ _mav_put_float(buf, 8, delta_angle_y);
+ _mav_put_float(buf, 12, delta_angle_z);
+ _mav_put_float(buf, 16, delta_velocity_x);
+ _mav_put_float(buf, 20, delta_velocity_y);
+ _mav_put_float(buf, 24, delta_velocity_z);
+ _mav_put_float(buf, 28, joint_roll);
+ _mav_put_float(buf, 32, joint_el);
+ _mav_put_float(buf, 36, joint_az);
+ _mav_put_uint8_t(buf, 40, target_system);
+ _mav_put_uint8_t(buf, 41, target_component);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GIMBAL_REPORT_LEN);
+#else
+ mavlink_gimbal_report_t packet;
+ packet.delta_time = delta_time;
+ packet.delta_angle_x = delta_angle_x;
+ packet.delta_angle_y = delta_angle_y;
+ packet.delta_angle_z = delta_angle_z;
+ packet.delta_velocity_x = delta_velocity_x;
+ packet.delta_velocity_y = delta_velocity_y;
+ packet.delta_velocity_z = delta_velocity_z;
+ packet.joint_roll = joint_roll;
+ packet.joint_el = joint_el;
+ packet.joint_az = joint_az;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GIMBAL_REPORT_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_GIMBAL_REPORT;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GIMBAL_REPORT_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_REPORT_LEN, MAVLINK_MSG_ID_GIMBAL_REPORT_CRC);
+}
+
+/**
+ * @brief Pack a gimbal_report 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 target_system System ID.
+ * @param target_component Component ID.
+ * @param delta_time [s] Time since last update.
+ * @param delta_angle_x [rad] Delta angle X.
+ * @param delta_angle_y [rad] Delta angle Y.
+ * @param delta_angle_z [rad] Delta angle X.
+ * @param delta_velocity_x [m/s] Delta velocity X.
+ * @param delta_velocity_y [m/s] Delta velocity Y.
+ * @param delta_velocity_z [m/s] Delta velocity Z.
+ * @param joint_roll [rad] Joint ROLL.
+ * @param joint_el [rad] Joint EL.
+ * @param joint_az [rad] Joint AZ.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_gimbal_report_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ uint8_t target_system, uint8_t target_component, float delta_time, float delta_angle_x, float delta_angle_y, float delta_angle_z, float delta_velocity_x, float delta_velocity_y, float delta_velocity_z, float joint_roll, float joint_el, float joint_az)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_GIMBAL_REPORT_LEN];
+ _mav_put_float(buf, 0, delta_time);
+ _mav_put_float(buf, 4, delta_angle_x);
+ _mav_put_float(buf, 8, delta_angle_y);
+ _mav_put_float(buf, 12, delta_angle_z);
+ _mav_put_float(buf, 16, delta_velocity_x);
+ _mav_put_float(buf, 20, delta_velocity_y);
+ _mav_put_float(buf, 24, delta_velocity_z);
+ _mav_put_float(buf, 28, joint_roll);
+ _mav_put_float(buf, 32, joint_el);
+ _mav_put_float(buf, 36, joint_az);
+ _mav_put_uint8_t(buf, 40, target_system);
+ _mav_put_uint8_t(buf, 41, target_component);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GIMBAL_REPORT_LEN);
+#else
+ mavlink_gimbal_report_t packet;
+ packet.delta_time = delta_time;
+ packet.delta_angle_x = delta_angle_x;
+ packet.delta_angle_y = delta_angle_y;
+ packet.delta_angle_z = delta_angle_z;
+ packet.delta_velocity_x = delta_velocity_x;
+ packet.delta_velocity_y = delta_velocity_y;
+ packet.delta_velocity_z = delta_velocity_z;
+ packet.joint_roll = joint_roll;
+ packet.joint_el = joint_el;
+ packet.joint_az = joint_az;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GIMBAL_REPORT_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_GIMBAL_REPORT;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_GIMBAL_REPORT_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_REPORT_LEN, MAVLINK_MSG_ID_GIMBAL_REPORT_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_GIMBAL_REPORT_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_REPORT_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a gimbal_report 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 target_system System ID.
+ * @param target_component Component ID.
+ * @param delta_time [s] Time since last update.
+ * @param delta_angle_x [rad] Delta angle X.
+ * @param delta_angle_y [rad] Delta angle Y.
+ * @param delta_angle_z [rad] Delta angle X.
+ * @param delta_velocity_x [m/s] Delta velocity X.
+ * @param delta_velocity_y [m/s] Delta velocity Y.
+ * @param delta_velocity_z [m/s] Delta velocity Z.
+ * @param joint_roll [rad] Joint ROLL.
+ * @param joint_el [rad] Joint EL.
+ * @param joint_az [rad] Joint AZ.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_gimbal_report_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint8_t target_system,uint8_t target_component,float delta_time,float delta_angle_x,float delta_angle_y,float delta_angle_z,float delta_velocity_x,float delta_velocity_y,float delta_velocity_z,float joint_roll,float joint_el,float joint_az)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_GIMBAL_REPORT_LEN];
+ _mav_put_float(buf, 0, delta_time);
+ _mav_put_float(buf, 4, delta_angle_x);
+ _mav_put_float(buf, 8, delta_angle_y);
+ _mav_put_float(buf, 12, delta_angle_z);
+ _mav_put_float(buf, 16, delta_velocity_x);
+ _mav_put_float(buf, 20, delta_velocity_y);
+ _mav_put_float(buf, 24, delta_velocity_z);
+ _mav_put_float(buf, 28, joint_roll);
+ _mav_put_float(buf, 32, joint_el);
+ _mav_put_float(buf, 36, joint_az);
+ _mav_put_uint8_t(buf, 40, target_system);
+ _mav_put_uint8_t(buf, 41, target_component);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GIMBAL_REPORT_LEN);
+#else
+ mavlink_gimbal_report_t packet;
+ packet.delta_time = delta_time;
+ packet.delta_angle_x = delta_angle_x;
+ packet.delta_angle_y = delta_angle_y;
+ packet.delta_angle_z = delta_angle_z;
+ packet.delta_velocity_x = delta_velocity_x;
+ packet.delta_velocity_y = delta_velocity_y;
+ packet.delta_velocity_z = delta_velocity_z;
+ packet.joint_roll = joint_roll;
+ packet.joint_el = joint_el;
+ packet.joint_az = joint_az;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GIMBAL_REPORT_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_GIMBAL_REPORT;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GIMBAL_REPORT_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_REPORT_LEN, MAVLINK_MSG_ID_GIMBAL_REPORT_CRC);
+}
+
+/**
+ * @brief Encode a gimbal_report 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 gimbal_report C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_gimbal_report_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gimbal_report_t* gimbal_report)
+{
+ return mavlink_msg_gimbal_report_pack(system_id, component_id, msg, gimbal_report->target_system, gimbal_report->target_component, gimbal_report->delta_time, gimbal_report->delta_angle_x, gimbal_report->delta_angle_y, gimbal_report->delta_angle_z, gimbal_report->delta_velocity_x, gimbal_report->delta_velocity_y, gimbal_report->delta_velocity_z, gimbal_report->joint_roll, gimbal_report->joint_el, gimbal_report->joint_az);
+}
+
+/**
+ * @brief Encode a gimbal_report 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 gimbal_report C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_gimbal_report_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gimbal_report_t* gimbal_report)
+{
+ return mavlink_msg_gimbal_report_pack_chan(system_id, component_id, chan, msg, gimbal_report->target_system, gimbal_report->target_component, gimbal_report->delta_time, gimbal_report->delta_angle_x, gimbal_report->delta_angle_y, gimbal_report->delta_angle_z, gimbal_report->delta_velocity_x, gimbal_report->delta_velocity_y, gimbal_report->delta_velocity_z, gimbal_report->joint_roll, gimbal_report->joint_el, gimbal_report->joint_az);
+}
+
+/**
+ * @brief Encode a gimbal_report 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 gimbal_report C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_gimbal_report_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_gimbal_report_t* gimbal_report)
+{
+ return mavlink_msg_gimbal_report_pack_status(system_id, component_id, _status, msg, gimbal_report->target_system, gimbal_report->target_component, gimbal_report->delta_time, gimbal_report->delta_angle_x, gimbal_report->delta_angle_y, gimbal_report->delta_angle_z, gimbal_report->delta_velocity_x, gimbal_report->delta_velocity_y, gimbal_report->delta_velocity_z, gimbal_report->joint_roll, gimbal_report->joint_el, gimbal_report->joint_az);
+}
+
+/**
+ * @brief Send a gimbal_report message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param target_system System ID.
+ * @param target_component Component ID.
+ * @param delta_time [s] Time since last update.
+ * @param delta_angle_x [rad] Delta angle X.
+ * @param delta_angle_y [rad] Delta angle Y.
+ * @param delta_angle_z [rad] Delta angle X.
+ * @param delta_velocity_x [m/s] Delta velocity X.
+ * @param delta_velocity_y [m/s] Delta velocity Y.
+ * @param delta_velocity_z [m/s] Delta velocity Z.
+ * @param joint_roll [rad] Joint ROLL.
+ * @param joint_el [rad] Joint EL.
+ * @param joint_az [rad] Joint AZ.
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_gimbal_report_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, float delta_time, float delta_angle_x, float delta_angle_y, float delta_angle_z, float delta_velocity_x, float delta_velocity_y, float delta_velocity_z, float joint_roll, float joint_el, float joint_az)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_GIMBAL_REPORT_LEN];
+ _mav_put_float(buf, 0, delta_time);
+ _mav_put_float(buf, 4, delta_angle_x);
+ _mav_put_float(buf, 8, delta_angle_y);
+ _mav_put_float(buf, 12, delta_angle_z);
+ _mav_put_float(buf, 16, delta_velocity_x);
+ _mav_put_float(buf, 20, delta_velocity_y);
+ _mav_put_float(buf, 24, delta_velocity_z);
+ _mav_put_float(buf, 28, joint_roll);
+ _mav_put_float(buf, 32, joint_el);
+ _mav_put_float(buf, 36, joint_az);
+ _mav_put_uint8_t(buf, 40, target_system);
+ _mav_put_uint8_t(buf, 41, target_component);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_REPORT, buf, MAVLINK_MSG_ID_GIMBAL_REPORT_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_REPORT_LEN, MAVLINK_MSG_ID_GIMBAL_REPORT_CRC);
+#else
+ mavlink_gimbal_report_t packet;
+ packet.delta_time = delta_time;
+ packet.delta_angle_x = delta_angle_x;
+ packet.delta_angle_y = delta_angle_y;
+ packet.delta_angle_z = delta_angle_z;
+ packet.delta_velocity_x = delta_velocity_x;
+ packet.delta_velocity_y = delta_velocity_y;
+ packet.delta_velocity_z = delta_velocity_z;
+ packet.joint_roll = joint_roll;
+ packet.joint_el = joint_el;
+ packet.joint_az = joint_az;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_REPORT, (const char *)&packet, MAVLINK_MSG_ID_GIMBAL_REPORT_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_REPORT_LEN, MAVLINK_MSG_ID_GIMBAL_REPORT_CRC);
+#endif
+}
+
+/**
+ * @brief Send a gimbal_report message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_gimbal_report_send_struct(mavlink_channel_t chan, const mavlink_gimbal_report_t* gimbal_report)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_gimbal_report_send(chan, gimbal_report->target_system, gimbal_report->target_component, gimbal_report->delta_time, gimbal_report->delta_angle_x, gimbal_report->delta_angle_y, gimbal_report->delta_angle_z, gimbal_report->delta_velocity_x, gimbal_report->delta_velocity_y, gimbal_report->delta_velocity_z, gimbal_report->joint_roll, gimbal_report->joint_el, gimbal_report->joint_az);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_REPORT, (const char *)gimbal_report, MAVLINK_MSG_ID_GIMBAL_REPORT_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_REPORT_LEN, MAVLINK_MSG_ID_GIMBAL_REPORT_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_GIMBAL_REPORT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_gimbal_report_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, float delta_time, float delta_angle_x, float delta_angle_y, float delta_angle_z, float delta_velocity_x, float delta_velocity_y, float delta_velocity_z, float joint_roll, float joint_el, float joint_az)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_float(buf, 0, delta_time);
+ _mav_put_float(buf, 4, delta_angle_x);
+ _mav_put_float(buf, 8, delta_angle_y);
+ _mav_put_float(buf, 12, delta_angle_z);
+ _mav_put_float(buf, 16, delta_velocity_x);
+ _mav_put_float(buf, 20, delta_velocity_y);
+ _mav_put_float(buf, 24, delta_velocity_z);
+ _mav_put_float(buf, 28, joint_roll);
+ _mav_put_float(buf, 32, joint_el);
+ _mav_put_float(buf, 36, joint_az);
+ _mav_put_uint8_t(buf, 40, target_system);
+ _mav_put_uint8_t(buf, 41, target_component);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_REPORT, buf, MAVLINK_MSG_ID_GIMBAL_REPORT_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_REPORT_LEN, MAVLINK_MSG_ID_GIMBAL_REPORT_CRC);
+#else
+ mavlink_gimbal_report_t *packet = (mavlink_gimbal_report_t *)msgbuf;
+ packet->delta_time = delta_time;
+ packet->delta_angle_x = delta_angle_x;
+ packet->delta_angle_y = delta_angle_y;
+ packet->delta_angle_z = delta_angle_z;
+ packet->delta_velocity_x = delta_velocity_x;
+ packet->delta_velocity_y = delta_velocity_y;
+ packet->delta_velocity_z = delta_velocity_z;
+ packet->joint_roll = joint_roll;
+ packet->joint_el = joint_el;
+ packet->joint_az = joint_az;
+ packet->target_system = target_system;
+ packet->target_component = target_component;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_REPORT, (const char *)packet, MAVLINK_MSG_ID_GIMBAL_REPORT_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_REPORT_LEN, MAVLINK_MSG_ID_GIMBAL_REPORT_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE GIMBAL_REPORT UNPACKING
+
+
+/**
+ * @brief Get field target_system from gimbal_report message
+ *
+ * @return System ID.
+ */
+static inline uint8_t mavlink_msg_gimbal_report_get_target_system(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 40);
+}
+
+/**
+ * @brief Get field target_component from gimbal_report message
+ *
+ * @return Component ID.
+ */
+static inline uint8_t mavlink_msg_gimbal_report_get_target_component(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 41);
+}
+
+/**
+ * @brief Get field delta_time from gimbal_report message
+ *
+ * @return [s] Time since last update.
+ */
+static inline float mavlink_msg_gimbal_report_get_delta_time(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 0);
+}
+
+/**
+ * @brief Get field delta_angle_x from gimbal_report message
+ *
+ * @return [rad] Delta angle X.
+ */
+static inline float mavlink_msg_gimbal_report_get_delta_angle_x(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 4);
+}
+
+/**
+ * @brief Get field delta_angle_y from gimbal_report message
+ *
+ * @return [rad] Delta angle Y.
+ */
+static inline float mavlink_msg_gimbal_report_get_delta_angle_y(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 8);
+}
+
+/**
+ * @brief Get field delta_angle_z from gimbal_report message
+ *
+ * @return [rad] Delta angle X.
+ */
+static inline float mavlink_msg_gimbal_report_get_delta_angle_z(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 12);
+}
+
+/**
+ * @brief Get field delta_velocity_x from gimbal_report message
+ *
+ * @return [m/s] Delta velocity X.
+ */
+static inline float mavlink_msg_gimbal_report_get_delta_velocity_x(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 16);
+}
+
+/**
+ * @brief Get field delta_velocity_y from gimbal_report message
+ *
+ * @return [m/s] Delta velocity Y.
+ */
+static inline float mavlink_msg_gimbal_report_get_delta_velocity_y(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 20);
+}
+
+/**
+ * @brief Get field delta_velocity_z from gimbal_report message
+ *
+ * @return [m/s] Delta velocity Z.
+ */
+static inline float mavlink_msg_gimbal_report_get_delta_velocity_z(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 24);
+}
+
+/**
+ * @brief Get field joint_roll from gimbal_report message
+ *
+ * @return [rad] Joint ROLL.
+ */
+static inline float mavlink_msg_gimbal_report_get_joint_roll(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 28);
+}
+
+/**
+ * @brief Get field joint_el from gimbal_report message
+ *
+ * @return [rad] Joint EL.
+ */
+static inline float mavlink_msg_gimbal_report_get_joint_el(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 32);
+}
+
+/**
+ * @brief Get field joint_az from gimbal_report message
+ *
+ * @return [rad] Joint AZ.
+ */
+static inline float mavlink_msg_gimbal_report_get_joint_az(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 36);
+}
+
+/**
+ * @brief Decode a gimbal_report message into a struct
+ *
+ * @param msg The message to decode
+ * @param gimbal_report C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_gimbal_report_decode(const mavlink_message_t* msg, mavlink_gimbal_report_t* gimbal_report)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ gimbal_report->delta_time = mavlink_msg_gimbal_report_get_delta_time(msg);
+ gimbal_report->delta_angle_x = mavlink_msg_gimbal_report_get_delta_angle_x(msg);
+ gimbal_report->delta_angle_y = mavlink_msg_gimbal_report_get_delta_angle_y(msg);
+ gimbal_report->delta_angle_z = mavlink_msg_gimbal_report_get_delta_angle_z(msg);
+ gimbal_report->delta_velocity_x = mavlink_msg_gimbal_report_get_delta_velocity_x(msg);
+ gimbal_report->delta_velocity_y = mavlink_msg_gimbal_report_get_delta_velocity_y(msg);
+ gimbal_report->delta_velocity_z = mavlink_msg_gimbal_report_get_delta_velocity_z(msg);
+ gimbal_report->joint_roll = mavlink_msg_gimbal_report_get_joint_roll(msg);
+ gimbal_report->joint_el = mavlink_msg_gimbal_report_get_joint_el(msg);
+ gimbal_report->joint_az = mavlink_msg_gimbal_report_get_joint_az(msg);
+ gimbal_report->target_system = mavlink_msg_gimbal_report_get_target_system(msg);
+ gimbal_report->target_component = mavlink_msg_gimbal_report_get_target_component(msg);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_GIMBAL_REPORT_LEN? msg->len : MAVLINK_MSG_ID_GIMBAL_REPORT_LEN;
+ memset(gimbal_report, 0, MAVLINK_MSG_ID_GIMBAL_REPORT_LEN);
+ memcpy(gimbal_report, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/ardupilotmega/mavlink_msg_gimbal_torque_cmd_report.h b/lib/main/MAVLink/ardupilotmega/mavlink_msg_gimbal_torque_cmd_report.h
new file mode 100644
index 00000000000..18e953ead90
--- /dev/null
+++ b/lib/main/MAVLink/ardupilotmega/mavlink_msg_gimbal_torque_cmd_report.h
@@ -0,0 +1,372 @@
+#pragma once
+// MESSAGE GIMBAL_TORQUE_CMD_REPORT PACKING
+
+#define MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT 214
+
+
+typedef struct __mavlink_gimbal_torque_cmd_report_t {
+ int16_t rl_torque_cmd; /*< Roll Torque Command.*/
+ int16_t el_torque_cmd; /*< Elevation Torque Command.*/
+ int16_t az_torque_cmd; /*< Azimuth Torque Command.*/
+ uint8_t target_system; /*< System ID.*/
+ uint8_t target_component; /*< Component ID.*/
+} mavlink_gimbal_torque_cmd_report_t;
+
+#define MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_LEN 8
+#define MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_MIN_LEN 8
+#define MAVLINK_MSG_ID_214_LEN 8
+#define MAVLINK_MSG_ID_214_MIN_LEN 8
+
+#define MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_CRC 69
+#define MAVLINK_MSG_ID_214_CRC 69
+
+
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_GIMBAL_TORQUE_CMD_REPORT { \
+ 214, \
+ "GIMBAL_TORQUE_CMD_REPORT", \
+ 5, \
+ { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_gimbal_torque_cmd_report_t, target_system) }, \
+ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_gimbal_torque_cmd_report_t, target_component) }, \
+ { "rl_torque_cmd", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_gimbal_torque_cmd_report_t, rl_torque_cmd) }, \
+ { "el_torque_cmd", NULL, MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_gimbal_torque_cmd_report_t, el_torque_cmd) }, \
+ { "az_torque_cmd", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_gimbal_torque_cmd_report_t, az_torque_cmd) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_GIMBAL_TORQUE_CMD_REPORT { \
+ "GIMBAL_TORQUE_CMD_REPORT", \
+ 5, \
+ { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_gimbal_torque_cmd_report_t, target_system) }, \
+ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_gimbal_torque_cmd_report_t, target_component) }, \
+ { "rl_torque_cmd", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_gimbal_torque_cmd_report_t, rl_torque_cmd) }, \
+ { "el_torque_cmd", NULL, MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_gimbal_torque_cmd_report_t, el_torque_cmd) }, \
+ { "az_torque_cmd", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_gimbal_torque_cmd_report_t, az_torque_cmd) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a gimbal_torque_cmd_report 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 target_system System ID.
+ * @param target_component Component ID.
+ * @param rl_torque_cmd Roll Torque Command.
+ * @param el_torque_cmd Elevation Torque Command.
+ * @param az_torque_cmd Azimuth Torque Command.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_gimbal_torque_cmd_report_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint8_t target_system, uint8_t target_component, int16_t rl_torque_cmd, int16_t el_torque_cmd, int16_t az_torque_cmd)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_LEN];
+ _mav_put_int16_t(buf, 0, rl_torque_cmd);
+ _mav_put_int16_t(buf, 2, el_torque_cmd);
+ _mav_put_int16_t(buf, 4, az_torque_cmd);
+ _mav_put_uint8_t(buf, 6, target_system);
+ _mav_put_uint8_t(buf, 7, target_component);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_LEN);
+#else
+ mavlink_gimbal_torque_cmd_report_t packet;
+ packet.rl_torque_cmd = rl_torque_cmd;
+ packet.el_torque_cmd = el_torque_cmd;
+ packet.az_torque_cmd = az_torque_cmd;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_LEN, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_CRC);
+}
+
+/**
+ * @brief Pack a gimbal_torque_cmd_report 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 target_system System ID.
+ * @param target_component Component ID.
+ * @param rl_torque_cmd Roll Torque Command.
+ * @param el_torque_cmd Elevation Torque Command.
+ * @param az_torque_cmd Azimuth Torque Command.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_gimbal_torque_cmd_report_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ uint8_t target_system, uint8_t target_component, int16_t rl_torque_cmd, int16_t el_torque_cmd, int16_t az_torque_cmd)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_LEN];
+ _mav_put_int16_t(buf, 0, rl_torque_cmd);
+ _mav_put_int16_t(buf, 2, el_torque_cmd);
+ _mav_put_int16_t(buf, 4, az_torque_cmd);
+ _mav_put_uint8_t(buf, 6, target_system);
+ _mav_put_uint8_t(buf, 7, target_component);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_LEN);
+#else
+ mavlink_gimbal_torque_cmd_report_t packet;
+ packet.rl_torque_cmd = rl_torque_cmd;
+ packet.el_torque_cmd = el_torque_cmd;
+ packet.az_torque_cmd = az_torque_cmd;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_LEN, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a gimbal_torque_cmd_report 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 target_system System ID.
+ * @param target_component Component ID.
+ * @param rl_torque_cmd Roll Torque Command.
+ * @param el_torque_cmd Elevation Torque Command.
+ * @param az_torque_cmd Azimuth Torque Command.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_gimbal_torque_cmd_report_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint8_t target_system,uint8_t target_component,int16_t rl_torque_cmd,int16_t el_torque_cmd,int16_t az_torque_cmd)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_LEN];
+ _mav_put_int16_t(buf, 0, rl_torque_cmd);
+ _mav_put_int16_t(buf, 2, el_torque_cmd);
+ _mav_put_int16_t(buf, 4, az_torque_cmd);
+ _mav_put_uint8_t(buf, 6, target_system);
+ _mav_put_uint8_t(buf, 7, target_component);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_LEN);
+#else
+ mavlink_gimbal_torque_cmd_report_t packet;
+ packet.rl_torque_cmd = rl_torque_cmd;
+ packet.el_torque_cmd = el_torque_cmd;
+ packet.az_torque_cmd = az_torque_cmd;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_LEN, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_CRC);
+}
+
+/**
+ * @brief Encode a gimbal_torque_cmd_report 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 gimbal_torque_cmd_report C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_gimbal_torque_cmd_report_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gimbal_torque_cmd_report_t* gimbal_torque_cmd_report)
+{
+ return mavlink_msg_gimbal_torque_cmd_report_pack(system_id, component_id, msg, gimbal_torque_cmd_report->target_system, gimbal_torque_cmd_report->target_component, gimbal_torque_cmd_report->rl_torque_cmd, gimbal_torque_cmd_report->el_torque_cmd, gimbal_torque_cmd_report->az_torque_cmd);
+}
+
+/**
+ * @brief Encode a gimbal_torque_cmd_report 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 gimbal_torque_cmd_report C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_gimbal_torque_cmd_report_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gimbal_torque_cmd_report_t* gimbal_torque_cmd_report)
+{
+ return mavlink_msg_gimbal_torque_cmd_report_pack_chan(system_id, component_id, chan, msg, gimbal_torque_cmd_report->target_system, gimbal_torque_cmd_report->target_component, gimbal_torque_cmd_report->rl_torque_cmd, gimbal_torque_cmd_report->el_torque_cmd, gimbal_torque_cmd_report->az_torque_cmd);
+}
+
+/**
+ * @brief Encode a gimbal_torque_cmd_report 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 gimbal_torque_cmd_report C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_gimbal_torque_cmd_report_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_gimbal_torque_cmd_report_t* gimbal_torque_cmd_report)
+{
+ return mavlink_msg_gimbal_torque_cmd_report_pack_status(system_id, component_id, _status, msg, gimbal_torque_cmd_report->target_system, gimbal_torque_cmd_report->target_component, gimbal_torque_cmd_report->rl_torque_cmd, gimbal_torque_cmd_report->el_torque_cmd, gimbal_torque_cmd_report->az_torque_cmd);
+}
+
+/**
+ * @brief Send a gimbal_torque_cmd_report message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param target_system System ID.
+ * @param target_component Component ID.
+ * @param rl_torque_cmd Roll Torque Command.
+ * @param el_torque_cmd Elevation Torque Command.
+ * @param az_torque_cmd Azimuth Torque Command.
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_gimbal_torque_cmd_report_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, int16_t rl_torque_cmd, int16_t el_torque_cmd, int16_t az_torque_cmd)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_LEN];
+ _mav_put_int16_t(buf, 0, rl_torque_cmd);
+ _mav_put_int16_t(buf, 2, el_torque_cmd);
+ _mav_put_int16_t(buf, 4, az_torque_cmd);
+ _mav_put_uint8_t(buf, 6, target_system);
+ _mav_put_uint8_t(buf, 7, target_component);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT, buf, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_LEN, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_CRC);
+#else
+ mavlink_gimbal_torque_cmd_report_t packet;
+ packet.rl_torque_cmd = rl_torque_cmd;
+ packet.el_torque_cmd = el_torque_cmd;
+ packet.az_torque_cmd = az_torque_cmd;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT, (const char *)&packet, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_LEN, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_CRC);
+#endif
+}
+
+/**
+ * @brief Send a gimbal_torque_cmd_report message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_gimbal_torque_cmd_report_send_struct(mavlink_channel_t chan, const mavlink_gimbal_torque_cmd_report_t* gimbal_torque_cmd_report)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_gimbal_torque_cmd_report_send(chan, gimbal_torque_cmd_report->target_system, gimbal_torque_cmd_report->target_component, gimbal_torque_cmd_report->rl_torque_cmd, gimbal_torque_cmd_report->el_torque_cmd, gimbal_torque_cmd_report->az_torque_cmd);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT, (const char *)gimbal_torque_cmd_report, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_LEN, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_gimbal_torque_cmd_report_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, int16_t rl_torque_cmd, int16_t el_torque_cmd, int16_t az_torque_cmd)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_int16_t(buf, 0, rl_torque_cmd);
+ _mav_put_int16_t(buf, 2, el_torque_cmd);
+ _mav_put_int16_t(buf, 4, az_torque_cmd);
+ _mav_put_uint8_t(buf, 6, target_system);
+ _mav_put_uint8_t(buf, 7, target_component);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT, buf, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_LEN, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_CRC);
+#else
+ mavlink_gimbal_torque_cmd_report_t *packet = (mavlink_gimbal_torque_cmd_report_t *)msgbuf;
+ packet->rl_torque_cmd = rl_torque_cmd;
+ packet->el_torque_cmd = el_torque_cmd;
+ packet->az_torque_cmd = az_torque_cmd;
+ packet->target_system = target_system;
+ packet->target_component = target_component;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT, (const char *)packet, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_LEN, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE GIMBAL_TORQUE_CMD_REPORT UNPACKING
+
+
+/**
+ * @brief Get field target_system from gimbal_torque_cmd_report message
+ *
+ * @return System ID.
+ */
+static inline uint8_t mavlink_msg_gimbal_torque_cmd_report_get_target_system(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 6);
+}
+
+/**
+ * @brief Get field target_component from gimbal_torque_cmd_report message
+ *
+ * @return Component ID.
+ */
+static inline uint8_t mavlink_msg_gimbal_torque_cmd_report_get_target_component(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 7);
+}
+
+/**
+ * @brief Get field rl_torque_cmd from gimbal_torque_cmd_report message
+ *
+ * @return Roll Torque Command.
+ */
+static inline int16_t mavlink_msg_gimbal_torque_cmd_report_get_rl_torque_cmd(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_int16_t(msg, 0);
+}
+
+/**
+ * @brief Get field el_torque_cmd from gimbal_torque_cmd_report message
+ *
+ * @return Elevation Torque Command.
+ */
+static inline int16_t mavlink_msg_gimbal_torque_cmd_report_get_el_torque_cmd(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_int16_t(msg, 2);
+}
+
+/**
+ * @brief Get field az_torque_cmd from gimbal_torque_cmd_report message
+ *
+ * @return Azimuth Torque Command.
+ */
+static inline int16_t mavlink_msg_gimbal_torque_cmd_report_get_az_torque_cmd(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_int16_t(msg, 4);
+}
+
+/**
+ * @brief Decode a gimbal_torque_cmd_report message into a struct
+ *
+ * @param msg The message to decode
+ * @param gimbal_torque_cmd_report C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_gimbal_torque_cmd_report_decode(const mavlink_message_t* msg, mavlink_gimbal_torque_cmd_report_t* gimbal_torque_cmd_report)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ gimbal_torque_cmd_report->rl_torque_cmd = mavlink_msg_gimbal_torque_cmd_report_get_rl_torque_cmd(msg);
+ gimbal_torque_cmd_report->el_torque_cmd = mavlink_msg_gimbal_torque_cmd_report_get_el_torque_cmd(msg);
+ gimbal_torque_cmd_report->az_torque_cmd = mavlink_msg_gimbal_torque_cmd_report_get_az_torque_cmd(msg);
+ gimbal_torque_cmd_report->target_system = mavlink_msg_gimbal_torque_cmd_report_get_target_system(msg);
+ gimbal_torque_cmd_report->target_component = mavlink_msg_gimbal_torque_cmd_report_get_target_component(msg);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_LEN? msg->len : MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_LEN;
+ memset(gimbal_torque_cmd_report, 0, MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_LEN);
+ memcpy(gimbal_torque_cmd_report, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/ardupilotmega/mavlink_msg_gopro_get_request.h b/lib/main/MAVLink/ardupilotmega/mavlink_msg_gopro_get_request.h
new file mode 100644
index 00000000000..e0bc01ebe79
--- /dev/null
+++ b/lib/main/MAVLink/ardupilotmega/mavlink_msg_gopro_get_request.h
@@ -0,0 +1,316 @@
+#pragma once
+// MESSAGE GOPRO_GET_REQUEST PACKING
+
+#define MAVLINK_MSG_ID_GOPRO_GET_REQUEST 216
+
+
+typedef struct __mavlink_gopro_get_request_t {
+ uint8_t target_system; /*< System ID.*/
+ uint8_t target_component; /*< Component ID.*/
+ uint8_t cmd_id; /*< Command ID.*/
+} mavlink_gopro_get_request_t;
+
+#define MAVLINK_MSG_ID_GOPRO_GET_REQUEST_LEN 3
+#define MAVLINK_MSG_ID_GOPRO_GET_REQUEST_MIN_LEN 3
+#define MAVLINK_MSG_ID_216_LEN 3
+#define MAVLINK_MSG_ID_216_MIN_LEN 3
+
+#define MAVLINK_MSG_ID_GOPRO_GET_REQUEST_CRC 50
+#define MAVLINK_MSG_ID_216_CRC 50
+
+
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_GOPRO_GET_REQUEST { \
+ 216, \
+ "GOPRO_GET_REQUEST", \
+ 3, \
+ { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_gopro_get_request_t, target_system) }, \
+ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_gopro_get_request_t, target_component) }, \
+ { "cmd_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_gopro_get_request_t, cmd_id) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_GOPRO_GET_REQUEST { \
+ "GOPRO_GET_REQUEST", \
+ 3, \
+ { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_gopro_get_request_t, target_system) }, \
+ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_gopro_get_request_t, target_component) }, \
+ { "cmd_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_gopro_get_request_t, cmd_id) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a gopro_get_request 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 target_system System ID.
+ * @param target_component Component ID.
+ * @param cmd_id Command ID.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_gopro_get_request_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint8_t target_system, uint8_t target_component, uint8_t cmd_id)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_GOPRO_GET_REQUEST_LEN];
+ _mav_put_uint8_t(buf, 0, target_system);
+ _mav_put_uint8_t(buf, 1, target_component);
+ _mav_put_uint8_t(buf, 2, cmd_id);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GOPRO_GET_REQUEST_LEN);
+#else
+ mavlink_gopro_get_request_t packet;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.cmd_id = cmd_id;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GOPRO_GET_REQUEST_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_GOPRO_GET_REQUEST;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GOPRO_GET_REQUEST_MIN_LEN, MAVLINK_MSG_ID_GOPRO_GET_REQUEST_LEN, MAVLINK_MSG_ID_GOPRO_GET_REQUEST_CRC);
+}
+
+/**
+ * @brief Pack a gopro_get_request 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 target_system System ID.
+ * @param target_component Component ID.
+ * @param cmd_id Command ID.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_gopro_get_request_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ uint8_t target_system, uint8_t target_component, uint8_t cmd_id)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_GOPRO_GET_REQUEST_LEN];
+ _mav_put_uint8_t(buf, 0, target_system);
+ _mav_put_uint8_t(buf, 1, target_component);
+ _mav_put_uint8_t(buf, 2, cmd_id);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GOPRO_GET_REQUEST_LEN);
+#else
+ mavlink_gopro_get_request_t packet;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.cmd_id = cmd_id;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GOPRO_GET_REQUEST_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_GOPRO_GET_REQUEST;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_GOPRO_GET_REQUEST_MIN_LEN, MAVLINK_MSG_ID_GOPRO_GET_REQUEST_LEN, MAVLINK_MSG_ID_GOPRO_GET_REQUEST_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_GOPRO_GET_REQUEST_MIN_LEN, MAVLINK_MSG_ID_GOPRO_GET_REQUEST_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a gopro_get_request 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 target_system System ID.
+ * @param target_component Component ID.
+ * @param cmd_id Command ID.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_gopro_get_request_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint8_t target_system,uint8_t target_component,uint8_t cmd_id)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_GOPRO_GET_REQUEST_LEN];
+ _mav_put_uint8_t(buf, 0, target_system);
+ _mav_put_uint8_t(buf, 1, target_component);
+ _mav_put_uint8_t(buf, 2, cmd_id);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GOPRO_GET_REQUEST_LEN);
+#else
+ mavlink_gopro_get_request_t packet;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.cmd_id = cmd_id;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GOPRO_GET_REQUEST_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_GOPRO_GET_REQUEST;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GOPRO_GET_REQUEST_MIN_LEN, MAVLINK_MSG_ID_GOPRO_GET_REQUEST_LEN, MAVLINK_MSG_ID_GOPRO_GET_REQUEST_CRC);
+}
+
+/**
+ * @brief Encode a gopro_get_request 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 gopro_get_request C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_gopro_get_request_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gopro_get_request_t* gopro_get_request)
+{
+ return mavlink_msg_gopro_get_request_pack(system_id, component_id, msg, gopro_get_request->target_system, gopro_get_request->target_component, gopro_get_request->cmd_id);
+}
+
+/**
+ * @brief Encode a gopro_get_request 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 gopro_get_request C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_gopro_get_request_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gopro_get_request_t* gopro_get_request)
+{
+ return mavlink_msg_gopro_get_request_pack_chan(system_id, component_id, chan, msg, gopro_get_request->target_system, gopro_get_request->target_component, gopro_get_request->cmd_id);
+}
+
+/**
+ * @brief Encode a gopro_get_request 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 gopro_get_request C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_gopro_get_request_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_gopro_get_request_t* gopro_get_request)
+{
+ return mavlink_msg_gopro_get_request_pack_status(system_id, component_id, _status, msg, gopro_get_request->target_system, gopro_get_request->target_component, gopro_get_request->cmd_id);
+}
+
+/**
+ * @brief Send a gopro_get_request message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param target_system System ID.
+ * @param target_component Component ID.
+ * @param cmd_id Command ID.
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_gopro_get_request_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t cmd_id)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_GOPRO_GET_REQUEST_LEN];
+ _mav_put_uint8_t(buf, 0, target_system);
+ _mav_put_uint8_t(buf, 1, target_component);
+ _mav_put_uint8_t(buf, 2, cmd_id);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GOPRO_GET_REQUEST, buf, MAVLINK_MSG_ID_GOPRO_GET_REQUEST_MIN_LEN, MAVLINK_MSG_ID_GOPRO_GET_REQUEST_LEN, MAVLINK_MSG_ID_GOPRO_GET_REQUEST_CRC);
+#else
+ mavlink_gopro_get_request_t packet;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.cmd_id = cmd_id;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GOPRO_GET_REQUEST, (const char *)&packet, MAVLINK_MSG_ID_GOPRO_GET_REQUEST_MIN_LEN, MAVLINK_MSG_ID_GOPRO_GET_REQUEST_LEN, MAVLINK_MSG_ID_GOPRO_GET_REQUEST_CRC);
+#endif
+}
+
+/**
+ * @brief Send a gopro_get_request message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_gopro_get_request_send_struct(mavlink_channel_t chan, const mavlink_gopro_get_request_t* gopro_get_request)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_gopro_get_request_send(chan, gopro_get_request->target_system, gopro_get_request->target_component, gopro_get_request->cmd_id);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GOPRO_GET_REQUEST, (const char *)gopro_get_request, MAVLINK_MSG_ID_GOPRO_GET_REQUEST_MIN_LEN, MAVLINK_MSG_ID_GOPRO_GET_REQUEST_LEN, MAVLINK_MSG_ID_GOPRO_GET_REQUEST_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_GOPRO_GET_REQUEST_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_gopro_get_request_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t cmd_id)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint8_t(buf, 0, target_system);
+ _mav_put_uint8_t(buf, 1, target_component);
+ _mav_put_uint8_t(buf, 2, cmd_id);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GOPRO_GET_REQUEST, buf, MAVLINK_MSG_ID_GOPRO_GET_REQUEST_MIN_LEN, MAVLINK_MSG_ID_GOPRO_GET_REQUEST_LEN, MAVLINK_MSG_ID_GOPRO_GET_REQUEST_CRC);
+#else
+ mavlink_gopro_get_request_t *packet = (mavlink_gopro_get_request_t *)msgbuf;
+ packet->target_system = target_system;
+ packet->target_component = target_component;
+ packet->cmd_id = cmd_id;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GOPRO_GET_REQUEST, (const char *)packet, MAVLINK_MSG_ID_GOPRO_GET_REQUEST_MIN_LEN, MAVLINK_MSG_ID_GOPRO_GET_REQUEST_LEN, MAVLINK_MSG_ID_GOPRO_GET_REQUEST_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE GOPRO_GET_REQUEST UNPACKING
+
+
+/**
+ * @brief Get field target_system from gopro_get_request message
+ *
+ * @return System ID.
+ */
+static inline uint8_t mavlink_msg_gopro_get_request_get_target_system(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 0);
+}
+
+/**
+ * @brief Get field target_component from gopro_get_request message
+ *
+ * @return Component ID.
+ */
+static inline uint8_t mavlink_msg_gopro_get_request_get_target_component(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 1);
+}
+
+/**
+ * @brief Get field cmd_id from gopro_get_request message
+ *
+ * @return Command ID.
+ */
+static inline uint8_t mavlink_msg_gopro_get_request_get_cmd_id(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 2);
+}
+
+/**
+ * @brief Decode a gopro_get_request message into a struct
+ *
+ * @param msg The message to decode
+ * @param gopro_get_request C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_gopro_get_request_decode(const mavlink_message_t* msg, mavlink_gopro_get_request_t* gopro_get_request)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ gopro_get_request->target_system = mavlink_msg_gopro_get_request_get_target_system(msg);
+ gopro_get_request->target_component = mavlink_msg_gopro_get_request_get_target_component(msg);
+ gopro_get_request->cmd_id = mavlink_msg_gopro_get_request_get_cmd_id(msg);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_GOPRO_GET_REQUEST_LEN? msg->len : MAVLINK_MSG_ID_GOPRO_GET_REQUEST_LEN;
+ memset(gopro_get_request, 0, MAVLINK_MSG_ID_GOPRO_GET_REQUEST_LEN);
+ memcpy(gopro_get_request, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/ardupilotmega/mavlink_msg_gopro_get_response.h b/lib/main/MAVLink/ardupilotmega/mavlink_msg_gopro_get_response.h
new file mode 100644
index 00000000000..467e608fbb8
--- /dev/null
+++ b/lib/main/MAVLink/ardupilotmega/mavlink_msg_gopro_get_response.h
@@ -0,0 +1,306 @@
+#pragma once
+// MESSAGE GOPRO_GET_RESPONSE PACKING
+
+#define MAVLINK_MSG_ID_GOPRO_GET_RESPONSE 217
+
+
+typedef struct __mavlink_gopro_get_response_t {
+ uint8_t cmd_id; /*< Command ID.*/
+ uint8_t status; /*< Status.*/
+ uint8_t value[4]; /*< Value.*/
+} mavlink_gopro_get_response_t;
+
+#define MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_LEN 6
+#define MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_MIN_LEN 6
+#define MAVLINK_MSG_ID_217_LEN 6
+#define MAVLINK_MSG_ID_217_MIN_LEN 6
+
+#define MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_CRC 202
+#define MAVLINK_MSG_ID_217_CRC 202
+
+#define MAVLINK_MSG_GOPRO_GET_RESPONSE_FIELD_VALUE_LEN 4
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_GOPRO_GET_RESPONSE { \
+ 217, \
+ "GOPRO_GET_RESPONSE", \
+ 3, \
+ { { "cmd_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_gopro_get_response_t, cmd_id) }, \
+ { "status", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_gopro_get_response_t, status) }, \
+ { "value", NULL, MAVLINK_TYPE_UINT8_T, 4, 2, offsetof(mavlink_gopro_get_response_t, value) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_GOPRO_GET_RESPONSE { \
+ "GOPRO_GET_RESPONSE", \
+ 3, \
+ { { "cmd_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_gopro_get_response_t, cmd_id) }, \
+ { "status", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_gopro_get_response_t, status) }, \
+ { "value", NULL, MAVLINK_TYPE_UINT8_T, 4, 2, offsetof(mavlink_gopro_get_response_t, value) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a gopro_get_response 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 cmd_id Command ID.
+ * @param status Status.
+ * @param value Value.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_gopro_get_response_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint8_t cmd_id, uint8_t status, const uint8_t *value)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_LEN];
+ _mav_put_uint8_t(buf, 0, cmd_id);
+ _mav_put_uint8_t(buf, 1, status);
+ _mav_put_uint8_t_array(buf, 2, value, 4);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_LEN);
+#else
+ mavlink_gopro_get_response_t packet;
+ packet.cmd_id = cmd_id;
+ packet.status = status;
+ mav_array_assign_uint8_t(packet.value, value, 4);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_GOPRO_GET_RESPONSE;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_MIN_LEN, MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_LEN, MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_CRC);
+}
+
+/**
+ * @brief Pack a gopro_get_response 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 cmd_id Command ID.
+ * @param status Status.
+ * @param value Value.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_gopro_get_response_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ uint8_t cmd_id, uint8_t status, const uint8_t *value)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_LEN];
+ _mav_put_uint8_t(buf, 0, cmd_id);
+ _mav_put_uint8_t(buf, 1, status);
+ _mav_put_uint8_t_array(buf, 2, value, 4);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_LEN);
+#else
+ mavlink_gopro_get_response_t packet;
+ packet.cmd_id = cmd_id;
+ packet.status = status;
+ mav_array_memcpy(packet.value, value, sizeof(uint8_t)*4);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_GOPRO_GET_RESPONSE;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_MIN_LEN, MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_LEN, MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_MIN_LEN, MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a gopro_get_response 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 cmd_id Command ID.
+ * @param status Status.
+ * @param value Value.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_gopro_get_response_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint8_t cmd_id,uint8_t status,const uint8_t *value)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_LEN];
+ _mav_put_uint8_t(buf, 0, cmd_id);
+ _mav_put_uint8_t(buf, 1, status);
+ _mav_put_uint8_t_array(buf, 2, value, 4);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_LEN);
+#else
+ mavlink_gopro_get_response_t packet;
+ packet.cmd_id = cmd_id;
+ packet.status = status;
+ mav_array_assign_uint8_t(packet.value, value, 4);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_GOPRO_GET_RESPONSE;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_MIN_LEN, MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_LEN, MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_CRC);
+}
+
+/**
+ * @brief Encode a gopro_get_response 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 gopro_get_response C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_gopro_get_response_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gopro_get_response_t* gopro_get_response)
+{
+ return mavlink_msg_gopro_get_response_pack(system_id, component_id, msg, gopro_get_response->cmd_id, gopro_get_response->status, gopro_get_response->value);
+}
+
+/**
+ * @brief Encode a gopro_get_response 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 gopro_get_response C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_gopro_get_response_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gopro_get_response_t* gopro_get_response)
+{
+ return mavlink_msg_gopro_get_response_pack_chan(system_id, component_id, chan, msg, gopro_get_response->cmd_id, gopro_get_response->status, gopro_get_response->value);
+}
+
+/**
+ * @brief Encode a gopro_get_response 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 gopro_get_response C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_gopro_get_response_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_gopro_get_response_t* gopro_get_response)
+{
+ return mavlink_msg_gopro_get_response_pack_status(system_id, component_id, _status, msg, gopro_get_response->cmd_id, gopro_get_response->status, gopro_get_response->value);
+}
+
+/**
+ * @brief Send a gopro_get_response message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param cmd_id Command ID.
+ * @param status Status.
+ * @param value Value.
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_gopro_get_response_send(mavlink_channel_t chan, uint8_t cmd_id, uint8_t status, const uint8_t *value)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_LEN];
+ _mav_put_uint8_t(buf, 0, cmd_id);
+ _mav_put_uint8_t(buf, 1, status);
+ _mav_put_uint8_t_array(buf, 2, value, 4);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GOPRO_GET_RESPONSE, buf, MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_MIN_LEN, MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_LEN, MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_CRC);
+#else
+ mavlink_gopro_get_response_t packet;
+ packet.cmd_id = cmd_id;
+ packet.status = status;
+ mav_array_assign_uint8_t(packet.value, value, 4);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GOPRO_GET_RESPONSE, (const char *)&packet, MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_MIN_LEN, MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_LEN, MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_CRC);
+#endif
+}
+
+/**
+ * @brief Send a gopro_get_response message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_gopro_get_response_send_struct(mavlink_channel_t chan, const mavlink_gopro_get_response_t* gopro_get_response)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_gopro_get_response_send(chan, gopro_get_response->cmd_id, gopro_get_response->status, gopro_get_response->value);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GOPRO_GET_RESPONSE, (const char *)gopro_get_response, MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_MIN_LEN, MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_LEN, MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_gopro_get_response_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t cmd_id, uint8_t status, const uint8_t *value)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint8_t(buf, 0, cmd_id);
+ _mav_put_uint8_t(buf, 1, status);
+ _mav_put_uint8_t_array(buf, 2, value, 4);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GOPRO_GET_RESPONSE, buf, MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_MIN_LEN, MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_LEN, MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_CRC);
+#else
+ mavlink_gopro_get_response_t *packet = (mavlink_gopro_get_response_t *)msgbuf;
+ packet->cmd_id = cmd_id;
+ packet->status = status;
+ mav_array_assign_uint8_t(packet->value, value, 4);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GOPRO_GET_RESPONSE, (const char *)packet, MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_MIN_LEN, MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_LEN, MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE GOPRO_GET_RESPONSE UNPACKING
+
+
+/**
+ * @brief Get field cmd_id from gopro_get_response message
+ *
+ * @return Command ID.
+ */
+static inline uint8_t mavlink_msg_gopro_get_response_get_cmd_id(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 0);
+}
+
+/**
+ * @brief Get field status from gopro_get_response message
+ *
+ * @return Status.
+ */
+static inline uint8_t mavlink_msg_gopro_get_response_get_status(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 1);
+}
+
+/**
+ * @brief Get field value from gopro_get_response message
+ *
+ * @return Value.
+ */
+static inline uint16_t mavlink_msg_gopro_get_response_get_value(const mavlink_message_t* msg, uint8_t *value)
+{
+ return _MAV_RETURN_uint8_t_array(msg, value, 4, 2);
+}
+
+/**
+ * @brief Decode a gopro_get_response message into a struct
+ *
+ * @param msg The message to decode
+ * @param gopro_get_response C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_gopro_get_response_decode(const mavlink_message_t* msg, mavlink_gopro_get_response_t* gopro_get_response)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ gopro_get_response->cmd_id = mavlink_msg_gopro_get_response_get_cmd_id(msg);
+ gopro_get_response->status = mavlink_msg_gopro_get_response_get_status(msg);
+ mavlink_msg_gopro_get_response_get_value(msg, gopro_get_response->value);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_LEN? msg->len : MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_LEN;
+ memset(gopro_get_response, 0, MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_LEN);
+ memcpy(gopro_get_response, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/ardupilotmega/mavlink_msg_gopro_heartbeat.h b/lib/main/MAVLink/ardupilotmega/mavlink_msg_gopro_heartbeat.h
new file mode 100644
index 00000000000..18d5e527001
--- /dev/null
+++ b/lib/main/MAVLink/ardupilotmega/mavlink_msg_gopro_heartbeat.h
@@ -0,0 +1,316 @@
+#pragma once
+// MESSAGE GOPRO_HEARTBEAT PACKING
+
+#define MAVLINK_MSG_ID_GOPRO_HEARTBEAT 215
+
+
+typedef struct __mavlink_gopro_heartbeat_t {
+ uint8_t status; /*< Status.*/
+ uint8_t capture_mode; /*< Current capture mode.*/
+ uint8_t flags; /*< Additional status bits.*/
+} mavlink_gopro_heartbeat_t;
+
+#define MAVLINK_MSG_ID_GOPRO_HEARTBEAT_LEN 3
+#define MAVLINK_MSG_ID_GOPRO_HEARTBEAT_MIN_LEN 3
+#define MAVLINK_MSG_ID_215_LEN 3
+#define MAVLINK_MSG_ID_215_MIN_LEN 3
+
+#define MAVLINK_MSG_ID_GOPRO_HEARTBEAT_CRC 101
+#define MAVLINK_MSG_ID_215_CRC 101
+
+
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_GOPRO_HEARTBEAT { \
+ 215, \
+ "GOPRO_HEARTBEAT", \
+ 3, \
+ { { "status", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_gopro_heartbeat_t, status) }, \
+ { "capture_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_gopro_heartbeat_t, capture_mode) }, \
+ { "flags", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_gopro_heartbeat_t, flags) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_GOPRO_HEARTBEAT { \
+ "GOPRO_HEARTBEAT", \
+ 3, \
+ { { "status", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_gopro_heartbeat_t, status) }, \
+ { "capture_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_gopro_heartbeat_t, capture_mode) }, \
+ { "flags", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_gopro_heartbeat_t, flags) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a gopro_heartbeat 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 status Status.
+ * @param capture_mode Current capture mode.
+ * @param flags Additional status bits.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_gopro_heartbeat_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint8_t status, uint8_t capture_mode, uint8_t flags)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_GOPRO_HEARTBEAT_LEN];
+ _mav_put_uint8_t(buf, 0, status);
+ _mav_put_uint8_t(buf, 1, capture_mode);
+ _mav_put_uint8_t(buf, 2, flags);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GOPRO_HEARTBEAT_LEN);
+#else
+ mavlink_gopro_heartbeat_t packet;
+ packet.status = status;
+ packet.capture_mode = capture_mode;
+ packet.flags = flags;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GOPRO_HEARTBEAT_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_GOPRO_HEARTBEAT;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GOPRO_HEARTBEAT_MIN_LEN, MAVLINK_MSG_ID_GOPRO_HEARTBEAT_LEN, MAVLINK_MSG_ID_GOPRO_HEARTBEAT_CRC);
+}
+
+/**
+ * @brief Pack a gopro_heartbeat 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 status Status.
+ * @param capture_mode Current capture mode.
+ * @param flags Additional status bits.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_gopro_heartbeat_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ uint8_t status, uint8_t capture_mode, uint8_t flags)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_GOPRO_HEARTBEAT_LEN];
+ _mav_put_uint8_t(buf, 0, status);
+ _mav_put_uint8_t(buf, 1, capture_mode);
+ _mav_put_uint8_t(buf, 2, flags);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GOPRO_HEARTBEAT_LEN);
+#else
+ mavlink_gopro_heartbeat_t packet;
+ packet.status = status;
+ packet.capture_mode = capture_mode;
+ packet.flags = flags;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GOPRO_HEARTBEAT_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_GOPRO_HEARTBEAT;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_GOPRO_HEARTBEAT_MIN_LEN, MAVLINK_MSG_ID_GOPRO_HEARTBEAT_LEN, MAVLINK_MSG_ID_GOPRO_HEARTBEAT_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_GOPRO_HEARTBEAT_MIN_LEN, MAVLINK_MSG_ID_GOPRO_HEARTBEAT_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a gopro_heartbeat 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 status Status.
+ * @param capture_mode Current capture mode.
+ * @param flags Additional status bits.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_gopro_heartbeat_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint8_t status,uint8_t capture_mode,uint8_t flags)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_GOPRO_HEARTBEAT_LEN];
+ _mav_put_uint8_t(buf, 0, status);
+ _mav_put_uint8_t(buf, 1, capture_mode);
+ _mav_put_uint8_t(buf, 2, flags);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GOPRO_HEARTBEAT_LEN);
+#else
+ mavlink_gopro_heartbeat_t packet;
+ packet.status = status;
+ packet.capture_mode = capture_mode;
+ packet.flags = flags;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GOPRO_HEARTBEAT_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_GOPRO_HEARTBEAT;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GOPRO_HEARTBEAT_MIN_LEN, MAVLINK_MSG_ID_GOPRO_HEARTBEAT_LEN, MAVLINK_MSG_ID_GOPRO_HEARTBEAT_CRC);
+}
+
+/**
+ * @brief Encode a gopro_heartbeat 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 gopro_heartbeat C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_gopro_heartbeat_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gopro_heartbeat_t* gopro_heartbeat)
+{
+ return mavlink_msg_gopro_heartbeat_pack(system_id, component_id, msg, gopro_heartbeat->status, gopro_heartbeat->capture_mode, gopro_heartbeat->flags);
+}
+
+/**
+ * @brief Encode a gopro_heartbeat 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 gopro_heartbeat C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_gopro_heartbeat_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gopro_heartbeat_t* gopro_heartbeat)
+{
+ return mavlink_msg_gopro_heartbeat_pack_chan(system_id, component_id, chan, msg, gopro_heartbeat->status, gopro_heartbeat->capture_mode, gopro_heartbeat->flags);
+}
+
+/**
+ * @brief Encode a gopro_heartbeat 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 gopro_heartbeat C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_gopro_heartbeat_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_gopro_heartbeat_t* gopro_heartbeat)
+{
+ return mavlink_msg_gopro_heartbeat_pack_status(system_id, component_id, _status, msg, gopro_heartbeat->status, gopro_heartbeat->capture_mode, gopro_heartbeat->flags);
+}
+
+/**
+ * @brief Send a gopro_heartbeat message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param status Status.
+ * @param capture_mode Current capture mode.
+ * @param flags Additional status bits.
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_gopro_heartbeat_send(mavlink_channel_t chan, uint8_t status, uint8_t capture_mode, uint8_t flags)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_GOPRO_HEARTBEAT_LEN];
+ _mav_put_uint8_t(buf, 0, status);
+ _mav_put_uint8_t(buf, 1, capture_mode);
+ _mav_put_uint8_t(buf, 2, flags);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GOPRO_HEARTBEAT, buf, MAVLINK_MSG_ID_GOPRO_HEARTBEAT_MIN_LEN, MAVLINK_MSG_ID_GOPRO_HEARTBEAT_LEN, MAVLINK_MSG_ID_GOPRO_HEARTBEAT_CRC);
+#else
+ mavlink_gopro_heartbeat_t packet;
+ packet.status = status;
+ packet.capture_mode = capture_mode;
+ packet.flags = flags;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GOPRO_HEARTBEAT, (const char *)&packet, MAVLINK_MSG_ID_GOPRO_HEARTBEAT_MIN_LEN, MAVLINK_MSG_ID_GOPRO_HEARTBEAT_LEN, MAVLINK_MSG_ID_GOPRO_HEARTBEAT_CRC);
+#endif
+}
+
+/**
+ * @brief Send a gopro_heartbeat message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_gopro_heartbeat_send_struct(mavlink_channel_t chan, const mavlink_gopro_heartbeat_t* gopro_heartbeat)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_gopro_heartbeat_send(chan, gopro_heartbeat->status, gopro_heartbeat->capture_mode, gopro_heartbeat->flags);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GOPRO_HEARTBEAT, (const char *)gopro_heartbeat, MAVLINK_MSG_ID_GOPRO_HEARTBEAT_MIN_LEN, MAVLINK_MSG_ID_GOPRO_HEARTBEAT_LEN, MAVLINK_MSG_ID_GOPRO_HEARTBEAT_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_GOPRO_HEARTBEAT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_gopro_heartbeat_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t status, uint8_t capture_mode, uint8_t flags)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint8_t(buf, 0, status);
+ _mav_put_uint8_t(buf, 1, capture_mode);
+ _mav_put_uint8_t(buf, 2, flags);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GOPRO_HEARTBEAT, buf, MAVLINK_MSG_ID_GOPRO_HEARTBEAT_MIN_LEN, MAVLINK_MSG_ID_GOPRO_HEARTBEAT_LEN, MAVLINK_MSG_ID_GOPRO_HEARTBEAT_CRC);
+#else
+ mavlink_gopro_heartbeat_t *packet = (mavlink_gopro_heartbeat_t *)msgbuf;
+ packet->status = status;
+ packet->capture_mode = capture_mode;
+ packet->flags = flags;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GOPRO_HEARTBEAT, (const char *)packet, MAVLINK_MSG_ID_GOPRO_HEARTBEAT_MIN_LEN, MAVLINK_MSG_ID_GOPRO_HEARTBEAT_LEN, MAVLINK_MSG_ID_GOPRO_HEARTBEAT_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE GOPRO_HEARTBEAT UNPACKING
+
+
+/**
+ * @brief Get field status from gopro_heartbeat message
+ *
+ * @return Status.
+ */
+static inline uint8_t mavlink_msg_gopro_heartbeat_get_status(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 0);
+}
+
+/**
+ * @brief Get field capture_mode from gopro_heartbeat message
+ *
+ * @return Current capture mode.
+ */
+static inline uint8_t mavlink_msg_gopro_heartbeat_get_capture_mode(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 1);
+}
+
+/**
+ * @brief Get field flags from gopro_heartbeat message
+ *
+ * @return Additional status bits.
+ */
+static inline uint8_t mavlink_msg_gopro_heartbeat_get_flags(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 2);
+}
+
+/**
+ * @brief Decode a gopro_heartbeat message into a struct
+ *
+ * @param msg The message to decode
+ * @param gopro_heartbeat C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_gopro_heartbeat_decode(const mavlink_message_t* msg, mavlink_gopro_heartbeat_t* gopro_heartbeat)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ gopro_heartbeat->status = mavlink_msg_gopro_heartbeat_get_status(msg);
+ gopro_heartbeat->capture_mode = mavlink_msg_gopro_heartbeat_get_capture_mode(msg);
+ gopro_heartbeat->flags = mavlink_msg_gopro_heartbeat_get_flags(msg);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_GOPRO_HEARTBEAT_LEN? msg->len : MAVLINK_MSG_ID_GOPRO_HEARTBEAT_LEN;
+ memset(gopro_heartbeat, 0, MAVLINK_MSG_ID_GOPRO_HEARTBEAT_LEN);
+ memcpy(gopro_heartbeat, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/ardupilotmega/mavlink_msg_gopro_set_request.h b/lib/main/MAVLink/ardupilotmega/mavlink_msg_gopro_set_request.h
new file mode 100644
index 00000000000..a1b85188463
--- /dev/null
+++ b/lib/main/MAVLink/ardupilotmega/mavlink_msg_gopro_set_request.h
@@ -0,0 +1,334 @@
+#pragma once
+// MESSAGE GOPRO_SET_REQUEST PACKING
+
+#define MAVLINK_MSG_ID_GOPRO_SET_REQUEST 218
+
+
+typedef struct __mavlink_gopro_set_request_t {
+ uint8_t target_system; /*< System ID.*/
+ uint8_t target_component; /*< Component ID.*/
+ uint8_t cmd_id; /*< Command ID.*/
+ uint8_t value[4]; /*< Value.*/
+} mavlink_gopro_set_request_t;
+
+#define MAVLINK_MSG_ID_GOPRO_SET_REQUEST_LEN 7
+#define MAVLINK_MSG_ID_GOPRO_SET_REQUEST_MIN_LEN 7
+#define MAVLINK_MSG_ID_218_LEN 7
+#define MAVLINK_MSG_ID_218_MIN_LEN 7
+
+#define MAVLINK_MSG_ID_GOPRO_SET_REQUEST_CRC 17
+#define MAVLINK_MSG_ID_218_CRC 17
+
+#define MAVLINK_MSG_GOPRO_SET_REQUEST_FIELD_VALUE_LEN 4
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_GOPRO_SET_REQUEST { \
+ 218, \
+ "GOPRO_SET_REQUEST", \
+ 4, \
+ { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_gopro_set_request_t, target_system) }, \
+ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_gopro_set_request_t, target_component) }, \
+ { "cmd_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_gopro_set_request_t, cmd_id) }, \
+ { "value", NULL, MAVLINK_TYPE_UINT8_T, 4, 3, offsetof(mavlink_gopro_set_request_t, value) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_GOPRO_SET_REQUEST { \
+ "GOPRO_SET_REQUEST", \
+ 4, \
+ { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_gopro_set_request_t, target_system) }, \
+ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_gopro_set_request_t, target_component) }, \
+ { "cmd_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_gopro_set_request_t, cmd_id) }, \
+ { "value", NULL, MAVLINK_TYPE_UINT8_T, 4, 3, offsetof(mavlink_gopro_set_request_t, value) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a gopro_set_request 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 target_system System ID.
+ * @param target_component Component ID.
+ * @param cmd_id Command ID.
+ * @param value Value.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_gopro_set_request_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint8_t target_system, uint8_t target_component, uint8_t cmd_id, const uint8_t *value)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_GOPRO_SET_REQUEST_LEN];
+ _mav_put_uint8_t(buf, 0, target_system);
+ _mav_put_uint8_t(buf, 1, target_component);
+ _mav_put_uint8_t(buf, 2, cmd_id);
+ _mav_put_uint8_t_array(buf, 3, value, 4);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GOPRO_SET_REQUEST_LEN);
+#else
+ mavlink_gopro_set_request_t packet;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.cmd_id = cmd_id;
+ mav_array_assign_uint8_t(packet.value, value, 4);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GOPRO_SET_REQUEST_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_GOPRO_SET_REQUEST;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GOPRO_SET_REQUEST_MIN_LEN, MAVLINK_MSG_ID_GOPRO_SET_REQUEST_LEN, MAVLINK_MSG_ID_GOPRO_SET_REQUEST_CRC);
+}
+
+/**
+ * @brief Pack a gopro_set_request 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 target_system System ID.
+ * @param target_component Component ID.
+ * @param cmd_id Command ID.
+ * @param value Value.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_gopro_set_request_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ uint8_t target_system, uint8_t target_component, uint8_t cmd_id, const uint8_t *value)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_GOPRO_SET_REQUEST_LEN];
+ _mav_put_uint8_t(buf, 0, target_system);
+ _mav_put_uint8_t(buf, 1, target_component);
+ _mav_put_uint8_t(buf, 2, cmd_id);
+ _mav_put_uint8_t_array(buf, 3, value, 4);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GOPRO_SET_REQUEST_LEN);
+#else
+ mavlink_gopro_set_request_t packet;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.cmd_id = cmd_id;
+ mav_array_memcpy(packet.value, value, sizeof(uint8_t)*4);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GOPRO_SET_REQUEST_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_GOPRO_SET_REQUEST;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_GOPRO_SET_REQUEST_MIN_LEN, MAVLINK_MSG_ID_GOPRO_SET_REQUEST_LEN, MAVLINK_MSG_ID_GOPRO_SET_REQUEST_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_GOPRO_SET_REQUEST_MIN_LEN, MAVLINK_MSG_ID_GOPRO_SET_REQUEST_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a gopro_set_request 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 target_system System ID.
+ * @param target_component Component ID.
+ * @param cmd_id Command ID.
+ * @param value Value.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_gopro_set_request_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint8_t target_system,uint8_t target_component,uint8_t cmd_id,const uint8_t *value)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_GOPRO_SET_REQUEST_LEN];
+ _mav_put_uint8_t(buf, 0, target_system);
+ _mav_put_uint8_t(buf, 1, target_component);
+ _mav_put_uint8_t(buf, 2, cmd_id);
+ _mav_put_uint8_t_array(buf, 3, value, 4);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GOPRO_SET_REQUEST_LEN);
+#else
+ mavlink_gopro_set_request_t packet;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.cmd_id = cmd_id;
+ mav_array_assign_uint8_t(packet.value, value, 4);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GOPRO_SET_REQUEST_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_GOPRO_SET_REQUEST;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GOPRO_SET_REQUEST_MIN_LEN, MAVLINK_MSG_ID_GOPRO_SET_REQUEST_LEN, MAVLINK_MSG_ID_GOPRO_SET_REQUEST_CRC);
+}
+
+/**
+ * @brief Encode a gopro_set_request 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 gopro_set_request C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_gopro_set_request_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gopro_set_request_t* gopro_set_request)
+{
+ return mavlink_msg_gopro_set_request_pack(system_id, component_id, msg, gopro_set_request->target_system, gopro_set_request->target_component, gopro_set_request->cmd_id, gopro_set_request->value);
+}
+
+/**
+ * @brief Encode a gopro_set_request 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 gopro_set_request C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_gopro_set_request_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gopro_set_request_t* gopro_set_request)
+{
+ return mavlink_msg_gopro_set_request_pack_chan(system_id, component_id, chan, msg, gopro_set_request->target_system, gopro_set_request->target_component, gopro_set_request->cmd_id, gopro_set_request->value);
+}
+
+/**
+ * @brief Encode a gopro_set_request 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 gopro_set_request C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_gopro_set_request_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_gopro_set_request_t* gopro_set_request)
+{
+ return mavlink_msg_gopro_set_request_pack_status(system_id, component_id, _status, msg, gopro_set_request->target_system, gopro_set_request->target_component, gopro_set_request->cmd_id, gopro_set_request->value);
+}
+
+/**
+ * @brief Send a gopro_set_request message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param target_system System ID.
+ * @param target_component Component ID.
+ * @param cmd_id Command ID.
+ * @param value Value.
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_gopro_set_request_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t cmd_id, const uint8_t *value)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_GOPRO_SET_REQUEST_LEN];
+ _mav_put_uint8_t(buf, 0, target_system);
+ _mav_put_uint8_t(buf, 1, target_component);
+ _mav_put_uint8_t(buf, 2, cmd_id);
+ _mav_put_uint8_t_array(buf, 3, value, 4);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GOPRO_SET_REQUEST, buf, MAVLINK_MSG_ID_GOPRO_SET_REQUEST_MIN_LEN, MAVLINK_MSG_ID_GOPRO_SET_REQUEST_LEN, MAVLINK_MSG_ID_GOPRO_SET_REQUEST_CRC);
+#else
+ mavlink_gopro_set_request_t packet;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.cmd_id = cmd_id;
+ mav_array_assign_uint8_t(packet.value, value, 4);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GOPRO_SET_REQUEST, (const char *)&packet, MAVLINK_MSG_ID_GOPRO_SET_REQUEST_MIN_LEN, MAVLINK_MSG_ID_GOPRO_SET_REQUEST_LEN, MAVLINK_MSG_ID_GOPRO_SET_REQUEST_CRC);
+#endif
+}
+
+/**
+ * @brief Send a gopro_set_request message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_gopro_set_request_send_struct(mavlink_channel_t chan, const mavlink_gopro_set_request_t* gopro_set_request)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_gopro_set_request_send(chan, gopro_set_request->target_system, gopro_set_request->target_component, gopro_set_request->cmd_id, gopro_set_request->value);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GOPRO_SET_REQUEST, (const char *)gopro_set_request, MAVLINK_MSG_ID_GOPRO_SET_REQUEST_MIN_LEN, MAVLINK_MSG_ID_GOPRO_SET_REQUEST_LEN, MAVLINK_MSG_ID_GOPRO_SET_REQUEST_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_GOPRO_SET_REQUEST_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_gopro_set_request_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t cmd_id, const uint8_t *value)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint8_t(buf, 0, target_system);
+ _mav_put_uint8_t(buf, 1, target_component);
+ _mav_put_uint8_t(buf, 2, cmd_id);
+ _mav_put_uint8_t_array(buf, 3, value, 4);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GOPRO_SET_REQUEST, buf, MAVLINK_MSG_ID_GOPRO_SET_REQUEST_MIN_LEN, MAVLINK_MSG_ID_GOPRO_SET_REQUEST_LEN, MAVLINK_MSG_ID_GOPRO_SET_REQUEST_CRC);
+#else
+ mavlink_gopro_set_request_t *packet = (mavlink_gopro_set_request_t *)msgbuf;
+ packet->target_system = target_system;
+ packet->target_component = target_component;
+ packet->cmd_id = cmd_id;
+ mav_array_assign_uint8_t(packet->value, value, 4);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GOPRO_SET_REQUEST, (const char *)packet, MAVLINK_MSG_ID_GOPRO_SET_REQUEST_MIN_LEN, MAVLINK_MSG_ID_GOPRO_SET_REQUEST_LEN, MAVLINK_MSG_ID_GOPRO_SET_REQUEST_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE GOPRO_SET_REQUEST UNPACKING
+
+
+/**
+ * @brief Get field target_system from gopro_set_request message
+ *
+ * @return System ID.
+ */
+static inline uint8_t mavlink_msg_gopro_set_request_get_target_system(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 0);
+}
+
+/**
+ * @brief Get field target_component from gopro_set_request message
+ *
+ * @return Component ID.
+ */
+static inline uint8_t mavlink_msg_gopro_set_request_get_target_component(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 1);
+}
+
+/**
+ * @brief Get field cmd_id from gopro_set_request message
+ *
+ * @return Command ID.
+ */
+static inline uint8_t mavlink_msg_gopro_set_request_get_cmd_id(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 2);
+}
+
+/**
+ * @brief Get field value from gopro_set_request message
+ *
+ * @return Value.
+ */
+static inline uint16_t mavlink_msg_gopro_set_request_get_value(const mavlink_message_t* msg, uint8_t *value)
+{
+ return _MAV_RETURN_uint8_t_array(msg, value, 4, 3);
+}
+
+/**
+ * @brief Decode a gopro_set_request message into a struct
+ *
+ * @param msg The message to decode
+ * @param gopro_set_request C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_gopro_set_request_decode(const mavlink_message_t* msg, mavlink_gopro_set_request_t* gopro_set_request)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ gopro_set_request->target_system = mavlink_msg_gopro_set_request_get_target_system(msg);
+ gopro_set_request->target_component = mavlink_msg_gopro_set_request_get_target_component(msg);
+ gopro_set_request->cmd_id = mavlink_msg_gopro_set_request_get_cmd_id(msg);
+ mavlink_msg_gopro_set_request_get_value(msg, gopro_set_request->value);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_GOPRO_SET_REQUEST_LEN? msg->len : MAVLINK_MSG_ID_GOPRO_SET_REQUEST_LEN;
+ memset(gopro_set_request, 0, MAVLINK_MSG_ID_GOPRO_SET_REQUEST_LEN);
+ memcpy(gopro_set_request, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/ardupilotmega/mavlink_msg_gopro_set_response.h b/lib/main/MAVLink/ardupilotmega/mavlink_msg_gopro_set_response.h
new file mode 100644
index 00000000000..4cf7b118f67
--- /dev/null
+++ b/lib/main/MAVLink/ardupilotmega/mavlink_msg_gopro_set_response.h
@@ -0,0 +1,288 @@
+#pragma once
+// MESSAGE GOPRO_SET_RESPONSE PACKING
+
+#define MAVLINK_MSG_ID_GOPRO_SET_RESPONSE 219
+
+
+typedef struct __mavlink_gopro_set_response_t {
+ uint8_t cmd_id; /*< Command ID.*/
+ uint8_t status; /*< Status.*/
+} mavlink_gopro_set_response_t;
+
+#define MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_LEN 2
+#define MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_MIN_LEN 2
+#define MAVLINK_MSG_ID_219_LEN 2
+#define MAVLINK_MSG_ID_219_MIN_LEN 2
+
+#define MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_CRC 162
+#define MAVLINK_MSG_ID_219_CRC 162
+
+
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_GOPRO_SET_RESPONSE { \
+ 219, \
+ "GOPRO_SET_RESPONSE", \
+ 2, \
+ { { "cmd_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_gopro_set_response_t, cmd_id) }, \
+ { "status", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_gopro_set_response_t, status) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_GOPRO_SET_RESPONSE { \
+ "GOPRO_SET_RESPONSE", \
+ 2, \
+ { { "cmd_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_gopro_set_response_t, cmd_id) }, \
+ { "status", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_gopro_set_response_t, status) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a gopro_set_response 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 cmd_id Command ID.
+ * @param status Status.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_gopro_set_response_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint8_t cmd_id, uint8_t status)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_LEN];
+ _mav_put_uint8_t(buf, 0, cmd_id);
+ _mav_put_uint8_t(buf, 1, status);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_LEN);
+#else
+ mavlink_gopro_set_response_t packet;
+ packet.cmd_id = cmd_id;
+ packet.status = status;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_GOPRO_SET_RESPONSE;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_MIN_LEN, MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_LEN, MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_CRC);
+}
+
+/**
+ * @brief Pack a gopro_set_response 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 cmd_id Command ID.
+ * @param status Status.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_gopro_set_response_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ uint8_t cmd_id, uint8_t status)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_LEN];
+ _mav_put_uint8_t(buf, 0, cmd_id);
+ _mav_put_uint8_t(buf, 1, status);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_LEN);
+#else
+ mavlink_gopro_set_response_t packet;
+ packet.cmd_id = cmd_id;
+ packet.status = status;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_GOPRO_SET_RESPONSE;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_MIN_LEN, MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_LEN, MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_MIN_LEN, MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a gopro_set_response 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 cmd_id Command ID.
+ * @param status Status.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_gopro_set_response_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint8_t cmd_id,uint8_t status)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_LEN];
+ _mav_put_uint8_t(buf, 0, cmd_id);
+ _mav_put_uint8_t(buf, 1, status);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_LEN);
+#else
+ mavlink_gopro_set_response_t packet;
+ packet.cmd_id = cmd_id;
+ packet.status = status;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_GOPRO_SET_RESPONSE;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_MIN_LEN, MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_LEN, MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_CRC);
+}
+
+/**
+ * @brief Encode a gopro_set_response 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 gopro_set_response C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_gopro_set_response_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gopro_set_response_t* gopro_set_response)
+{
+ return mavlink_msg_gopro_set_response_pack(system_id, component_id, msg, gopro_set_response->cmd_id, gopro_set_response->status);
+}
+
+/**
+ * @brief Encode a gopro_set_response 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 gopro_set_response C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_gopro_set_response_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gopro_set_response_t* gopro_set_response)
+{
+ return mavlink_msg_gopro_set_response_pack_chan(system_id, component_id, chan, msg, gopro_set_response->cmd_id, gopro_set_response->status);
+}
+
+/**
+ * @brief Encode a gopro_set_response 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 gopro_set_response C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_gopro_set_response_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_gopro_set_response_t* gopro_set_response)
+{
+ return mavlink_msg_gopro_set_response_pack_status(system_id, component_id, _status, msg, gopro_set_response->cmd_id, gopro_set_response->status);
+}
+
+/**
+ * @brief Send a gopro_set_response message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param cmd_id Command ID.
+ * @param status Status.
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_gopro_set_response_send(mavlink_channel_t chan, uint8_t cmd_id, uint8_t status)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_LEN];
+ _mav_put_uint8_t(buf, 0, cmd_id);
+ _mav_put_uint8_t(buf, 1, status);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GOPRO_SET_RESPONSE, buf, MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_MIN_LEN, MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_LEN, MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_CRC);
+#else
+ mavlink_gopro_set_response_t packet;
+ packet.cmd_id = cmd_id;
+ packet.status = status;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GOPRO_SET_RESPONSE, (const char *)&packet, MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_MIN_LEN, MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_LEN, MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_CRC);
+#endif
+}
+
+/**
+ * @brief Send a gopro_set_response message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_gopro_set_response_send_struct(mavlink_channel_t chan, const mavlink_gopro_set_response_t* gopro_set_response)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_gopro_set_response_send(chan, gopro_set_response->cmd_id, gopro_set_response->status);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GOPRO_SET_RESPONSE, (const char *)gopro_set_response, MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_MIN_LEN, MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_LEN, MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_gopro_set_response_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t cmd_id, uint8_t status)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint8_t(buf, 0, cmd_id);
+ _mav_put_uint8_t(buf, 1, status);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GOPRO_SET_RESPONSE, buf, MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_MIN_LEN, MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_LEN, MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_CRC);
+#else
+ mavlink_gopro_set_response_t *packet = (mavlink_gopro_set_response_t *)msgbuf;
+ packet->cmd_id = cmd_id;
+ packet->status = status;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GOPRO_SET_RESPONSE, (const char *)packet, MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_MIN_LEN, MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_LEN, MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE GOPRO_SET_RESPONSE UNPACKING
+
+
+/**
+ * @brief Get field cmd_id from gopro_set_response message
+ *
+ * @return Command ID.
+ */
+static inline uint8_t mavlink_msg_gopro_set_response_get_cmd_id(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 0);
+}
+
+/**
+ * @brief Get field status from gopro_set_response message
+ *
+ * @return Status.
+ */
+static inline uint8_t mavlink_msg_gopro_set_response_get_status(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 1);
+}
+
+/**
+ * @brief Decode a gopro_set_response message into a struct
+ *
+ * @param msg The message to decode
+ * @param gopro_set_response C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_gopro_set_response_decode(const mavlink_message_t* msg, mavlink_gopro_set_response_t* gopro_set_response)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ gopro_set_response->cmd_id = mavlink_msg_gopro_set_response_get_cmd_id(msg);
+ gopro_set_response->status = mavlink_msg_gopro_set_response_get_status(msg);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_LEN? msg->len : MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_LEN;
+ memset(gopro_set_response, 0, MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_LEN);
+ memcpy(gopro_set_response, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/ardupilotmega/mavlink_msg_hwstatus.h b/lib/main/MAVLink/ardupilotmega/mavlink_msg_hwstatus.h
new file mode 100644
index 00000000000..28b230ced7b
--- /dev/null
+++ b/lib/main/MAVLink/ardupilotmega/mavlink_msg_hwstatus.h
@@ -0,0 +1,288 @@
+#pragma once
+// MESSAGE HWSTATUS PACKING
+
+#define MAVLINK_MSG_ID_HWSTATUS 165
+
+
+typedef struct __mavlink_hwstatus_t {
+ uint16_t Vcc; /*< [mV] Board voltage.*/
+ uint8_t I2Cerr; /*< I2C error count.*/
+} mavlink_hwstatus_t;
+
+#define MAVLINK_MSG_ID_HWSTATUS_LEN 3
+#define MAVLINK_MSG_ID_HWSTATUS_MIN_LEN 3
+#define MAVLINK_MSG_ID_165_LEN 3
+#define MAVLINK_MSG_ID_165_MIN_LEN 3
+
+#define MAVLINK_MSG_ID_HWSTATUS_CRC 21
+#define MAVLINK_MSG_ID_165_CRC 21
+
+
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_HWSTATUS { \
+ 165, \
+ "HWSTATUS", \
+ 2, \
+ { { "Vcc", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_hwstatus_t, Vcc) }, \
+ { "I2Cerr", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_hwstatus_t, I2Cerr) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_HWSTATUS { \
+ "HWSTATUS", \
+ 2, \
+ { { "Vcc", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_hwstatus_t, Vcc) }, \
+ { "I2Cerr", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_hwstatus_t, I2Cerr) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a hwstatus 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 Vcc [mV] Board voltage.
+ * @param I2Cerr I2C error count.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_hwstatus_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint16_t Vcc, uint8_t I2Cerr)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_HWSTATUS_LEN];
+ _mav_put_uint16_t(buf, 0, Vcc);
+ _mav_put_uint8_t(buf, 2, I2Cerr);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HWSTATUS_LEN);
+#else
+ mavlink_hwstatus_t packet;
+ packet.Vcc = Vcc;
+ packet.I2Cerr = I2Cerr;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HWSTATUS_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_HWSTATUS;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HWSTATUS_MIN_LEN, MAVLINK_MSG_ID_HWSTATUS_LEN, MAVLINK_MSG_ID_HWSTATUS_CRC);
+}
+
+/**
+ * @brief Pack a hwstatus 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 Vcc [mV] Board voltage.
+ * @param I2Cerr I2C error count.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_hwstatus_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ uint16_t Vcc, uint8_t I2Cerr)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_HWSTATUS_LEN];
+ _mav_put_uint16_t(buf, 0, Vcc);
+ _mav_put_uint8_t(buf, 2, I2Cerr);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HWSTATUS_LEN);
+#else
+ mavlink_hwstatus_t packet;
+ packet.Vcc = Vcc;
+ packet.I2Cerr = I2Cerr;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HWSTATUS_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_HWSTATUS;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_HWSTATUS_MIN_LEN, MAVLINK_MSG_ID_HWSTATUS_LEN, MAVLINK_MSG_ID_HWSTATUS_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_HWSTATUS_MIN_LEN, MAVLINK_MSG_ID_HWSTATUS_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a hwstatus 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 Vcc [mV] Board voltage.
+ * @param I2Cerr I2C error count.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_hwstatus_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint16_t Vcc,uint8_t I2Cerr)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_HWSTATUS_LEN];
+ _mav_put_uint16_t(buf, 0, Vcc);
+ _mav_put_uint8_t(buf, 2, I2Cerr);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HWSTATUS_LEN);
+#else
+ mavlink_hwstatus_t packet;
+ packet.Vcc = Vcc;
+ packet.I2Cerr = I2Cerr;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HWSTATUS_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_HWSTATUS;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HWSTATUS_MIN_LEN, MAVLINK_MSG_ID_HWSTATUS_LEN, MAVLINK_MSG_ID_HWSTATUS_CRC);
+}
+
+/**
+ * @brief Encode a hwstatus 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 hwstatus C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_hwstatus_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_hwstatus_t* hwstatus)
+{
+ return mavlink_msg_hwstatus_pack(system_id, component_id, msg, hwstatus->Vcc, hwstatus->I2Cerr);
+}
+
+/**
+ * @brief Encode a hwstatus 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 hwstatus C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_hwstatus_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_hwstatus_t* hwstatus)
+{
+ return mavlink_msg_hwstatus_pack_chan(system_id, component_id, chan, msg, hwstatus->Vcc, hwstatus->I2Cerr);
+}
+
+/**
+ * @brief Encode a hwstatus 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 hwstatus C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_hwstatus_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_hwstatus_t* hwstatus)
+{
+ return mavlink_msg_hwstatus_pack_status(system_id, component_id, _status, msg, hwstatus->Vcc, hwstatus->I2Cerr);
+}
+
+/**
+ * @brief Send a hwstatus message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param Vcc [mV] Board voltage.
+ * @param I2Cerr I2C error count.
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_hwstatus_send(mavlink_channel_t chan, uint16_t Vcc, uint8_t I2Cerr)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_HWSTATUS_LEN];
+ _mav_put_uint16_t(buf, 0, Vcc);
+ _mav_put_uint8_t(buf, 2, I2Cerr);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HWSTATUS, buf, MAVLINK_MSG_ID_HWSTATUS_MIN_LEN, MAVLINK_MSG_ID_HWSTATUS_LEN, MAVLINK_MSG_ID_HWSTATUS_CRC);
+#else
+ mavlink_hwstatus_t packet;
+ packet.Vcc = Vcc;
+ packet.I2Cerr = I2Cerr;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HWSTATUS, (const char *)&packet, MAVLINK_MSG_ID_HWSTATUS_MIN_LEN, MAVLINK_MSG_ID_HWSTATUS_LEN, MAVLINK_MSG_ID_HWSTATUS_CRC);
+#endif
+}
+
+/**
+ * @brief Send a hwstatus message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_hwstatus_send_struct(mavlink_channel_t chan, const mavlink_hwstatus_t* hwstatus)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_hwstatus_send(chan, hwstatus->Vcc, hwstatus->I2Cerr);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HWSTATUS, (const char *)hwstatus, MAVLINK_MSG_ID_HWSTATUS_MIN_LEN, MAVLINK_MSG_ID_HWSTATUS_LEN, MAVLINK_MSG_ID_HWSTATUS_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_HWSTATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_hwstatus_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t Vcc, uint8_t I2Cerr)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint16_t(buf, 0, Vcc);
+ _mav_put_uint8_t(buf, 2, I2Cerr);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HWSTATUS, buf, MAVLINK_MSG_ID_HWSTATUS_MIN_LEN, MAVLINK_MSG_ID_HWSTATUS_LEN, MAVLINK_MSG_ID_HWSTATUS_CRC);
+#else
+ mavlink_hwstatus_t *packet = (mavlink_hwstatus_t *)msgbuf;
+ packet->Vcc = Vcc;
+ packet->I2Cerr = I2Cerr;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HWSTATUS, (const char *)packet, MAVLINK_MSG_ID_HWSTATUS_MIN_LEN, MAVLINK_MSG_ID_HWSTATUS_LEN, MAVLINK_MSG_ID_HWSTATUS_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE HWSTATUS UNPACKING
+
+
+/**
+ * @brief Get field Vcc from hwstatus message
+ *
+ * @return [mV] Board voltage.
+ */
+static inline uint16_t mavlink_msg_hwstatus_get_Vcc(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 0);
+}
+
+/**
+ * @brief Get field I2Cerr from hwstatus message
+ *
+ * @return I2C error count.
+ */
+static inline uint8_t mavlink_msg_hwstatus_get_I2Cerr(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 2);
+}
+
+/**
+ * @brief Decode a hwstatus message into a struct
+ *
+ * @param msg The message to decode
+ * @param hwstatus C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_hwstatus_decode(const mavlink_message_t* msg, mavlink_hwstatus_t* hwstatus)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ hwstatus->Vcc = mavlink_msg_hwstatus_get_Vcc(msg);
+ hwstatus->I2Cerr = mavlink_msg_hwstatus_get_I2Cerr(msg);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_HWSTATUS_LEN? msg->len : MAVLINK_MSG_ID_HWSTATUS_LEN;
+ memset(hwstatus, 0, MAVLINK_MSG_ID_HWSTATUS_LEN);
+ memcpy(hwstatus, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/ardupilotmega/mavlink_msg_led_control.h b/lib/main/MAVLink/ardupilotmega/mavlink_msg_led_control.h
new file mode 100644
index 00000000000..e3bf6722d55
--- /dev/null
+++ b/lib/main/MAVLink/ardupilotmega/mavlink_msg_led_control.h
@@ -0,0 +1,390 @@
+#pragma once
+// MESSAGE LED_CONTROL PACKING
+
+#define MAVLINK_MSG_ID_LED_CONTROL 186
+
+
+typedef struct __mavlink_led_control_t {
+ uint8_t target_system; /*< System ID.*/
+ uint8_t target_component; /*< Component ID.*/
+ uint8_t instance; /*< Instance (LED instance to control or 255 for all LEDs).*/
+ uint8_t pattern; /*< Pattern (see LED_PATTERN_ENUM).*/
+ uint8_t custom_len; /*< Custom Byte Length.*/
+ uint8_t custom_bytes[24]; /*< Custom Bytes.*/
+} mavlink_led_control_t;
+
+#define MAVLINK_MSG_ID_LED_CONTROL_LEN 29
+#define MAVLINK_MSG_ID_LED_CONTROL_MIN_LEN 29
+#define MAVLINK_MSG_ID_186_LEN 29
+#define MAVLINK_MSG_ID_186_MIN_LEN 29
+
+#define MAVLINK_MSG_ID_LED_CONTROL_CRC 72
+#define MAVLINK_MSG_ID_186_CRC 72
+
+#define MAVLINK_MSG_LED_CONTROL_FIELD_CUSTOM_BYTES_LEN 24
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_LED_CONTROL { \
+ 186, \
+ "LED_CONTROL", \
+ 6, \
+ { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_led_control_t, target_system) }, \
+ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_led_control_t, target_component) }, \
+ { "instance", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_led_control_t, instance) }, \
+ { "pattern", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_led_control_t, pattern) }, \
+ { "custom_len", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_led_control_t, custom_len) }, \
+ { "custom_bytes", NULL, MAVLINK_TYPE_UINT8_T, 24, 5, offsetof(mavlink_led_control_t, custom_bytes) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_LED_CONTROL { \
+ "LED_CONTROL", \
+ 6, \
+ { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_led_control_t, target_system) }, \
+ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_led_control_t, target_component) }, \
+ { "instance", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_led_control_t, instance) }, \
+ { "pattern", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_led_control_t, pattern) }, \
+ { "custom_len", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_led_control_t, custom_len) }, \
+ { "custom_bytes", NULL, MAVLINK_TYPE_UINT8_T, 24, 5, offsetof(mavlink_led_control_t, custom_bytes) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a led_control 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 target_system System ID.
+ * @param target_component Component ID.
+ * @param instance Instance (LED instance to control or 255 for all LEDs).
+ * @param pattern Pattern (see LED_PATTERN_ENUM).
+ * @param custom_len Custom Byte Length.
+ * @param custom_bytes Custom Bytes.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_led_control_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint8_t target_system, uint8_t target_component, uint8_t instance, uint8_t pattern, uint8_t custom_len, const uint8_t *custom_bytes)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_LED_CONTROL_LEN];
+ _mav_put_uint8_t(buf, 0, target_system);
+ _mav_put_uint8_t(buf, 1, target_component);
+ _mav_put_uint8_t(buf, 2, instance);
+ _mav_put_uint8_t(buf, 3, pattern);
+ _mav_put_uint8_t(buf, 4, custom_len);
+ _mav_put_uint8_t_array(buf, 5, custom_bytes, 24);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LED_CONTROL_LEN);
+#else
+ mavlink_led_control_t packet;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.instance = instance;
+ packet.pattern = pattern;
+ packet.custom_len = custom_len;
+ mav_array_assign_uint8_t(packet.custom_bytes, custom_bytes, 24);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LED_CONTROL_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_LED_CONTROL;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LED_CONTROL_MIN_LEN, MAVLINK_MSG_ID_LED_CONTROL_LEN, MAVLINK_MSG_ID_LED_CONTROL_CRC);
+}
+
+/**
+ * @brief Pack a led_control 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 target_system System ID.
+ * @param target_component Component ID.
+ * @param instance Instance (LED instance to control or 255 for all LEDs).
+ * @param pattern Pattern (see LED_PATTERN_ENUM).
+ * @param custom_len Custom Byte Length.
+ * @param custom_bytes Custom Bytes.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_led_control_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ uint8_t target_system, uint8_t target_component, uint8_t instance, uint8_t pattern, uint8_t custom_len, const uint8_t *custom_bytes)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_LED_CONTROL_LEN];
+ _mav_put_uint8_t(buf, 0, target_system);
+ _mav_put_uint8_t(buf, 1, target_component);
+ _mav_put_uint8_t(buf, 2, instance);
+ _mav_put_uint8_t(buf, 3, pattern);
+ _mav_put_uint8_t(buf, 4, custom_len);
+ _mav_put_uint8_t_array(buf, 5, custom_bytes, 24);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LED_CONTROL_LEN);
+#else
+ mavlink_led_control_t packet;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.instance = instance;
+ packet.pattern = pattern;
+ packet.custom_len = custom_len;
+ mav_array_memcpy(packet.custom_bytes, custom_bytes, sizeof(uint8_t)*24);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LED_CONTROL_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_LED_CONTROL;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_LED_CONTROL_MIN_LEN, MAVLINK_MSG_ID_LED_CONTROL_LEN, MAVLINK_MSG_ID_LED_CONTROL_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_LED_CONTROL_MIN_LEN, MAVLINK_MSG_ID_LED_CONTROL_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a led_control 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 target_system System ID.
+ * @param target_component Component ID.
+ * @param instance Instance (LED instance to control or 255 for all LEDs).
+ * @param pattern Pattern (see LED_PATTERN_ENUM).
+ * @param custom_len Custom Byte Length.
+ * @param custom_bytes Custom Bytes.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_led_control_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint8_t target_system,uint8_t target_component,uint8_t instance,uint8_t pattern,uint8_t custom_len,const uint8_t *custom_bytes)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_LED_CONTROL_LEN];
+ _mav_put_uint8_t(buf, 0, target_system);
+ _mav_put_uint8_t(buf, 1, target_component);
+ _mav_put_uint8_t(buf, 2, instance);
+ _mav_put_uint8_t(buf, 3, pattern);
+ _mav_put_uint8_t(buf, 4, custom_len);
+ _mav_put_uint8_t_array(buf, 5, custom_bytes, 24);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LED_CONTROL_LEN);
+#else
+ mavlink_led_control_t packet;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.instance = instance;
+ packet.pattern = pattern;
+ packet.custom_len = custom_len;
+ mav_array_assign_uint8_t(packet.custom_bytes, custom_bytes, 24);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LED_CONTROL_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_LED_CONTROL;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LED_CONTROL_MIN_LEN, MAVLINK_MSG_ID_LED_CONTROL_LEN, MAVLINK_MSG_ID_LED_CONTROL_CRC);
+}
+
+/**
+ * @brief Encode a led_control 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 led_control C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_led_control_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_led_control_t* led_control)
+{
+ return mavlink_msg_led_control_pack(system_id, component_id, msg, led_control->target_system, led_control->target_component, led_control->instance, led_control->pattern, led_control->custom_len, led_control->custom_bytes);
+}
+
+/**
+ * @brief Encode a led_control 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 led_control C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_led_control_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_led_control_t* led_control)
+{
+ return mavlink_msg_led_control_pack_chan(system_id, component_id, chan, msg, led_control->target_system, led_control->target_component, led_control->instance, led_control->pattern, led_control->custom_len, led_control->custom_bytes);
+}
+
+/**
+ * @brief Encode a led_control 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 led_control C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_led_control_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_led_control_t* led_control)
+{
+ return mavlink_msg_led_control_pack_status(system_id, component_id, _status, msg, led_control->target_system, led_control->target_component, led_control->instance, led_control->pattern, led_control->custom_len, led_control->custom_bytes);
+}
+
+/**
+ * @brief Send a led_control message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param target_system System ID.
+ * @param target_component Component ID.
+ * @param instance Instance (LED instance to control or 255 for all LEDs).
+ * @param pattern Pattern (see LED_PATTERN_ENUM).
+ * @param custom_len Custom Byte Length.
+ * @param custom_bytes Custom Bytes.
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_led_control_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t instance, uint8_t pattern, uint8_t custom_len, const uint8_t *custom_bytes)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_LED_CONTROL_LEN];
+ _mav_put_uint8_t(buf, 0, target_system);
+ _mav_put_uint8_t(buf, 1, target_component);
+ _mav_put_uint8_t(buf, 2, instance);
+ _mav_put_uint8_t(buf, 3, pattern);
+ _mav_put_uint8_t(buf, 4, custom_len);
+ _mav_put_uint8_t_array(buf, 5, custom_bytes, 24);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LED_CONTROL, buf, MAVLINK_MSG_ID_LED_CONTROL_MIN_LEN, MAVLINK_MSG_ID_LED_CONTROL_LEN, MAVLINK_MSG_ID_LED_CONTROL_CRC);
+#else
+ mavlink_led_control_t packet;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.instance = instance;
+ packet.pattern = pattern;
+ packet.custom_len = custom_len;
+ mav_array_assign_uint8_t(packet.custom_bytes, custom_bytes, 24);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LED_CONTROL, (const char *)&packet, MAVLINK_MSG_ID_LED_CONTROL_MIN_LEN, MAVLINK_MSG_ID_LED_CONTROL_LEN, MAVLINK_MSG_ID_LED_CONTROL_CRC);
+#endif
+}
+
+/**
+ * @brief Send a led_control message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_led_control_send_struct(mavlink_channel_t chan, const mavlink_led_control_t* led_control)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_led_control_send(chan, led_control->target_system, led_control->target_component, led_control->instance, led_control->pattern, led_control->custom_len, led_control->custom_bytes);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LED_CONTROL, (const char *)led_control, MAVLINK_MSG_ID_LED_CONTROL_MIN_LEN, MAVLINK_MSG_ID_LED_CONTROL_LEN, MAVLINK_MSG_ID_LED_CONTROL_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_LED_CONTROL_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_led_control_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t instance, uint8_t pattern, uint8_t custom_len, const uint8_t *custom_bytes)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint8_t(buf, 0, target_system);
+ _mav_put_uint8_t(buf, 1, target_component);
+ _mav_put_uint8_t(buf, 2, instance);
+ _mav_put_uint8_t(buf, 3, pattern);
+ _mav_put_uint8_t(buf, 4, custom_len);
+ _mav_put_uint8_t_array(buf, 5, custom_bytes, 24);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LED_CONTROL, buf, MAVLINK_MSG_ID_LED_CONTROL_MIN_LEN, MAVLINK_MSG_ID_LED_CONTROL_LEN, MAVLINK_MSG_ID_LED_CONTROL_CRC);
+#else
+ mavlink_led_control_t *packet = (mavlink_led_control_t *)msgbuf;
+ packet->target_system = target_system;
+ packet->target_component = target_component;
+ packet->instance = instance;
+ packet->pattern = pattern;
+ packet->custom_len = custom_len;
+ mav_array_assign_uint8_t(packet->custom_bytes, custom_bytes, 24);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LED_CONTROL, (const char *)packet, MAVLINK_MSG_ID_LED_CONTROL_MIN_LEN, MAVLINK_MSG_ID_LED_CONTROL_LEN, MAVLINK_MSG_ID_LED_CONTROL_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE LED_CONTROL UNPACKING
+
+
+/**
+ * @brief Get field target_system from led_control message
+ *
+ * @return System ID.
+ */
+static inline uint8_t mavlink_msg_led_control_get_target_system(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 0);
+}
+
+/**
+ * @brief Get field target_component from led_control message
+ *
+ * @return Component ID.
+ */
+static inline uint8_t mavlink_msg_led_control_get_target_component(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 1);
+}
+
+/**
+ * @brief Get field instance from led_control message
+ *
+ * @return Instance (LED instance to control or 255 for all LEDs).
+ */
+static inline uint8_t mavlink_msg_led_control_get_instance(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 2);
+}
+
+/**
+ * @brief Get field pattern from led_control message
+ *
+ * @return Pattern (see LED_PATTERN_ENUM).
+ */
+static inline uint8_t mavlink_msg_led_control_get_pattern(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 3);
+}
+
+/**
+ * @brief Get field custom_len from led_control message
+ *
+ * @return Custom Byte Length.
+ */
+static inline uint8_t mavlink_msg_led_control_get_custom_len(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 4);
+}
+
+/**
+ * @brief Get field custom_bytes from led_control message
+ *
+ * @return Custom Bytes.
+ */
+static inline uint16_t mavlink_msg_led_control_get_custom_bytes(const mavlink_message_t* msg, uint8_t *custom_bytes)
+{
+ return _MAV_RETURN_uint8_t_array(msg, custom_bytes, 24, 5);
+}
+
+/**
+ * @brief Decode a led_control message into a struct
+ *
+ * @param msg The message to decode
+ * @param led_control C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_led_control_decode(const mavlink_message_t* msg, mavlink_led_control_t* led_control)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ led_control->target_system = mavlink_msg_led_control_get_target_system(msg);
+ led_control->target_component = mavlink_msg_led_control_get_target_component(msg);
+ led_control->instance = mavlink_msg_led_control_get_instance(msg);
+ led_control->pattern = mavlink_msg_led_control_get_pattern(msg);
+ led_control->custom_len = mavlink_msg_led_control_get_custom_len(msg);
+ mavlink_msg_led_control_get_custom_bytes(msg, led_control->custom_bytes);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_LED_CONTROL_LEN? msg->len : MAVLINK_MSG_ID_LED_CONTROL_LEN;
+ memset(led_control, 0, MAVLINK_MSG_ID_LED_CONTROL_LEN);
+ memcpy(led_control, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/ardupilotmega/mavlink_msg_limits_status.h b/lib/main/MAVLink/ardupilotmega/mavlink_msg_limits_status.h
new file mode 100644
index 00000000000..0710a48b29a
--- /dev/null
+++ b/lib/main/MAVLink/ardupilotmega/mavlink_msg_limits_status.h
@@ -0,0 +1,484 @@
+#pragma once
+// MESSAGE LIMITS_STATUS PACKING
+
+#define MAVLINK_MSG_ID_LIMITS_STATUS 167
+
+
+typedef struct __mavlink_limits_status_t {
+ uint32_t last_trigger; /*< [ms] Time (since boot) of last breach.*/
+ uint32_t last_action; /*< [ms] Time (since boot) of last recovery action.*/
+ uint32_t last_recovery; /*< [ms] Time (since boot) of last successful recovery.*/
+ uint32_t last_clear; /*< [ms] Time (since boot) of last all-clear.*/
+ uint16_t breach_count; /*< Number of fence breaches.*/
+ uint8_t limits_state; /*< State of AP_Limits.*/
+ uint8_t mods_enabled; /*< AP_Limit_Module bitfield of enabled modules.*/
+ uint8_t mods_required; /*< AP_Limit_Module bitfield of required modules.*/
+ uint8_t mods_triggered; /*< AP_Limit_Module bitfield of triggered modules.*/
+} mavlink_limits_status_t;
+
+#define MAVLINK_MSG_ID_LIMITS_STATUS_LEN 22
+#define MAVLINK_MSG_ID_LIMITS_STATUS_MIN_LEN 22
+#define MAVLINK_MSG_ID_167_LEN 22
+#define MAVLINK_MSG_ID_167_MIN_LEN 22
+
+#define MAVLINK_MSG_ID_LIMITS_STATUS_CRC 144
+#define MAVLINK_MSG_ID_167_CRC 144
+
+
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_LIMITS_STATUS { \
+ 167, \
+ "LIMITS_STATUS", \
+ 9, \
+ { { "limits_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 18, offsetof(mavlink_limits_status_t, limits_state) }, \
+ { "last_trigger", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_limits_status_t, last_trigger) }, \
+ { "last_action", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_limits_status_t, last_action) }, \
+ { "last_recovery", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_limits_status_t, last_recovery) }, \
+ { "last_clear", NULL, MAVLINK_TYPE_UINT32_T, 0, 12, offsetof(mavlink_limits_status_t, last_clear) }, \
+ { "breach_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_limits_status_t, breach_count) }, \
+ { "mods_enabled", NULL, MAVLINK_TYPE_UINT8_T, 0, 19, offsetof(mavlink_limits_status_t, mods_enabled) }, \
+ { "mods_required", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_limits_status_t, mods_required) }, \
+ { "mods_triggered", NULL, MAVLINK_TYPE_UINT8_T, 0, 21, offsetof(mavlink_limits_status_t, mods_triggered) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_LIMITS_STATUS { \
+ "LIMITS_STATUS", \
+ 9, \
+ { { "limits_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 18, offsetof(mavlink_limits_status_t, limits_state) }, \
+ { "last_trigger", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_limits_status_t, last_trigger) }, \
+ { "last_action", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_limits_status_t, last_action) }, \
+ { "last_recovery", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_limits_status_t, last_recovery) }, \
+ { "last_clear", NULL, MAVLINK_TYPE_UINT32_T, 0, 12, offsetof(mavlink_limits_status_t, last_clear) }, \
+ { "breach_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_limits_status_t, breach_count) }, \
+ { "mods_enabled", NULL, MAVLINK_TYPE_UINT8_T, 0, 19, offsetof(mavlink_limits_status_t, mods_enabled) }, \
+ { "mods_required", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_limits_status_t, mods_required) }, \
+ { "mods_triggered", NULL, MAVLINK_TYPE_UINT8_T, 0, 21, offsetof(mavlink_limits_status_t, mods_triggered) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a limits_status 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 limits_state State of AP_Limits.
+ * @param last_trigger [ms] Time (since boot) of last breach.
+ * @param last_action [ms] Time (since boot) of last recovery action.
+ * @param last_recovery [ms] Time (since boot) of last successful recovery.
+ * @param last_clear [ms] Time (since boot) of last all-clear.
+ * @param breach_count Number of fence breaches.
+ * @param mods_enabled AP_Limit_Module bitfield of enabled modules.
+ * @param mods_required AP_Limit_Module bitfield of required modules.
+ * @param mods_triggered AP_Limit_Module bitfield of triggered modules.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_limits_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint8_t limits_state, uint32_t last_trigger, uint32_t last_action, uint32_t last_recovery, uint32_t last_clear, uint16_t breach_count, uint8_t mods_enabled, uint8_t mods_required, uint8_t mods_triggered)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_LIMITS_STATUS_LEN];
+ _mav_put_uint32_t(buf, 0, last_trigger);
+ _mav_put_uint32_t(buf, 4, last_action);
+ _mav_put_uint32_t(buf, 8, last_recovery);
+ _mav_put_uint32_t(buf, 12, last_clear);
+ _mav_put_uint16_t(buf, 16, breach_count);
+ _mav_put_uint8_t(buf, 18, limits_state);
+ _mav_put_uint8_t(buf, 19, mods_enabled);
+ _mav_put_uint8_t(buf, 20, mods_required);
+ _mav_put_uint8_t(buf, 21, mods_triggered);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LIMITS_STATUS_LEN);
+#else
+ mavlink_limits_status_t packet;
+ packet.last_trigger = last_trigger;
+ packet.last_action = last_action;
+ packet.last_recovery = last_recovery;
+ packet.last_clear = last_clear;
+ packet.breach_count = breach_count;
+ packet.limits_state = limits_state;
+ packet.mods_enabled = mods_enabled;
+ packet.mods_required = mods_required;
+ packet.mods_triggered = mods_triggered;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LIMITS_STATUS_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_LIMITS_STATUS;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LIMITS_STATUS_MIN_LEN, MAVLINK_MSG_ID_LIMITS_STATUS_LEN, MAVLINK_MSG_ID_LIMITS_STATUS_CRC);
+}
+
+/**
+ * @brief Pack a limits_status 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 limits_state State of AP_Limits.
+ * @param last_trigger [ms] Time (since boot) of last breach.
+ * @param last_action [ms] Time (since boot) of last recovery action.
+ * @param last_recovery [ms] Time (since boot) of last successful recovery.
+ * @param last_clear [ms] Time (since boot) of last all-clear.
+ * @param breach_count Number of fence breaches.
+ * @param mods_enabled AP_Limit_Module bitfield of enabled modules.
+ * @param mods_required AP_Limit_Module bitfield of required modules.
+ * @param mods_triggered AP_Limit_Module bitfield of triggered modules.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_limits_status_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ uint8_t limits_state, uint32_t last_trigger, uint32_t last_action, uint32_t last_recovery, uint32_t last_clear, uint16_t breach_count, uint8_t mods_enabled, uint8_t mods_required, uint8_t mods_triggered)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_LIMITS_STATUS_LEN];
+ _mav_put_uint32_t(buf, 0, last_trigger);
+ _mav_put_uint32_t(buf, 4, last_action);
+ _mav_put_uint32_t(buf, 8, last_recovery);
+ _mav_put_uint32_t(buf, 12, last_clear);
+ _mav_put_uint16_t(buf, 16, breach_count);
+ _mav_put_uint8_t(buf, 18, limits_state);
+ _mav_put_uint8_t(buf, 19, mods_enabled);
+ _mav_put_uint8_t(buf, 20, mods_required);
+ _mav_put_uint8_t(buf, 21, mods_triggered);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LIMITS_STATUS_LEN);
+#else
+ mavlink_limits_status_t packet;
+ packet.last_trigger = last_trigger;
+ packet.last_action = last_action;
+ packet.last_recovery = last_recovery;
+ packet.last_clear = last_clear;
+ packet.breach_count = breach_count;
+ packet.limits_state = limits_state;
+ packet.mods_enabled = mods_enabled;
+ packet.mods_required = mods_required;
+ packet.mods_triggered = mods_triggered;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LIMITS_STATUS_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_LIMITS_STATUS;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_LIMITS_STATUS_MIN_LEN, MAVLINK_MSG_ID_LIMITS_STATUS_LEN, MAVLINK_MSG_ID_LIMITS_STATUS_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_LIMITS_STATUS_MIN_LEN, MAVLINK_MSG_ID_LIMITS_STATUS_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a limits_status 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 limits_state State of AP_Limits.
+ * @param last_trigger [ms] Time (since boot) of last breach.
+ * @param last_action [ms] Time (since boot) of last recovery action.
+ * @param last_recovery [ms] Time (since boot) of last successful recovery.
+ * @param last_clear [ms] Time (since boot) of last all-clear.
+ * @param breach_count Number of fence breaches.
+ * @param mods_enabled AP_Limit_Module bitfield of enabled modules.
+ * @param mods_required AP_Limit_Module bitfield of required modules.
+ * @param mods_triggered AP_Limit_Module bitfield of triggered modules.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_limits_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint8_t limits_state,uint32_t last_trigger,uint32_t last_action,uint32_t last_recovery,uint32_t last_clear,uint16_t breach_count,uint8_t mods_enabled,uint8_t mods_required,uint8_t mods_triggered)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_LIMITS_STATUS_LEN];
+ _mav_put_uint32_t(buf, 0, last_trigger);
+ _mav_put_uint32_t(buf, 4, last_action);
+ _mav_put_uint32_t(buf, 8, last_recovery);
+ _mav_put_uint32_t(buf, 12, last_clear);
+ _mav_put_uint16_t(buf, 16, breach_count);
+ _mav_put_uint8_t(buf, 18, limits_state);
+ _mav_put_uint8_t(buf, 19, mods_enabled);
+ _mav_put_uint8_t(buf, 20, mods_required);
+ _mav_put_uint8_t(buf, 21, mods_triggered);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LIMITS_STATUS_LEN);
+#else
+ mavlink_limits_status_t packet;
+ packet.last_trigger = last_trigger;
+ packet.last_action = last_action;
+ packet.last_recovery = last_recovery;
+ packet.last_clear = last_clear;
+ packet.breach_count = breach_count;
+ packet.limits_state = limits_state;
+ packet.mods_enabled = mods_enabled;
+ packet.mods_required = mods_required;
+ packet.mods_triggered = mods_triggered;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LIMITS_STATUS_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_LIMITS_STATUS;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LIMITS_STATUS_MIN_LEN, MAVLINK_MSG_ID_LIMITS_STATUS_LEN, MAVLINK_MSG_ID_LIMITS_STATUS_CRC);
+}
+
+/**
+ * @brief Encode a limits_status 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 limits_status C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_limits_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_limits_status_t* limits_status)
+{
+ return mavlink_msg_limits_status_pack(system_id, component_id, msg, limits_status->limits_state, limits_status->last_trigger, limits_status->last_action, limits_status->last_recovery, limits_status->last_clear, limits_status->breach_count, limits_status->mods_enabled, limits_status->mods_required, limits_status->mods_triggered);
+}
+
+/**
+ * @brief Encode a limits_status 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 limits_status C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_limits_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_limits_status_t* limits_status)
+{
+ return mavlink_msg_limits_status_pack_chan(system_id, component_id, chan, msg, limits_status->limits_state, limits_status->last_trigger, limits_status->last_action, limits_status->last_recovery, limits_status->last_clear, limits_status->breach_count, limits_status->mods_enabled, limits_status->mods_required, limits_status->mods_triggered);
+}
+
+/**
+ * @brief Encode a limits_status 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 limits_status C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_limits_status_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_limits_status_t* limits_status)
+{
+ return mavlink_msg_limits_status_pack_status(system_id, component_id, _status, msg, limits_status->limits_state, limits_status->last_trigger, limits_status->last_action, limits_status->last_recovery, limits_status->last_clear, limits_status->breach_count, limits_status->mods_enabled, limits_status->mods_required, limits_status->mods_triggered);
+}
+
+/**
+ * @brief Send a limits_status message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param limits_state State of AP_Limits.
+ * @param last_trigger [ms] Time (since boot) of last breach.
+ * @param last_action [ms] Time (since boot) of last recovery action.
+ * @param last_recovery [ms] Time (since boot) of last successful recovery.
+ * @param last_clear [ms] Time (since boot) of last all-clear.
+ * @param breach_count Number of fence breaches.
+ * @param mods_enabled AP_Limit_Module bitfield of enabled modules.
+ * @param mods_required AP_Limit_Module bitfield of required modules.
+ * @param mods_triggered AP_Limit_Module bitfield of triggered modules.
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_limits_status_send(mavlink_channel_t chan, uint8_t limits_state, uint32_t last_trigger, uint32_t last_action, uint32_t last_recovery, uint32_t last_clear, uint16_t breach_count, uint8_t mods_enabled, uint8_t mods_required, uint8_t mods_triggered)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_LIMITS_STATUS_LEN];
+ _mav_put_uint32_t(buf, 0, last_trigger);
+ _mav_put_uint32_t(buf, 4, last_action);
+ _mav_put_uint32_t(buf, 8, last_recovery);
+ _mav_put_uint32_t(buf, 12, last_clear);
+ _mav_put_uint16_t(buf, 16, breach_count);
+ _mav_put_uint8_t(buf, 18, limits_state);
+ _mav_put_uint8_t(buf, 19, mods_enabled);
+ _mav_put_uint8_t(buf, 20, mods_required);
+ _mav_put_uint8_t(buf, 21, mods_triggered);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LIMITS_STATUS, buf, MAVLINK_MSG_ID_LIMITS_STATUS_MIN_LEN, MAVLINK_MSG_ID_LIMITS_STATUS_LEN, MAVLINK_MSG_ID_LIMITS_STATUS_CRC);
+#else
+ mavlink_limits_status_t packet;
+ packet.last_trigger = last_trigger;
+ packet.last_action = last_action;
+ packet.last_recovery = last_recovery;
+ packet.last_clear = last_clear;
+ packet.breach_count = breach_count;
+ packet.limits_state = limits_state;
+ packet.mods_enabled = mods_enabled;
+ packet.mods_required = mods_required;
+ packet.mods_triggered = mods_triggered;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LIMITS_STATUS, (const char *)&packet, MAVLINK_MSG_ID_LIMITS_STATUS_MIN_LEN, MAVLINK_MSG_ID_LIMITS_STATUS_LEN, MAVLINK_MSG_ID_LIMITS_STATUS_CRC);
+#endif
+}
+
+/**
+ * @brief Send a limits_status message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_limits_status_send_struct(mavlink_channel_t chan, const mavlink_limits_status_t* limits_status)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_limits_status_send(chan, limits_status->limits_state, limits_status->last_trigger, limits_status->last_action, limits_status->last_recovery, limits_status->last_clear, limits_status->breach_count, limits_status->mods_enabled, limits_status->mods_required, limits_status->mods_triggered);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LIMITS_STATUS, (const char *)limits_status, MAVLINK_MSG_ID_LIMITS_STATUS_MIN_LEN, MAVLINK_MSG_ID_LIMITS_STATUS_LEN, MAVLINK_MSG_ID_LIMITS_STATUS_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_LIMITS_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_limits_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t limits_state, uint32_t last_trigger, uint32_t last_action, uint32_t last_recovery, uint32_t last_clear, uint16_t breach_count, uint8_t mods_enabled, uint8_t mods_required, uint8_t mods_triggered)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint32_t(buf, 0, last_trigger);
+ _mav_put_uint32_t(buf, 4, last_action);
+ _mav_put_uint32_t(buf, 8, last_recovery);
+ _mav_put_uint32_t(buf, 12, last_clear);
+ _mav_put_uint16_t(buf, 16, breach_count);
+ _mav_put_uint8_t(buf, 18, limits_state);
+ _mav_put_uint8_t(buf, 19, mods_enabled);
+ _mav_put_uint8_t(buf, 20, mods_required);
+ _mav_put_uint8_t(buf, 21, mods_triggered);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LIMITS_STATUS, buf, MAVLINK_MSG_ID_LIMITS_STATUS_MIN_LEN, MAVLINK_MSG_ID_LIMITS_STATUS_LEN, MAVLINK_MSG_ID_LIMITS_STATUS_CRC);
+#else
+ mavlink_limits_status_t *packet = (mavlink_limits_status_t *)msgbuf;
+ packet->last_trigger = last_trigger;
+ packet->last_action = last_action;
+ packet->last_recovery = last_recovery;
+ packet->last_clear = last_clear;
+ packet->breach_count = breach_count;
+ packet->limits_state = limits_state;
+ packet->mods_enabled = mods_enabled;
+ packet->mods_required = mods_required;
+ packet->mods_triggered = mods_triggered;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LIMITS_STATUS, (const char *)packet, MAVLINK_MSG_ID_LIMITS_STATUS_MIN_LEN, MAVLINK_MSG_ID_LIMITS_STATUS_LEN, MAVLINK_MSG_ID_LIMITS_STATUS_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE LIMITS_STATUS UNPACKING
+
+
+/**
+ * @brief Get field limits_state from limits_status message
+ *
+ * @return State of AP_Limits.
+ */
+static inline uint8_t mavlink_msg_limits_status_get_limits_state(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 18);
+}
+
+/**
+ * @brief Get field last_trigger from limits_status message
+ *
+ * @return [ms] Time (since boot) of last breach.
+ */
+static inline uint32_t mavlink_msg_limits_status_get_last_trigger(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint32_t(msg, 0);
+}
+
+/**
+ * @brief Get field last_action from limits_status message
+ *
+ * @return [ms] Time (since boot) of last recovery action.
+ */
+static inline uint32_t mavlink_msg_limits_status_get_last_action(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint32_t(msg, 4);
+}
+
+/**
+ * @brief Get field last_recovery from limits_status message
+ *
+ * @return [ms] Time (since boot) of last successful recovery.
+ */
+static inline uint32_t mavlink_msg_limits_status_get_last_recovery(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint32_t(msg, 8);
+}
+
+/**
+ * @brief Get field last_clear from limits_status message
+ *
+ * @return [ms] Time (since boot) of last all-clear.
+ */
+static inline uint32_t mavlink_msg_limits_status_get_last_clear(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint32_t(msg, 12);
+}
+
+/**
+ * @brief Get field breach_count from limits_status message
+ *
+ * @return Number of fence breaches.
+ */
+static inline uint16_t mavlink_msg_limits_status_get_breach_count(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 16);
+}
+
+/**
+ * @brief Get field mods_enabled from limits_status message
+ *
+ * @return AP_Limit_Module bitfield of enabled modules.
+ */
+static inline uint8_t mavlink_msg_limits_status_get_mods_enabled(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 19);
+}
+
+/**
+ * @brief Get field mods_required from limits_status message
+ *
+ * @return AP_Limit_Module bitfield of required modules.
+ */
+static inline uint8_t mavlink_msg_limits_status_get_mods_required(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 20);
+}
+
+/**
+ * @brief Get field mods_triggered from limits_status message
+ *
+ * @return AP_Limit_Module bitfield of triggered modules.
+ */
+static inline uint8_t mavlink_msg_limits_status_get_mods_triggered(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 21);
+}
+
+/**
+ * @brief Decode a limits_status message into a struct
+ *
+ * @param msg The message to decode
+ * @param limits_status C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_limits_status_decode(const mavlink_message_t* msg, mavlink_limits_status_t* limits_status)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ limits_status->last_trigger = mavlink_msg_limits_status_get_last_trigger(msg);
+ limits_status->last_action = mavlink_msg_limits_status_get_last_action(msg);
+ limits_status->last_recovery = mavlink_msg_limits_status_get_last_recovery(msg);
+ limits_status->last_clear = mavlink_msg_limits_status_get_last_clear(msg);
+ limits_status->breach_count = mavlink_msg_limits_status_get_breach_count(msg);
+ limits_status->limits_state = mavlink_msg_limits_status_get_limits_state(msg);
+ limits_status->mods_enabled = mavlink_msg_limits_status_get_mods_enabled(msg);
+ limits_status->mods_required = mavlink_msg_limits_status_get_mods_required(msg);
+ limits_status->mods_triggered = mavlink_msg_limits_status_get_mods_triggered(msg);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_LIMITS_STATUS_LEN? msg->len : MAVLINK_MSG_ID_LIMITS_STATUS_LEN;
+ memset(limits_status, 0, MAVLINK_MSG_ID_LIMITS_STATUS_LEN);
+ memcpy(limits_status, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/ardupilotmega/mavlink_msg_mag_cal_progress.h b/lib/main/MAVLink/ardupilotmega/mavlink_msg_mag_cal_progress.h
new file mode 100644
index 00000000000..a471355abd4
--- /dev/null
+++ b/lib/main/MAVLink/ardupilotmega/mavlink_msg_mag_cal_progress.h
@@ -0,0 +1,474 @@
+#pragma once
+// MESSAGE MAG_CAL_PROGRESS PACKING
+
+#define MAVLINK_MSG_ID_MAG_CAL_PROGRESS 191
+
+
+typedef struct __mavlink_mag_cal_progress_t {
+ float direction_x; /*< Body frame direction vector for display.*/
+ float direction_y; /*< Body frame direction vector for display.*/
+ float direction_z; /*< Body frame direction vector for display.*/
+ uint8_t compass_id; /*< Compass being calibrated.*/
+ uint8_t cal_mask; /*< Bitmask of compasses being calibrated.*/
+ uint8_t cal_status; /*< Calibration Status.*/
+ uint8_t attempt; /*< Attempt number.*/
+ uint8_t completion_pct; /*< [%] Completion percentage.*/
+ uint8_t completion_mask[10]; /*< Bitmask of sphere sections (see http://en.wikipedia.org/wiki/Geodesic_grid).*/
+} mavlink_mag_cal_progress_t;
+
+#define MAVLINK_MSG_ID_MAG_CAL_PROGRESS_LEN 27
+#define MAVLINK_MSG_ID_MAG_CAL_PROGRESS_MIN_LEN 27
+#define MAVLINK_MSG_ID_191_LEN 27
+#define MAVLINK_MSG_ID_191_MIN_LEN 27
+
+#define MAVLINK_MSG_ID_MAG_CAL_PROGRESS_CRC 92
+#define MAVLINK_MSG_ID_191_CRC 92
+
+#define MAVLINK_MSG_MAG_CAL_PROGRESS_FIELD_COMPLETION_MASK_LEN 10
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_MAG_CAL_PROGRESS { \
+ 191, \
+ "MAG_CAL_PROGRESS", \
+ 9, \
+ { { "compass_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_mag_cal_progress_t, compass_id) }, \
+ { "cal_mask", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_mag_cal_progress_t, cal_mask) }, \
+ { "cal_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 14, offsetof(mavlink_mag_cal_progress_t, cal_status) }, \
+ { "attempt", NULL, MAVLINK_TYPE_UINT8_T, 0, 15, offsetof(mavlink_mag_cal_progress_t, attempt) }, \
+ { "completion_pct", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_mag_cal_progress_t, completion_pct) }, \
+ { "completion_mask", NULL, MAVLINK_TYPE_UINT8_T, 10, 17, offsetof(mavlink_mag_cal_progress_t, completion_mask) }, \
+ { "direction_x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_mag_cal_progress_t, direction_x) }, \
+ { "direction_y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_mag_cal_progress_t, direction_y) }, \
+ { "direction_z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_mag_cal_progress_t, direction_z) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_MAG_CAL_PROGRESS { \
+ "MAG_CAL_PROGRESS", \
+ 9, \
+ { { "compass_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_mag_cal_progress_t, compass_id) }, \
+ { "cal_mask", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_mag_cal_progress_t, cal_mask) }, \
+ { "cal_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 14, offsetof(mavlink_mag_cal_progress_t, cal_status) }, \
+ { "attempt", NULL, MAVLINK_TYPE_UINT8_T, 0, 15, offsetof(mavlink_mag_cal_progress_t, attempt) }, \
+ { "completion_pct", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_mag_cal_progress_t, completion_pct) }, \
+ { "completion_mask", NULL, MAVLINK_TYPE_UINT8_T, 10, 17, offsetof(mavlink_mag_cal_progress_t, completion_mask) }, \
+ { "direction_x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_mag_cal_progress_t, direction_x) }, \
+ { "direction_y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_mag_cal_progress_t, direction_y) }, \
+ { "direction_z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_mag_cal_progress_t, direction_z) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a mag_cal_progress 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 compass_id Compass being calibrated.
+ * @param cal_mask Bitmask of compasses being calibrated.
+ * @param cal_status Calibration Status.
+ * @param attempt Attempt number.
+ * @param completion_pct [%] Completion percentage.
+ * @param completion_mask Bitmask of sphere sections (see http://en.wikipedia.org/wiki/Geodesic_grid).
+ * @param direction_x Body frame direction vector for display.
+ * @param direction_y Body frame direction vector for display.
+ * @param direction_z Body frame direction vector for display.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_mag_cal_progress_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint8_t compass_id, uint8_t cal_mask, uint8_t cal_status, uint8_t attempt, uint8_t completion_pct, const uint8_t *completion_mask, float direction_x, float direction_y, float direction_z)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_MAG_CAL_PROGRESS_LEN];
+ _mav_put_float(buf, 0, direction_x);
+ _mav_put_float(buf, 4, direction_y);
+ _mav_put_float(buf, 8, direction_z);
+ _mav_put_uint8_t(buf, 12, compass_id);
+ _mav_put_uint8_t(buf, 13, cal_mask);
+ _mav_put_uint8_t(buf, 14, cal_status);
+ _mav_put_uint8_t(buf, 15, attempt);
+ _mav_put_uint8_t(buf, 16, completion_pct);
+ _mav_put_uint8_t_array(buf, 17, completion_mask, 10);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MAG_CAL_PROGRESS_LEN);
+#else
+ mavlink_mag_cal_progress_t packet;
+ packet.direction_x = direction_x;
+ packet.direction_y = direction_y;
+ packet.direction_z = direction_z;
+ packet.compass_id = compass_id;
+ packet.cal_mask = cal_mask;
+ packet.cal_status = cal_status;
+ packet.attempt = attempt;
+ packet.completion_pct = completion_pct;
+ mav_array_assign_uint8_t(packet.completion_mask, completion_mask, 10);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MAG_CAL_PROGRESS_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_MAG_CAL_PROGRESS;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MAG_CAL_PROGRESS_MIN_LEN, MAVLINK_MSG_ID_MAG_CAL_PROGRESS_LEN, MAVLINK_MSG_ID_MAG_CAL_PROGRESS_CRC);
+}
+
+/**
+ * @brief Pack a mag_cal_progress 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 compass_id Compass being calibrated.
+ * @param cal_mask Bitmask of compasses being calibrated.
+ * @param cal_status Calibration Status.
+ * @param attempt Attempt number.
+ * @param completion_pct [%] Completion percentage.
+ * @param completion_mask Bitmask of sphere sections (see http://en.wikipedia.org/wiki/Geodesic_grid).
+ * @param direction_x Body frame direction vector for display.
+ * @param direction_y Body frame direction vector for display.
+ * @param direction_z Body frame direction vector for display.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_mag_cal_progress_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ uint8_t compass_id, uint8_t cal_mask, uint8_t cal_status, uint8_t attempt, uint8_t completion_pct, const uint8_t *completion_mask, float direction_x, float direction_y, float direction_z)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_MAG_CAL_PROGRESS_LEN];
+ _mav_put_float(buf, 0, direction_x);
+ _mav_put_float(buf, 4, direction_y);
+ _mav_put_float(buf, 8, direction_z);
+ _mav_put_uint8_t(buf, 12, compass_id);
+ _mav_put_uint8_t(buf, 13, cal_mask);
+ _mav_put_uint8_t(buf, 14, cal_status);
+ _mav_put_uint8_t(buf, 15, attempt);
+ _mav_put_uint8_t(buf, 16, completion_pct);
+ _mav_put_uint8_t_array(buf, 17, completion_mask, 10);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MAG_CAL_PROGRESS_LEN);
+#else
+ mavlink_mag_cal_progress_t packet;
+ packet.direction_x = direction_x;
+ packet.direction_y = direction_y;
+ packet.direction_z = direction_z;
+ packet.compass_id = compass_id;
+ packet.cal_mask = cal_mask;
+ packet.cal_status = cal_status;
+ packet.attempt = attempt;
+ packet.completion_pct = completion_pct;
+ mav_array_memcpy(packet.completion_mask, completion_mask, sizeof(uint8_t)*10);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MAG_CAL_PROGRESS_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_MAG_CAL_PROGRESS;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_MAG_CAL_PROGRESS_MIN_LEN, MAVLINK_MSG_ID_MAG_CAL_PROGRESS_LEN, MAVLINK_MSG_ID_MAG_CAL_PROGRESS_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_MAG_CAL_PROGRESS_MIN_LEN, MAVLINK_MSG_ID_MAG_CAL_PROGRESS_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a mag_cal_progress 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 compass_id Compass being calibrated.
+ * @param cal_mask Bitmask of compasses being calibrated.
+ * @param cal_status Calibration Status.
+ * @param attempt Attempt number.
+ * @param completion_pct [%] Completion percentage.
+ * @param completion_mask Bitmask of sphere sections (see http://en.wikipedia.org/wiki/Geodesic_grid).
+ * @param direction_x Body frame direction vector for display.
+ * @param direction_y Body frame direction vector for display.
+ * @param direction_z Body frame direction vector for display.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_mag_cal_progress_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint8_t compass_id,uint8_t cal_mask,uint8_t cal_status,uint8_t attempt,uint8_t completion_pct,const uint8_t *completion_mask,float direction_x,float direction_y,float direction_z)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_MAG_CAL_PROGRESS_LEN];
+ _mav_put_float(buf, 0, direction_x);
+ _mav_put_float(buf, 4, direction_y);
+ _mav_put_float(buf, 8, direction_z);
+ _mav_put_uint8_t(buf, 12, compass_id);
+ _mav_put_uint8_t(buf, 13, cal_mask);
+ _mav_put_uint8_t(buf, 14, cal_status);
+ _mav_put_uint8_t(buf, 15, attempt);
+ _mav_put_uint8_t(buf, 16, completion_pct);
+ _mav_put_uint8_t_array(buf, 17, completion_mask, 10);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MAG_CAL_PROGRESS_LEN);
+#else
+ mavlink_mag_cal_progress_t packet;
+ packet.direction_x = direction_x;
+ packet.direction_y = direction_y;
+ packet.direction_z = direction_z;
+ packet.compass_id = compass_id;
+ packet.cal_mask = cal_mask;
+ packet.cal_status = cal_status;
+ packet.attempt = attempt;
+ packet.completion_pct = completion_pct;
+ mav_array_assign_uint8_t(packet.completion_mask, completion_mask, 10);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MAG_CAL_PROGRESS_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_MAG_CAL_PROGRESS;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MAG_CAL_PROGRESS_MIN_LEN, MAVLINK_MSG_ID_MAG_CAL_PROGRESS_LEN, MAVLINK_MSG_ID_MAG_CAL_PROGRESS_CRC);
+}
+
+/**
+ * @brief Encode a mag_cal_progress 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 mag_cal_progress C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_mag_cal_progress_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mag_cal_progress_t* mag_cal_progress)
+{
+ return mavlink_msg_mag_cal_progress_pack(system_id, component_id, msg, mag_cal_progress->compass_id, mag_cal_progress->cal_mask, mag_cal_progress->cal_status, mag_cal_progress->attempt, mag_cal_progress->completion_pct, mag_cal_progress->completion_mask, mag_cal_progress->direction_x, mag_cal_progress->direction_y, mag_cal_progress->direction_z);
+}
+
+/**
+ * @brief Encode a mag_cal_progress 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 mag_cal_progress C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_mag_cal_progress_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mag_cal_progress_t* mag_cal_progress)
+{
+ return mavlink_msg_mag_cal_progress_pack_chan(system_id, component_id, chan, msg, mag_cal_progress->compass_id, mag_cal_progress->cal_mask, mag_cal_progress->cal_status, mag_cal_progress->attempt, mag_cal_progress->completion_pct, mag_cal_progress->completion_mask, mag_cal_progress->direction_x, mag_cal_progress->direction_y, mag_cal_progress->direction_z);
+}
+
+/**
+ * @brief Encode a mag_cal_progress 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 mag_cal_progress C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_mag_cal_progress_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_mag_cal_progress_t* mag_cal_progress)
+{
+ return mavlink_msg_mag_cal_progress_pack_status(system_id, component_id, _status, msg, mag_cal_progress->compass_id, mag_cal_progress->cal_mask, mag_cal_progress->cal_status, mag_cal_progress->attempt, mag_cal_progress->completion_pct, mag_cal_progress->completion_mask, mag_cal_progress->direction_x, mag_cal_progress->direction_y, mag_cal_progress->direction_z);
+}
+
+/**
+ * @brief Send a mag_cal_progress message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param compass_id Compass being calibrated.
+ * @param cal_mask Bitmask of compasses being calibrated.
+ * @param cal_status Calibration Status.
+ * @param attempt Attempt number.
+ * @param completion_pct [%] Completion percentage.
+ * @param completion_mask Bitmask of sphere sections (see http://en.wikipedia.org/wiki/Geodesic_grid).
+ * @param direction_x Body frame direction vector for display.
+ * @param direction_y Body frame direction vector for display.
+ * @param direction_z Body frame direction vector for display.
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_mag_cal_progress_send(mavlink_channel_t chan, uint8_t compass_id, uint8_t cal_mask, uint8_t cal_status, uint8_t attempt, uint8_t completion_pct, const uint8_t *completion_mask, float direction_x, float direction_y, float direction_z)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_MAG_CAL_PROGRESS_LEN];
+ _mav_put_float(buf, 0, direction_x);
+ _mav_put_float(buf, 4, direction_y);
+ _mav_put_float(buf, 8, direction_z);
+ _mav_put_uint8_t(buf, 12, compass_id);
+ _mav_put_uint8_t(buf, 13, cal_mask);
+ _mav_put_uint8_t(buf, 14, cal_status);
+ _mav_put_uint8_t(buf, 15, attempt);
+ _mav_put_uint8_t(buf, 16, completion_pct);
+ _mav_put_uint8_t_array(buf, 17, completion_mask, 10);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MAG_CAL_PROGRESS, buf, MAVLINK_MSG_ID_MAG_CAL_PROGRESS_MIN_LEN, MAVLINK_MSG_ID_MAG_CAL_PROGRESS_LEN, MAVLINK_MSG_ID_MAG_CAL_PROGRESS_CRC);
+#else
+ mavlink_mag_cal_progress_t packet;
+ packet.direction_x = direction_x;
+ packet.direction_y = direction_y;
+ packet.direction_z = direction_z;
+ packet.compass_id = compass_id;
+ packet.cal_mask = cal_mask;
+ packet.cal_status = cal_status;
+ packet.attempt = attempt;
+ packet.completion_pct = completion_pct;
+ mav_array_assign_uint8_t(packet.completion_mask, completion_mask, 10);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MAG_CAL_PROGRESS, (const char *)&packet, MAVLINK_MSG_ID_MAG_CAL_PROGRESS_MIN_LEN, MAVLINK_MSG_ID_MAG_CAL_PROGRESS_LEN, MAVLINK_MSG_ID_MAG_CAL_PROGRESS_CRC);
+#endif
+}
+
+/**
+ * @brief Send a mag_cal_progress message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_mag_cal_progress_send_struct(mavlink_channel_t chan, const mavlink_mag_cal_progress_t* mag_cal_progress)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_mag_cal_progress_send(chan, mag_cal_progress->compass_id, mag_cal_progress->cal_mask, mag_cal_progress->cal_status, mag_cal_progress->attempt, mag_cal_progress->completion_pct, mag_cal_progress->completion_mask, mag_cal_progress->direction_x, mag_cal_progress->direction_y, mag_cal_progress->direction_z);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MAG_CAL_PROGRESS, (const char *)mag_cal_progress, MAVLINK_MSG_ID_MAG_CAL_PROGRESS_MIN_LEN, MAVLINK_MSG_ID_MAG_CAL_PROGRESS_LEN, MAVLINK_MSG_ID_MAG_CAL_PROGRESS_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_MAG_CAL_PROGRESS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_mag_cal_progress_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t compass_id, uint8_t cal_mask, uint8_t cal_status, uint8_t attempt, uint8_t completion_pct, const uint8_t *completion_mask, float direction_x, float direction_y, float direction_z)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_float(buf, 0, direction_x);
+ _mav_put_float(buf, 4, direction_y);
+ _mav_put_float(buf, 8, direction_z);
+ _mav_put_uint8_t(buf, 12, compass_id);
+ _mav_put_uint8_t(buf, 13, cal_mask);
+ _mav_put_uint8_t(buf, 14, cal_status);
+ _mav_put_uint8_t(buf, 15, attempt);
+ _mav_put_uint8_t(buf, 16, completion_pct);
+ _mav_put_uint8_t_array(buf, 17, completion_mask, 10);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MAG_CAL_PROGRESS, buf, MAVLINK_MSG_ID_MAG_CAL_PROGRESS_MIN_LEN, MAVLINK_MSG_ID_MAG_CAL_PROGRESS_LEN, MAVLINK_MSG_ID_MAG_CAL_PROGRESS_CRC);
+#else
+ mavlink_mag_cal_progress_t *packet = (mavlink_mag_cal_progress_t *)msgbuf;
+ packet->direction_x = direction_x;
+ packet->direction_y = direction_y;
+ packet->direction_z = direction_z;
+ packet->compass_id = compass_id;
+ packet->cal_mask = cal_mask;
+ packet->cal_status = cal_status;
+ packet->attempt = attempt;
+ packet->completion_pct = completion_pct;
+ mav_array_assign_uint8_t(packet->completion_mask, completion_mask, 10);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MAG_CAL_PROGRESS, (const char *)packet, MAVLINK_MSG_ID_MAG_CAL_PROGRESS_MIN_LEN, MAVLINK_MSG_ID_MAG_CAL_PROGRESS_LEN, MAVLINK_MSG_ID_MAG_CAL_PROGRESS_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE MAG_CAL_PROGRESS UNPACKING
+
+
+/**
+ * @brief Get field compass_id from mag_cal_progress message
+ *
+ * @return Compass being calibrated.
+ */
+static inline uint8_t mavlink_msg_mag_cal_progress_get_compass_id(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 12);
+}
+
+/**
+ * @brief Get field cal_mask from mag_cal_progress message
+ *
+ * @return Bitmask of compasses being calibrated.
+ */
+static inline uint8_t mavlink_msg_mag_cal_progress_get_cal_mask(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 13);
+}
+
+/**
+ * @brief Get field cal_status from mag_cal_progress message
+ *
+ * @return Calibration Status.
+ */
+static inline uint8_t mavlink_msg_mag_cal_progress_get_cal_status(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 14);
+}
+
+/**
+ * @brief Get field attempt from mag_cal_progress message
+ *
+ * @return Attempt number.
+ */
+static inline uint8_t mavlink_msg_mag_cal_progress_get_attempt(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 15);
+}
+
+/**
+ * @brief Get field completion_pct from mag_cal_progress message
+ *
+ * @return [%] Completion percentage.
+ */
+static inline uint8_t mavlink_msg_mag_cal_progress_get_completion_pct(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 16);
+}
+
+/**
+ * @brief Get field completion_mask from mag_cal_progress message
+ *
+ * @return Bitmask of sphere sections (see http://en.wikipedia.org/wiki/Geodesic_grid).
+ */
+static inline uint16_t mavlink_msg_mag_cal_progress_get_completion_mask(const mavlink_message_t* msg, uint8_t *completion_mask)
+{
+ return _MAV_RETURN_uint8_t_array(msg, completion_mask, 10, 17);
+}
+
+/**
+ * @brief Get field direction_x from mag_cal_progress message
+ *
+ * @return Body frame direction vector for display.
+ */
+static inline float mavlink_msg_mag_cal_progress_get_direction_x(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 0);
+}
+
+/**
+ * @brief Get field direction_y from mag_cal_progress message
+ *
+ * @return Body frame direction vector for display.
+ */
+static inline float mavlink_msg_mag_cal_progress_get_direction_y(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 4);
+}
+
+/**
+ * @brief Get field direction_z from mag_cal_progress message
+ *
+ * @return Body frame direction vector for display.
+ */
+static inline float mavlink_msg_mag_cal_progress_get_direction_z(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 8);
+}
+
+/**
+ * @brief Decode a mag_cal_progress message into a struct
+ *
+ * @param msg The message to decode
+ * @param mag_cal_progress C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_mag_cal_progress_decode(const mavlink_message_t* msg, mavlink_mag_cal_progress_t* mag_cal_progress)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mag_cal_progress->direction_x = mavlink_msg_mag_cal_progress_get_direction_x(msg);
+ mag_cal_progress->direction_y = mavlink_msg_mag_cal_progress_get_direction_y(msg);
+ mag_cal_progress->direction_z = mavlink_msg_mag_cal_progress_get_direction_z(msg);
+ mag_cal_progress->compass_id = mavlink_msg_mag_cal_progress_get_compass_id(msg);
+ mag_cal_progress->cal_mask = mavlink_msg_mag_cal_progress_get_cal_mask(msg);
+ mag_cal_progress->cal_status = mavlink_msg_mag_cal_progress_get_cal_status(msg);
+ mag_cal_progress->attempt = mavlink_msg_mag_cal_progress_get_attempt(msg);
+ mag_cal_progress->completion_pct = mavlink_msg_mag_cal_progress_get_completion_pct(msg);
+ mavlink_msg_mag_cal_progress_get_completion_mask(msg, mag_cal_progress->completion_mask);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_MAG_CAL_PROGRESS_LEN? msg->len : MAVLINK_MSG_ID_MAG_CAL_PROGRESS_LEN;
+ memset(mag_cal_progress, 0, MAVLINK_MSG_ID_MAG_CAL_PROGRESS_LEN);
+ memcpy(mag_cal_progress, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/ardupilotmega/mavlink_msg_mcu_status.h b/lib/main/MAVLink/ardupilotmega/mavlink_msg_mcu_status.h
new file mode 100644
index 00000000000..409332e6bb0
--- /dev/null
+++ b/lib/main/MAVLink/ardupilotmega/mavlink_msg_mcu_status.h
@@ -0,0 +1,372 @@
+#pragma once
+// MESSAGE MCU_STATUS PACKING
+
+#define MAVLINK_MSG_ID_MCU_STATUS 11039
+
+
+typedef struct __mavlink_mcu_status_t {
+ int16_t MCU_temperature; /*< [cdegC] MCU Internal temperature*/
+ uint16_t MCU_voltage; /*< [mV] MCU voltage*/
+ uint16_t MCU_voltage_min; /*< [mV] MCU voltage minimum*/
+ uint16_t MCU_voltage_max; /*< [mV] MCU voltage maximum*/
+ uint8_t id; /*< MCU instance*/
+} mavlink_mcu_status_t;
+
+#define MAVLINK_MSG_ID_MCU_STATUS_LEN 9
+#define MAVLINK_MSG_ID_MCU_STATUS_MIN_LEN 9
+#define MAVLINK_MSG_ID_11039_LEN 9
+#define MAVLINK_MSG_ID_11039_MIN_LEN 9
+
+#define MAVLINK_MSG_ID_MCU_STATUS_CRC 142
+#define MAVLINK_MSG_ID_11039_CRC 142
+
+
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_MCU_STATUS { \
+ 11039, \
+ "MCU_STATUS", \
+ 5, \
+ { { "id", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_mcu_status_t, id) }, \
+ { "MCU_temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_mcu_status_t, MCU_temperature) }, \
+ { "MCU_voltage", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_mcu_status_t, MCU_voltage) }, \
+ { "MCU_voltage_min", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_mcu_status_t, MCU_voltage_min) }, \
+ { "MCU_voltage_max", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_mcu_status_t, MCU_voltage_max) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_MCU_STATUS { \
+ "MCU_STATUS", \
+ 5, \
+ { { "id", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_mcu_status_t, id) }, \
+ { "MCU_temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_mcu_status_t, MCU_temperature) }, \
+ { "MCU_voltage", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_mcu_status_t, MCU_voltage) }, \
+ { "MCU_voltage_min", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_mcu_status_t, MCU_voltage_min) }, \
+ { "MCU_voltage_max", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_mcu_status_t, MCU_voltage_max) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a mcu_status 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 id MCU instance
+ * @param MCU_temperature [cdegC] MCU Internal temperature
+ * @param MCU_voltage [mV] MCU voltage
+ * @param MCU_voltage_min [mV] MCU voltage minimum
+ * @param MCU_voltage_max [mV] MCU voltage maximum
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_mcu_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint8_t id, int16_t MCU_temperature, uint16_t MCU_voltage, uint16_t MCU_voltage_min, uint16_t MCU_voltage_max)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_MCU_STATUS_LEN];
+ _mav_put_int16_t(buf, 0, MCU_temperature);
+ _mav_put_uint16_t(buf, 2, MCU_voltage);
+ _mav_put_uint16_t(buf, 4, MCU_voltage_min);
+ _mav_put_uint16_t(buf, 6, MCU_voltage_max);
+ _mav_put_uint8_t(buf, 8, id);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MCU_STATUS_LEN);
+#else
+ mavlink_mcu_status_t packet;
+ packet.MCU_temperature = MCU_temperature;
+ packet.MCU_voltage = MCU_voltage;
+ packet.MCU_voltage_min = MCU_voltage_min;
+ packet.MCU_voltage_max = MCU_voltage_max;
+ packet.id = id;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MCU_STATUS_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_MCU_STATUS;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MCU_STATUS_MIN_LEN, MAVLINK_MSG_ID_MCU_STATUS_LEN, MAVLINK_MSG_ID_MCU_STATUS_CRC);
+}
+
+/**
+ * @brief Pack a mcu_status 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 id MCU instance
+ * @param MCU_temperature [cdegC] MCU Internal temperature
+ * @param MCU_voltage [mV] MCU voltage
+ * @param MCU_voltage_min [mV] MCU voltage minimum
+ * @param MCU_voltage_max [mV] MCU voltage maximum
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_mcu_status_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ uint8_t id, int16_t MCU_temperature, uint16_t MCU_voltage, uint16_t MCU_voltage_min, uint16_t MCU_voltage_max)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_MCU_STATUS_LEN];
+ _mav_put_int16_t(buf, 0, MCU_temperature);
+ _mav_put_uint16_t(buf, 2, MCU_voltage);
+ _mav_put_uint16_t(buf, 4, MCU_voltage_min);
+ _mav_put_uint16_t(buf, 6, MCU_voltage_max);
+ _mav_put_uint8_t(buf, 8, id);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MCU_STATUS_LEN);
+#else
+ mavlink_mcu_status_t packet;
+ packet.MCU_temperature = MCU_temperature;
+ packet.MCU_voltage = MCU_voltage;
+ packet.MCU_voltage_min = MCU_voltage_min;
+ packet.MCU_voltage_max = MCU_voltage_max;
+ packet.id = id;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MCU_STATUS_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_MCU_STATUS;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_MCU_STATUS_MIN_LEN, MAVLINK_MSG_ID_MCU_STATUS_LEN, MAVLINK_MSG_ID_MCU_STATUS_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_MCU_STATUS_MIN_LEN, MAVLINK_MSG_ID_MCU_STATUS_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a mcu_status 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 id MCU instance
+ * @param MCU_temperature [cdegC] MCU Internal temperature
+ * @param MCU_voltage [mV] MCU voltage
+ * @param MCU_voltage_min [mV] MCU voltage minimum
+ * @param MCU_voltage_max [mV] MCU voltage maximum
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_mcu_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint8_t id,int16_t MCU_temperature,uint16_t MCU_voltage,uint16_t MCU_voltage_min,uint16_t MCU_voltage_max)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_MCU_STATUS_LEN];
+ _mav_put_int16_t(buf, 0, MCU_temperature);
+ _mav_put_uint16_t(buf, 2, MCU_voltage);
+ _mav_put_uint16_t(buf, 4, MCU_voltage_min);
+ _mav_put_uint16_t(buf, 6, MCU_voltage_max);
+ _mav_put_uint8_t(buf, 8, id);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MCU_STATUS_LEN);
+#else
+ mavlink_mcu_status_t packet;
+ packet.MCU_temperature = MCU_temperature;
+ packet.MCU_voltage = MCU_voltage;
+ packet.MCU_voltage_min = MCU_voltage_min;
+ packet.MCU_voltage_max = MCU_voltage_max;
+ packet.id = id;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MCU_STATUS_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_MCU_STATUS;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MCU_STATUS_MIN_LEN, MAVLINK_MSG_ID_MCU_STATUS_LEN, MAVLINK_MSG_ID_MCU_STATUS_CRC);
+}
+
+/**
+ * @brief Encode a mcu_status 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 mcu_status C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_mcu_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mcu_status_t* mcu_status)
+{
+ return mavlink_msg_mcu_status_pack(system_id, component_id, msg, mcu_status->id, mcu_status->MCU_temperature, mcu_status->MCU_voltage, mcu_status->MCU_voltage_min, mcu_status->MCU_voltage_max);
+}
+
+/**
+ * @brief Encode a mcu_status 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 mcu_status C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_mcu_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mcu_status_t* mcu_status)
+{
+ return mavlink_msg_mcu_status_pack_chan(system_id, component_id, chan, msg, mcu_status->id, mcu_status->MCU_temperature, mcu_status->MCU_voltage, mcu_status->MCU_voltage_min, mcu_status->MCU_voltage_max);
+}
+
+/**
+ * @brief Encode a mcu_status 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 mcu_status C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_mcu_status_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_mcu_status_t* mcu_status)
+{
+ return mavlink_msg_mcu_status_pack_status(system_id, component_id, _status, msg, mcu_status->id, mcu_status->MCU_temperature, mcu_status->MCU_voltage, mcu_status->MCU_voltage_min, mcu_status->MCU_voltage_max);
+}
+
+/**
+ * @brief Send a mcu_status message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param id MCU instance
+ * @param MCU_temperature [cdegC] MCU Internal temperature
+ * @param MCU_voltage [mV] MCU voltage
+ * @param MCU_voltage_min [mV] MCU voltage minimum
+ * @param MCU_voltage_max [mV] MCU voltage maximum
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_mcu_status_send(mavlink_channel_t chan, uint8_t id, int16_t MCU_temperature, uint16_t MCU_voltage, uint16_t MCU_voltage_min, uint16_t MCU_voltage_max)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_MCU_STATUS_LEN];
+ _mav_put_int16_t(buf, 0, MCU_temperature);
+ _mav_put_uint16_t(buf, 2, MCU_voltage);
+ _mav_put_uint16_t(buf, 4, MCU_voltage_min);
+ _mav_put_uint16_t(buf, 6, MCU_voltage_max);
+ _mav_put_uint8_t(buf, 8, id);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MCU_STATUS, buf, MAVLINK_MSG_ID_MCU_STATUS_MIN_LEN, MAVLINK_MSG_ID_MCU_STATUS_LEN, MAVLINK_MSG_ID_MCU_STATUS_CRC);
+#else
+ mavlink_mcu_status_t packet;
+ packet.MCU_temperature = MCU_temperature;
+ packet.MCU_voltage = MCU_voltage;
+ packet.MCU_voltage_min = MCU_voltage_min;
+ packet.MCU_voltage_max = MCU_voltage_max;
+ packet.id = id;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MCU_STATUS, (const char *)&packet, MAVLINK_MSG_ID_MCU_STATUS_MIN_LEN, MAVLINK_MSG_ID_MCU_STATUS_LEN, MAVLINK_MSG_ID_MCU_STATUS_CRC);
+#endif
+}
+
+/**
+ * @brief Send a mcu_status message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_mcu_status_send_struct(mavlink_channel_t chan, const mavlink_mcu_status_t* mcu_status)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_mcu_status_send(chan, mcu_status->id, mcu_status->MCU_temperature, mcu_status->MCU_voltage, mcu_status->MCU_voltage_min, mcu_status->MCU_voltage_max);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MCU_STATUS, (const char *)mcu_status, MAVLINK_MSG_ID_MCU_STATUS_MIN_LEN, MAVLINK_MSG_ID_MCU_STATUS_LEN, MAVLINK_MSG_ID_MCU_STATUS_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_MCU_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_mcu_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t id, int16_t MCU_temperature, uint16_t MCU_voltage, uint16_t MCU_voltage_min, uint16_t MCU_voltage_max)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_int16_t(buf, 0, MCU_temperature);
+ _mav_put_uint16_t(buf, 2, MCU_voltage);
+ _mav_put_uint16_t(buf, 4, MCU_voltage_min);
+ _mav_put_uint16_t(buf, 6, MCU_voltage_max);
+ _mav_put_uint8_t(buf, 8, id);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MCU_STATUS, buf, MAVLINK_MSG_ID_MCU_STATUS_MIN_LEN, MAVLINK_MSG_ID_MCU_STATUS_LEN, MAVLINK_MSG_ID_MCU_STATUS_CRC);
+#else
+ mavlink_mcu_status_t *packet = (mavlink_mcu_status_t *)msgbuf;
+ packet->MCU_temperature = MCU_temperature;
+ packet->MCU_voltage = MCU_voltage;
+ packet->MCU_voltage_min = MCU_voltage_min;
+ packet->MCU_voltage_max = MCU_voltage_max;
+ packet->id = id;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MCU_STATUS, (const char *)packet, MAVLINK_MSG_ID_MCU_STATUS_MIN_LEN, MAVLINK_MSG_ID_MCU_STATUS_LEN, MAVLINK_MSG_ID_MCU_STATUS_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE MCU_STATUS UNPACKING
+
+
+/**
+ * @brief Get field id from mcu_status message
+ *
+ * @return MCU instance
+ */
+static inline uint8_t mavlink_msg_mcu_status_get_id(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 8);
+}
+
+/**
+ * @brief Get field MCU_temperature from mcu_status message
+ *
+ * @return [cdegC] MCU Internal temperature
+ */
+static inline int16_t mavlink_msg_mcu_status_get_MCU_temperature(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_int16_t(msg, 0);
+}
+
+/**
+ * @brief Get field MCU_voltage from mcu_status message
+ *
+ * @return [mV] MCU voltage
+ */
+static inline uint16_t mavlink_msg_mcu_status_get_MCU_voltage(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 2);
+}
+
+/**
+ * @brief Get field MCU_voltage_min from mcu_status message
+ *
+ * @return [mV] MCU voltage minimum
+ */
+static inline uint16_t mavlink_msg_mcu_status_get_MCU_voltage_min(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 4);
+}
+
+/**
+ * @brief Get field MCU_voltage_max from mcu_status message
+ *
+ * @return [mV] MCU voltage maximum
+ */
+static inline uint16_t mavlink_msg_mcu_status_get_MCU_voltage_max(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 6);
+}
+
+/**
+ * @brief Decode a mcu_status message into a struct
+ *
+ * @param msg The message to decode
+ * @param mcu_status C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_mcu_status_decode(const mavlink_message_t* msg, mavlink_mcu_status_t* mcu_status)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mcu_status->MCU_temperature = mavlink_msg_mcu_status_get_MCU_temperature(msg);
+ mcu_status->MCU_voltage = mavlink_msg_mcu_status_get_MCU_voltage(msg);
+ mcu_status->MCU_voltage_min = mavlink_msg_mcu_status_get_MCU_voltage_min(msg);
+ mcu_status->MCU_voltage_max = mavlink_msg_mcu_status_get_MCU_voltage_max(msg);
+ mcu_status->id = mavlink_msg_mcu_status_get_id(msg);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_MCU_STATUS_LEN? msg->len : MAVLINK_MSG_ID_MCU_STATUS_LEN;
+ memset(mcu_status, 0, MAVLINK_MSG_ID_MCU_STATUS_LEN);
+ memcpy(mcu_status, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/ardupilotmega/mavlink_msg_meminfo.h b/lib/main/MAVLink/ardupilotmega/mavlink_msg_meminfo.h
new file mode 100644
index 00000000000..ff80bb51123
--- /dev/null
+++ b/lib/main/MAVLink/ardupilotmega/mavlink_msg_meminfo.h
@@ -0,0 +1,316 @@
+#pragma once
+// MESSAGE MEMINFO PACKING
+
+#define MAVLINK_MSG_ID_MEMINFO 152
+
+
+typedef struct __mavlink_meminfo_t {
+ uint16_t brkval; /*< Heap top.*/
+ uint16_t freemem; /*< [bytes] Free memory.*/
+ uint32_t freemem32; /*< [bytes] Free memory (32 bit).*/
+} mavlink_meminfo_t;
+
+#define MAVLINK_MSG_ID_MEMINFO_LEN 8
+#define MAVLINK_MSG_ID_MEMINFO_MIN_LEN 4
+#define MAVLINK_MSG_ID_152_LEN 8
+#define MAVLINK_MSG_ID_152_MIN_LEN 4
+
+#define MAVLINK_MSG_ID_MEMINFO_CRC 208
+#define MAVLINK_MSG_ID_152_CRC 208
+
+
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_MEMINFO { \
+ 152, \
+ "MEMINFO", \
+ 3, \
+ { { "brkval", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_meminfo_t, brkval) }, \
+ { "freemem", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_meminfo_t, freemem) }, \
+ { "freemem32", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_meminfo_t, freemem32) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_MEMINFO { \
+ "MEMINFO", \
+ 3, \
+ { { "brkval", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_meminfo_t, brkval) }, \
+ { "freemem", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_meminfo_t, freemem) }, \
+ { "freemem32", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_meminfo_t, freemem32) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a meminfo 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 brkval Heap top.
+ * @param freemem [bytes] Free memory.
+ * @param freemem32 [bytes] Free memory (32 bit).
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_meminfo_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint16_t brkval, uint16_t freemem, uint32_t freemem32)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_MEMINFO_LEN];
+ _mav_put_uint16_t(buf, 0, brkval);
+ _mav_put_uint16_t(buf, 2, freemem);
+ _mav_put_uint32_t(buf, 4, freemem32);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MEMINFO_LEN);
+#else
+ mavlink_meminfo_t packet;
+ packet.brkval = brkval;
+ packet.freemem = freemem;
+ packet.freemem32 = freemem32;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MEMINFO_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_MEMINFO;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MEMINFO_MIN_LEN, MAVLINK_MSG_ID_MEMINFO_LEN, MAVLINK_MSG_ID_MEMINFO_CRC);
+}
+
+/**
+ * @brief Pack a meminfo 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 brkval Heap top.
+ * @param freemem [bytes] Free memory.
+ * @param freemem32 [bytes] Free memory (32 bit).
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_meminfo_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ uint16_t brkval, uint16_t freemem, uint32_t freemem32)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_MEMINFO_LEN];
+ _mav_put_uint16_t(buf, 0, brkval);
+ _mav_put_uint16_t(buf, 2, freemem);
+ _mav_put_uint32_t(buf, 4, freemem32);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MEMINFO_LEN);
+#else
+ mavlink_meminfo_t packet;
+ packet.brkval = brkval;
+ packet.freemem = freemem;
+ packet.freemem32 = freemem32;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MEMINFO_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_MEMINFO;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_MEMINFO_MIN_LEN, MAVLINK_MSG_ID_MEMINFO_LEN, MAVLINK_MSG_ID_MEMINFO_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_MEMINFO_MIN_LEN, MAVLINK_MSG_ID_MEMINFO_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a meminfo 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 brkval Heap top.
+ * @param freemem [bytes] Free memory.
+ * @param freemem32 [bytes] Free memory (32 bit).
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_meminfo_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint16_t brkval,uint16_t freemem,uint32_t freemem32)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_MEMINFO_LEN];
+ _mav_put_uint16_t(buf, 0, brkval);
+ _mav_put_uint16_t(buf, 2, freemem);
+ _mav_put_uint32_t(buf, 4, freemem32);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MEMINFO_LEN);
+#else
+ mavlink_meminfo_t packet;
+ packet.brkval = brkval;
+ packet.freemem = freemem;
+ packet.freemem32 = freemem32;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MEMINFO_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_MEMINFO;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MEMINFO_MIN_LEN, MAVLINK_MSG_ID_MEMINFO_LEN, MAVLINK_MSG_ID_MEMINFO_CRC);
+}
+
+/**
+ * @brief Encode a meminfo 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 meminfo C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_meminfo_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_meminfo_t* meminfo)
+{
+ return mavlink_msg_meminfo_pack(system_id, component_id, msg, meminfo->brkval, meminfo->freemem, meminfo->freemem32);
+}
+
+/**
+ * @brief Encode a meminfo 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 meminfo C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_meminfo_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_meminfo_t* meminfo)
+{
+ return mavlink_msg_meminfo_pack_chan(system_id, component_id, chan, msg, meminfo->brkval, meminfo->freemem, meminfo->freemem32);
+}
+
+/**
+ * @brief Encode a meminfo 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 meminfo C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_meminfo_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_meminfo_t* meminfo)
+{
+ return mavlink_msg_meminfo_pack_status(system_id, component_id, _status, msg, meminfo->brkval, meminfo->freemem, meminfo->freemem32);
+}
+
+/**
+ * @brief Send a meminfo message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param brkval Heap top.
+ * @param freemem [bytes] Free memory.
+ * @param freemem32 [bytes] Free memory (32 bit).
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_meminfo_send(mavlink_channel_t chan, uint16_t brkval, uint16_t freemem, uint32_t freemem32)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_MEMINFO_LEN];
+ _mav_put_uint16_t(buf, 0, brkval);
+ _mav_put_uint16_t(buf, 2, freemem);
+ _mav_put_uint32_t(buf, 4, freemem32);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMINFO, buf, MAVLINK_MSG_ID_MEMINFO_MIN_LEN, MAVLINK_MSG_ID_MEMINFO_LEN, MAVLINK_MSG_ID_MEMINFO_CRC);
+#else
+ mavlink_meminfo_t packet;
+ packet.brkval = brkval;
+ packet.freemem = freemem;
+ packet.freemem32 = freemem32;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMINFO, (const char *)&packet, MAVLINK_MSG_ID_MEMINFO_MIN_LEN, MAVLINK_MSG_ID_MEMINFO_LEN, MAVLINK_MSG_ID_MEMINFO_CRC);
+#endif
+}
+
+/**
+ * @brief Send a meminfo message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_meminfo_send_struct(mavlink_channel_t chan, const mavlink_meminfo_t* meminfo)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_meminfo_send(chan, meminfo->brkval, meminfo->freemem, meminfo->freemem32);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMINFO, (const char *)meminfo, MAVLINK_MSG_ID_MEMINFO_MIN_LEN, MAVLINK_MSG_ID_MEMINFO_LEN, MAVLINK_MSG_ID_MEMINFO_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_MEMINFO_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_meminfo_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t brkval, uint16_t freemem, uint32_t freemem32)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint16_t(buf, 0, brkval);
+ _mav_put_uint16_t(buf, 2, freemem);
+ _mav_put_uint32_t(buf, 4, freemem32);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMINFO, buf, MAVLINK_MSG_ID_MEMINFO_MIN_LEN, MAVLINK_MSG_ID_MEMINFO_LEN, MAVLINK_MSG_ID_MEMINFO_CRC);
+#else
+ mavlink_meminfo_t *packet = (mavlink_meminfo_t *)msgbuf;
+ packet->brkval = brkval;
+ packet->freemem = freemem;
+ packet->freemem32 = freemem32;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMINFO, (const char *)packet, MAVLINK_MSG_ID_MEMINFO_MIN_LEN, MAVLINK_MSG_ID_MEMINFO_LEN, MAVLINK_MSG_ID_MEMINFO_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE MEMINFO UNPACKING
+
+
+/**
+ * @brief Get field brkval from meminfo message
+ *
+ * @return Heap top.
+ */
+static inline uint16_t mavlink_msg_meminfo_get_brkval(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 0);
+}
+
+/**
+ * @brief Get field freemem from meminfo message
+ *
+ * @return [bytes] Free memory.
+ */
+static inline uint16_t mavlink_msg_meminfo_get_freemem(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 2);
+}
+
+/**
+ * @brief Get field freemem32 from meminfo message
+ *
+ * @return [bytes] Free memory (32 bit).
+ */
+static inline uint32_t mavlink_msg_meminfo_get_freemem32(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint32_t(msg, 4);
+}
+
+/**
+ * @brief Decode a meminfo message into a struct
+ *
+ * @param msg The message to decode
+ * @param meminfo C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_meminfo_decode(const mavlink_message_t* msg, mavlink_meminfo_t* meminfo)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ meminfo->brkval = mavlink_msg_meminfo_get_brkval(msg);
+ meminfo->freemem = mavlink_msg_meminfo_get_freemem(msg);
+ meminfo->freemem32 = mavlink_msg_meminfo_get_freemem32(msg);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_MEMINFO_LEN? msg->len : MAVLINK_MSG_ID_MEMINFO_LEN;
+ memset(meminfo, 0, MAVLINK_MSG_ID_MEMINFO_LEN);
+ memcpy(meminfo, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/ardupilotmega/mavlink_msg_mount_configure.h b/lib/main/MAVLink/ardupilotmega/mavlink_msg_mount_configure.h
new file mode 100644
index 00000000000..7e80190c21b
--- /dev/null
+++ b/lib/main/MAVLink/ardupilotmega/mavlink_msg_mount_configure.h
@@ -0,0 +1,400 @@
+#pragma once
+// MESSAGE MOUNT_CONFIGURE PACKING
+
+#define MAVLINK_MSG_ID_MOUNT_CONFIGURE 156
+
+
+typedef struct __mavlink_mount_configure_t {
+ uint8_t target_system; /*< System ID.*/
+ uint8_t target_component; /*< Component ID.*/
+ uint8_t mount_mode; /*< Mount operating mode.*/
+ uint8_t stab_roll; /*< (1 = yes, 0 = no).*/
+ uint8_t stab_pitch; /*< (1 = yes, 0 = no).*/
+ uint8_t stab_yaw; /*< (1 = yes, 0 = no).*/
+} mavlink_mount_configure_t;
+
+#define MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN 6
+#define MAVLINK_MSG_ID_MOUNT_CONFIGURE_MIN_LEN 6
+#define MAVLINK_MSG_ID_156_LEN 6
+#define MAVLINK_MSG_ID_156_MIN_LEN 6
+
+#define MAVLINK_MSG_ID_MOUNT_CONFIGURE_CRC 19
+#define MAVLINK_MSG_ID_156_CRC 19
+
+
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_MOUNT_CONFIGURE { \
+ 156, \
+ "MOUNT_CONFIGURE", \
+ 6, \
+ { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_mount_configure_t, target_system) }, \
+ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_mount_configure_t, target_component) }, \
+ { "mount_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mount_configure_t, mount_mode) }, \
+ { "stab_roll", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_mount_configure_t, stab_roll) }, \
+ { "stab_pitch", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_mount_configure_t, stab_pitch) }, \
+ { "stab_yaw", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_mount_configure_t, stab_yaw) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_MOUNT_CONFIGURE { \
+ "MOUNT_CONFIGURE", \
+ 6, \
+ { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_mount_configure_t, target_system) }, \
+ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_mount_configure_t, target_component) }, \
+ { "mount_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mount_configure_t, mount_mode) }, \
+ { "stab_roll", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_mount_configure_t, stab_roll) }, \
+ { "stab_pitch", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_mount_configure_t, stab_pitch) }, \
+ { "stab_yaw", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_mount_configure_t, stab_yaw) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a mount_configure 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 target_system System ID.
+ * @param target_component Component ID.
+ * @param mount_mode Mount operating mode.
+ * @param stab_roll (1 = yes, 0 = no).
+ * @param stab_pitch (1 = yes, 0 = no).
+ * @param stab_yaw (1 = yes, 0 = no).
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_mount_configure_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint8_t target_system, uint8_t target_component, uint8_t mount_mode, uint8_t stab_roll, uint8_t stab_pitch, uint8_t stab_yaw)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN];
+ _mav_put_uint8_t(buf, 0, target_system);
+ _mav_put_uint8_t(buf, 1, target_component);
+ _mav_put_uint8_t(buf, 2, mount_mode);
+ _mav_put_uint8_t(buf, 3, stab_roll);
+ _mav_put_uint8_t(buf, 4, stab_pitch);
+ _mav_put_uint8_t(buf, 5, stab_yaw);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN);
+#else
+ mavlink_mount_configure_t packet;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.mount_mode = mount_mode;
+ packet.stab_roll = stab_roll;
+ packet.stab_pitch = stab_pitch;
+ packet.stab_yaw = stab_yaw;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_MOUNT_CONFIGURE;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MOUNT_CONFIGURE_MIN_LEN, MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN, MAVLINK_MSG_ID_MOUNT_CONFIGURE_CRC);
+}
+
+/**
+ * @brief Pack a mount_configure 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 target_system System ID.
+ * @param target_component Component ID.
+ * @param mount_mode Mount operating mode.
+ * @param stab_roll (1 = yes, 0 = no).
+ * @param stab_pitch (1 = yes, 0 = no).
+ * @param stab_yaw (1 = yes, 0 = no).
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_mount_configure_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ uint8_t target_system, uint8_t target_component, uint8_t mount_mode, uint8_t stab_roll, uint8_t stab_pitch, uint8_t stab_yaw)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN];
+ _mav_put_uint8_t(buf, 0, target_system);
+ _mav_put_uint8_t(buf, 1, target_component);
+ _mav_put_uint8_t(buf, 2, mount_mode);
+ _mav_put_uint8_t(buf, 3, stab_roll);
+ _mav_put_uint8_t(buf, 4, stab_pitch);
+ _mav_put_uint8_t(buf, 5, stab_yaw);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN);
+#else
+ mavlink_mount_configure_t packet;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.mount_mode = mount_mode;
+ packet.stab_roll = stab_roll;
+ packet.stab_pitch = stab_pitch;
+ packet.stab_yaw = stab_yaw;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_MOUNT_CONFIGURE;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_MOUNT_CONFIGURE_MIN_LEN, MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN, MAVLINK_MSG_ID_MOUNT_CONFIGURE_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_MOUNT_CONFIGURE_MIN_LEN, MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a mount_configure 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 target_system System ID.
+ * @param target_component Component ID.
+ * @param mount_mode Mount operating mode.
+ * @param stab_roll (1 = yes, 0 = no).
+ * @param stab_pitch (1 = yes, 0 = no).
+ * @param stab_yaw (1 = yes, 0 = no).
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_mount_configure_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint8_t target_system,uint8_t target_component,uint8_t mount_mode,uint8_t stab_roll,uint8_t stab_pitch,uint8_t stab_yaw)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN];
+ _mav_put_uint8_t(buf, 0, target_system);
+ _mav_put_uint8_t(buf, 1, target_component);
+ _mav_put_uint8_t(buf, 2, mount_mode);
+ _mav_put_uint8_t(buf, 3, stab_roll);
+ _mav_put_uint8_t(buf, 4, stab_pitch);
+ _mav_put_uint8_t(buf, 5, stab_yaw);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN);
+#else
+ mavlink_mount_configure_t packet;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.mount_mode = mount_mode;
+ packet.stab_roll = stab_roll;
+ packet.stab_pitch = stab_pitch;
+ packet.stab_yaw = stab_yaw;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_MOUNT_CONFIGURE;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MOUNT_CONFIGURE_MIN_LEN, MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN, MAVLINK_MSG_ID_MOUNT_CONFIGURE_CRC);
+}
+
+/**
+ * @brief Encode a mount_configure 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 mount_configure C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_mount_configure_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mount_configure_t* mount_configure)
+{
+ return mavlink_msg_mount_configure_pack(system_id, component_id, msg, mount_configure->target_system, mount_configure->target_component, mount_configure->mount_mode, mount_configure->stab_roll, mount_configure->stab_pitch, mount_configure->stab_yaw);
+}
+
+/**
+ * @brief Encode a mount_configure 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 mount_configure C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_mount_configure_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mount_configure_t* mount_configure)
+{
+ return mavlink_msg_mount_configure_pack_chan(system_id, component_id, chan, msg, mount_configure->target_system, mount_configure->target_component, mount_configure->mount_mode, mount_configure->stab_roll, mount_configure->stab_pitch, mount_configure->stab_yaw);
+}
+
+/**
+ * @brief Encode a mount_configure 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 mount_configure C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_mount_configure_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_mount_configure_t* mount_configure)
+{
+ return mavlink_msg_mount_configure_pack_status(system_id, component_id, _status, msg, mount_configure->target_system, mount_configure->target_component, mount_configure->mount_mode, mount_configure->stab_roll, mount_configure->stab_pitch, mount_configure->stab_yaw);
+}
+
+/**
+ * @brief Send a mount_configure message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param target_system System ID.
+ * @param target_component Component ID.
+ * @param mount_mode Mount operating mode.
+ * @param stab_roll (1 = yes, 0 = no).
+ * @param stab_pitch (1 = yes, 0 = no).
+ * @param stab_yaw (1 = yes, 0 = no).
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_mount_configure_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t mount_mode, uint8_t stab_roll, uint8_t stab_pitch, uint8_t stab_yaw)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN];
+ _mav_put_uint8_t(buf, 0, target_system);
+ _mav_put_uint8_t(buf, 1, target_component);
+ _mav_put_uint8_t(buf, 2, mount_mode);
+ _mav_put_uint8_t(buf, 3, stab_roll);
+ _mav_put_uint8_t(buf, 4, stab_pitch);
+ _mav_put_uint8_t(buf, 5, stab_yaw);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_CONFIGURE, buf, MAVLINK_MSG_ID_MOUNT_CONFIGURE_MIN_LEN, MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN, MAVLINK_MSG_ID_MOUNT_CONFIGURE_CRC);
+#else
+ mavlink_mount_configure_t packet;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.mount_mode = mount_mode;
+ packet.stab_roll = stab_roll;
+ packet.stab_pitch = stab_pitch;
+ packet.stab_yaw = stab_yaw;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_CONFIGURE, (const char *)&packet, MAVLINK_MSG_ID_MOUNT_CONFIGURE_MIN_LEN, MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN, MAVLINK_MSG_ID_MOUNT_CONFIGURE_CRC);
+#endif
+}
+
+/**
+ * @brief Send a mount_configure message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_mount_configure_send_struct(mavlink_channel_t chan, const mavlink_mount_configure_t* mount_configure)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_mount_configure_send(chan, mount_configure->target_system, mount_configure->target_component, mount_configure->mount_mode, mount_configure->stab_roll, mount_configure->stab_pitch, mount_configure->stab_yaw);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_CONFIGURE, (const char *)mount_configure, MAVLINK_MSG_ID_MOUNT_CONFIGURE_MIN_LEN, MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN, MAVLINK_MSG_ID_MOUNT_CONFIGURE_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_mount_configure_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t mount_mode, uint8_t stab_roll, uint8_t stab_pitch, uint8_t stab_yaw)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint8_t(buf, 0, target_system);
+ _mav_put_uint8_t(buf, 1, target_component);
+ _mav_put_uint8_t(buf, 2, mount_mode);
+ _mav_put_uint8_t(buf, 3, stab_roll);
+ _mav_put_uint8_t(buf, 4, stab_pitch);
+ _mav_put_uint8_t(buf, 5, stab_yaw);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_CONFIGURE, buf, MAVLINK_MSG_ID_MOUNT_CONFIGURE_MIN_LEN, MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN, MAVLINK_MSG_ID_MOUNT_CONFIGURE_CRC);
+#else
+ mavlink_mount_configure_t *packet = (mavlink_mount_configure_t *)msgbuf;
+ packet->target_system = target_system;
+ packet->target_component = target_component;
+ packet->mount_mode = mount_mode;
+ packet->stab_roll = stab_roll;
+ packet->stab_pitch = stab_pitch;
+ packet->stab_yaw = stab_yaw;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_CONFIGURE, (const char *)packet, MAVLINK_MSG_ID_MOUNT_CONFIGURE_MIN_LEN, MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN, MAVLINK_MSG_ID_MOUNT_CONFIGURE_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE MOUNT_CONFIGURE UNPACKING
+
+
+/**
+ * @brief Get field target_system from mount_configure message
+ *
+ * @return System ID.
+ */
+static inline uint8_t mavlink_msg_mount_configure_get_target_system(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 0);
+}
+
+/**
+ * @brief Get field target_component from mount_configure message
+ *
+ * @return Component ID.
+ */
+static inline uint8_t mavlink_msg_mount_configure_get_target_component(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 1);
+}
+
+/**
+ * @brief Get field mount_mode from mount_configure message
+ *
+ * @return Mount operating mode.
+ */
+static inline uint8_t mavlink_msg_mount_configure_get_mount_mode(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 2);
+}
+
+/**
+ * @brief Get field stab_roll from mount_configure message
+ *
+ * @return (1 = yes, 0 = no).
+ */
+static inline uint8_t mavlink_msg_mount_configure_get_stab_roll(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 3);
+}
+
+/**
+ * @brief Get field stab_pitch from mount_configure message
+ *
+ * @return (1 = yes, 0 = no).
+ */
+static inline uint8_t mavlink_msg_mount_configure_get_stab_pitch(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 4);
+}
+
+/**
+ * @brief Get field stab_yaw from mount_configure message
+ *
+ * @return (1 = yes, 0 = no).
+ */
+static inline uint8_t mavlink_msg_mount_configure_get_stab_yaw(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 5);
+}
+
+/**
+ * @brief Decode a mount_configure message into a struct
+ *
+ * @param msg The message to decode
+ * @param mount_configure C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_mount_configure_decode(const mavlink_message_t* msg, mavlink_mount_configure_t* mount_configure)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mount_configure->target_system = mavlink_msg_mount_configure_get_target_system(msg);
+ mount_configure->target_component = mavlink_msg_mount_configure_get_target_component(msg);
+ mount_configure->mount_mode = mavlink_msg_mount_configure_get_mount_mode(msg);
+ mount_configure->stab_roll = mavlink_msg_mount_configure_get_stab_roll(msg);
+ mount_configure->stab_pitch = mavlink_msg_mount_configure_get_stab_pitch(msg);
+ mount_configure->stab_yaw = mavlink_msg_mount_configure_get_stab_yaw(msg);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN? msg->len : MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN;
+ memset(mount_configure, 0, MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN);
+ memcpy(mount_configure, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/ardupilotmega/mavlink_msg_mount_control.h b/lib/main/MAVLink/ardupilotmega/mavlink_msg_mount_control.h
new file mode 100644
index 00000000000..65ec6304077
--- /dev/null
+++ b/lib/main/MAVLink/ardupilotmega/mavlink_msg_mount_control.h
@@ -0,0 +1,400 @@
+#pragma once
+// MESSAGE MOUNT_CONTROL PACKING
+
+#define MAVLINK_MSG_ID_MOUNT_CONTROL 157
+
+
+typedef struct __mavlink_mount_control_t {
+ int32_t input_a; /*< Pitch (centi-degrees) or lat (degE7), depending on mount mode.*/
+ int32_t input_b; /*< Roll (centi-degrees) or lon (degE7) depending on mount mode.*/
+ int32_t input_c; /*< Yaw (centi-degrees) or alt (cm) depending on mount mode.*/
+ uint8_t target_system; /*< System ID.*/
+ uint8_t target_component; /*< Component ID.*/
+ uint8_t save_position; /*< If "1" it will save current trimmed position on EEPROM (just valid for NEUTRAL and LANDING).*/
+} mavlink_mount_control_t;
+
+#define MAVLINK_MSG_ID_MOUNT_CONTROL_LEN 15
+#define MAVLINK_MSG_ID_MOUNT_CONTROL_MIN_LEN 15
+#define MAVLINK_MSG_ID_157_LEN 15
+#define MAVLINK_MSG_ID_157_MIN_LEN 15
+
+#define MAVLINK_MSG_ID_MOUNT_CONTROL_CRC 21
+#define MAVLINK_MSG_ID_157_CRC 21
+
+
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_MOUNT_CONTROL { \
+ 157, \
+ "MOUNT_CONTROL", \
+ 6, \
+ { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_mount_control_t, target_system) }, \
+ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_mount_control_t, target_component) }, \
+ { "input_a", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_mount_control_t, input_a) }, \
+ { "input_b", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_mount_control_t, input_b) }, \
+ { "input_c", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_mount_control_t, input_c) }, \
+ { "save_position", NULL, MAVLINK_TYPE_UINT8_T, 0, 14, offsetof(mavlink_mount_control_t, save_position) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_MOUNT_CONTROL { \
+ "MOUNT_CONTROL", \
+ 6, \
+ { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_mount_control_t, target_system) }, \
+ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_mount_control_t, target_component) }, \
+ { "input_a", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_mount_control_t, input_a) }, \
+ { "input_b", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_mount_control_t, input_b) }, \
+ { "input_c", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_mount_control_t, input_c) }, \
+ { "save_position", NULL, MAVLINK_TYPE_UINT8_T, 0, 14, offsetof(mavlink_mount_control_t, save_position) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a mount_control 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 target_system System ID.
+ * @param target_component Component ID.
+ * @param input_a Pitch (centi-degrees) or lat (degE7), depending on mount mode.
+ * @param input_b Roll (centi-degrees) or lon (degE7) depending on mount mode.
+ * @param input_c Yaw (centi-degrees) or alt (cm) depending on mount mode.
+ * @param save_position If "1" it will save current trimmed position on EEPROM (just valid for NEUTRAL and LANDING).
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_mount_control_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint8_t target_system, uint8_t target_component, int32_t input_a, int32_t input_b, int32_t input_c, uint8_t save_position)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_MOUNT_CONTROL_LEN];
+ _mav_put_int32_t(buf, 0, input_a);
+ _mav_put_int32_t(buf, 4, input_b);
+ _mav_put_int32_t(buf, 8, input_c);
+ _mav_put_uint8_t(buf, 12, target_system);
+ _mav_put_uint8_t(buf, 13, target_component);
+ _mav_put_uint8_t(buf, 14, save_position);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MOUNT_CONTROL_LEN);
+#else
+ mavlink_mount_control_t packet;
+ packet.input_a = input_a;
+ packet.input_b = input_b;
+ packet.input_c = input_c;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.save_position = save_position;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MOUNT_CONTROL_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_MOUNT_CONTROL;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MOUNT_CONTROL_MIN_LEN, MAVLINK_MSG_ID_MOUNT_CONTROL_LEN, MAVLINK_MSG_ID_MOUNT_CONTROL_CRC);
+}
+
+/**
+ * @brief Pack a mount_control 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 target_system System ID.
+ * @param target_component Component ID.
+ * @param input_a Pitch (centi-degrees) or lat (degE7), depending on mount mode.
+ * @param input_b Roll (centi-degrees) or lon (degE7) depending on mount mode.
+ * @param input_c Yaw (centi-degrees) or alt (cm) depending on mount mode.
+ * @param save_position If "1" it will save current trimmed position on EEPROM (just valid for NEUTRAL and LANDING).
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_mount_control_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ uint8_t target_system, uint8_t target_component, int32_t input_a, int32_t input_b, int32_t input_c, uint8_t save_position)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_MOUNT_CONTROL_LEN];
+ _mav_put_int32_t(buf, 0, input_a);
+ _mav_put_int32_t(buf, 4, input_b);
+ _mav_put_int32_t(buf, 8, input_c);
+ _mav_put_uint8_t(buf, 12, target_system);
+ _mav_put_uint8_t(buf, 13, target_component);
+ _mav_put_uint8_t(buf, 14, save_position);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MOUNT_CONTROL_LEN);
+#else
+ mavlink_mount_control_t packet;
+ packet.input_a = input_a;
+ packet.input_b = input_b;
+ packet.input_c = input_c;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.save_position = save_position;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MOUNT_CONTROL_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_MOUNT_CONTROL;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_MOUNT_CONTROL_MIN_LEN, MAVLINK_MSG_ID_MOUNT_CONTROL_LEN, MAVLINK_MSG_ID_MOUNT_CONTROL_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_MOUNT_CONTROL_MIN_LEN, MAVLINK_MSG_ID_MOUNT_CONTROL_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a mount_control 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 target_system System ID.
+ * @param target_component Component ID.
+ * @param input_a Pitch (centi-degrees) or lat (degE7), depending on mount mode.
+ * @param input_b Roll (centi-degrees) or lon (degE7) depending on mount mode.
+ * @param input_c Yaw (centi-degrees) or alt (cm) depending on mount mode.
+ * @param save_position If "1" it will save current trimmed position on EEPROM (just valid for NEUTRAL and LANDING).
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_mount_control_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint8_t target_system,uint8_t target_component,int32_t input_a,int32_t input_b,int32_t input_c,uint8_t save_position)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_MOUNT_CONTROL_LEN];
+ _mav_put_int32_t(buf, 0, input_a);
+ _mav_put_int32_t(buf, 4, input_b);
+ _mav_put_int32_t(buf, 8, input_c);
+ _mav_put_uint8_t(buf, 12, target_system);
+ _mav_put_uint8_t(buf, 13, target_component);
+ _mav_put_uint8_t(buf, 14, save_position);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MOUNT_CONTROL_LEN);
+#else
+ mavlink_mount_control_t packet;
+ packet.input_a = input_a;
+ packet.input_b = input_b;
+ packet.input_c = input_c;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.save_position = save_position;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MOUNT_CONTROL_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_MOUNT_CONTROL;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MOUNT_CONTROL_MIN_LEN, MAVLINK_MSG_ID_MOUNT_CONTROL_LEN, MAVLINK_MSG_ID_MOUNT_CONTROL_CRC);
+}
+
+/**
+ * @brief Encode a mount_control 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 mount_control C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_mount_control_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mount_control_t* mount_control)
+{
+ return mavlink_msg_mount_control_pack(system_id, component_id, msg, mount_control->target_system, mount_control->target_component, mount_control->input_a, mount_control->input_b, mount_control->input_c, mount_control->save_position);
+}
+
+/**
+ * @brief Encode a mount_control 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 mount_control C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_mount_control_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mount_control_t* mount_control)
+{
+ return mavlink_msg_mount_control_pack_chan(system_id, component_id, chan, msg, mount_control->target_system, mount_control->target_component, mount_control->input_a, mount_control->input_b, mount_control->input_c, mount_control->save_position);
+}
+
+/**
+ * @brief Encode a mount_control 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 mount_control C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_mount_control_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_mount_control_t* mount_control)
+{
+ return mavlink_msg_mount_control_pack_status(system_id, component_id, _status, msg, mount_control->target_system, mount_control->target_component, mount_control->input_a, mount_control->input_b, mount_control->input_c, mount_control->save_position);
+}
+
+/**
+ * @brief Send a mount_control message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param target_system System ID.
+ * @param target_component Component ID.
+ * @param input_a Pitch (centi-degrees) or lat (degE7), depending on mount mode.
+ * @param input_b Roll (centi-degrees) or lon (degE7) depending on mount mode.
+ * @param input_c Yaw (centi-degrees) or alt (cm) depending on mount mode.
+ * @param save_position If "1" it will save current trimmed position on EEPROM (just valid for NEUTRAL and LANDING).
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_mount_control_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, int32_t input_a, int32_t input_b, int32_t input_c, uint8_t save_position)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_MOUNT_CONTROL_LEN];
+ _mav_put_int32_t(buf, 0, input_a);
+ _mav_put_int32_t(buf, 4, input_b);
+ _mav_put_int32_t(buf, 8, input_c);
+ _mav_put_uint8_t(buf, 12, target_system);
+ _mav_put_uint8_t(buf, 13, target_component);
+ _mav_put_uint8_t(buf, 14, save_position);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_CONTROL, buf, MAVLINK_MSG_ID_MOUNT_CONTROL_MIN_LEN, MAVLINK_MSG_ID_MOUNT_CONTROL_LEN, MAVLINK_MSG_ID_MOUNT_CONTROL_CRC);
+#else
+ mavlink_mount_control_t packet;
+ packet.input_a = input_a;
+ packet.input_b = input_b;
+ packet.input_c = input_c;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.save_position = save_position;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_CONTROL, (const char *)&packet, MAVLINK_MSG_ID_MOUNT_CONTROL_MIN_LEN, MAVLINK_MSG_ID_MOUNT_CONTROL_LEN, MAVLINK_MSG_ID_MOUNT_CONTROL_CRC);
+#endif
+}
+
+/**
+ * @brief Send a mount_control message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_mount_control_send_struct(mavlink_channel_t chan, const mavlink_mount_control_t* mount_control)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_mount_control_send(chan, mount_control->target_system, mount_control->target_component, mount_control->input_a, mount_control->input_b, mount_control->input_c, mount_control->save_position);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_CONTROL, (const char *)mount_control, MAVLINK_MSG_ID_MOUNT_CONTROL_MIN_LEN, MAVLINK_MSG_ID_MOUNT_CONTROL_LEN, MAVLINK_MSG_ID_MOUNT_CONTROL_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_MOUNT_CONTROL_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_mount_control_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, int32_t input_a, int32_t input_b, int32_t input_c, uint8_t save_position)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_int32_t(buf, 0, input_a);
+ _mav_put_int32_t(buf, 4, input_b);
+ _mav_put_int32_t(buf, 8, input_c);
+ _mav_put_uint8_t(buf, 12, target_system);
+ _mav_put_uint8_t(buf, 13, target_component);
+ _mav_put_uint8_t(buf, 14, save_position);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_CONTROL, buf, MAVLINK_MSG_ID_MOUNT_CONTROL_MIN_LEN, MAVLINK_MSG_ID_MOUNT_CONTROL_LEN, MAVLINK_MSG_ID_MOUNT_CONTROL_CRC);
+#else
+ mavlink_mount_control_t *packet = (mavlink_mount_control_t *)msgbuf;
+ packet->input_a = input_a;
+ packet->input_b = input_b;
+ packet->input_c = input_c;
+ packet->target_system = target_system;
+ packet->target_component = target_component;
+ packet->save_position = save_position;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_CONTROL, (const char *)packet, MAVLINK_MSG_ID_MOUNT_CONTROL_MIN_LEN, MAVLINK_MSG_ID_MOUNT_CONTROL_LEN, MAVLINK_MSG_ID_MOUNT_CONTROL_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE MOUNT_CONTROL UNPACKING
+
+
+/**
+ * @brief Get field target_system from mount_control message
+ *
+ * @return System ID.
+ */
+static inline uint8_t mavlink_msg_mount_control_get_target_system(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 12);
+}
+
+/**
+ * @brief Get field target_component from mount_control message
+ *
+ * @return Component ID.
+ */
+static inline uint8_t mavlink_msg_mount_control_get_target_component(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 13);
+}
+
+/**
+ * @brief Get field input_a from mount_control message
+ *
+ * @return Pitch (centi-degrees) or lat (degE7), depending on mount mode.
+ */
+static inline int32_t mavlink_msg_mount_control_get_input_a(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_int32_t(msg, 0);
+}
+
+/**
+ * @brief Get field input_b from mount_control message
+ *
+ * @return Roll (centi-degrees) or lon (degE7) depending on mount mode.
+ */
+static inline int32_t mavlink_msg_mount_control_get_input_b(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_int32_t(msg, 4);
+}
+
+/**
+ * @brief Get field input_c from mount_control message
+ *
+ * @return Yaw (centi-degrees) or alt (cm) depending on mount mode.
+ */
+static inline int32_t mavlink_msg_mount_control_get_input_c(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_int32_t(msg, 8);
+}
+
+/**
+ * @brief Get field save_position from mount_control message
+ *
+ * @return If "1" it will save current trimmed position on EEPROM (just valid for NEUTRAL and LANDING).
+ */
+static inline uint8_t mavlink_msg_mount_control_get_save_position(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 14);
+}
+
+/**
+ * @brief Decode a mount_control message into a struct
+ *
+ * @param msg The message to decode
+ * @param mount_control C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_mount_control_decode(const mavlink_message_t* msg, mavlink_mount_control_t* mount_control)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mount_control->input_a = mavlink_msg_mount_control_get_input_a(msg);
+ mount_control->input_b = mavlink_msg_mount_control_get_input_b(msg);
+ mount_control->input_c = mavlink_msg_mount_control_get_input_c(msg);
+ mount_control->target_system = mavlink_msg_mount_control_get_target_system(msg);
+ mount_control->target_component = mavlink_msg_mount_control_get_target_component(msg);
+ mount_control->save_position = mavlink_msg_mount_control_get_save_position(msg);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_MOUNT_CONTROL_LEN? msg->len : MAVLINK_MSG_ID_MOUNT_CONTROL_LEN;
+ memset(mount_control, 0, MAVLINK_MSG_ID_MOUNT_CONTROL_LEN);
+ memcpy(mount_control, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/ardupilotmega/mavlink_msg_mount_status.h b/lib/main/MAVLink/ardupilotmega/mavlink_msg_mount_status.h
new file mode 100644
index 00000000000..344cf3508b9
--- /dev/null
+++ b/lib/main/MAVLink/ardupilotmega/mavlink_msg_mount_status.h
@@ -0,0 +1,400 @@
+#pragma once
+// MESSAGE MOUNT_STATUS PACKING
+
+#define MAVLINK_MSG_ID_MOUNT_STATUS 158
+
+
+typedef struct __mavlink_mount_status_t {
+ int32_t pointing_a; /*< [cdeg] Pitch.*/
+ int32_t pointing_b; /*< [cdeg] Roll.*/
+ int32_t pointing_c; /*< [cdeg] Yaw.*/
+ uint8_t target_system; /*< System ID.*/
+ uint8_t target_component; /*< Component ID.*/
+ uint8_t mount_mode; /*< Mount operating mode.*/
+} mavlink_mount_status_t;
+
+#define MAVLINK_MSG_ID_MOUNT_STATUS_LEN 15
+#define MAVLINK_MSG_ID_MOUNT_STATUS_MIN_LEN 14
+#define MAVLINK_MSG_ID_158_LEN 15
+#define MAVLINK_MSG_ID_158_MIN_LEN 14
+
+#define MAVLINK_MSG_ID_MOUNT_STATUS_CRC 134
+#define MAVLINK_MSG_ID_158_CRC 134
+
+
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_MOUNT_STATUS { \
+ 158, \
+ "MOUNT_STATUS", \
+ 6, \
+ { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_mount_status_t, target_system) }, \
+ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_mount_status_t, target_component) }, \
+ { "pointing_a", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_mount_status_t, pointing_a) }, \
+ { "pointing_b", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_mount_status_t, pointing_b) }, \
+ { "pointing_c", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_mount_status_t, pointing_c) }, \
+ { "mount_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 14, offsetof(mavlink_mount_status_t, mount_mode) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_MOUNT_STATUS { \
+ "MOUNT_STATUS", \
+ 6, \
+ { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_mount_status_t, target_system) }, \
+ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_mount_status_t, target_component) }, \
+ { "pointing_a", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_mount_status_t, pointing_a) }, \
+ { "pointing_b", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_mount_status_t, pointing_b) }, \
+ { "pointing_c", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_mount_status_t, pointing_c) }, \
+ { "mount_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 14, offsetof(mavlink_mount_status_t, mount_mode) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a mount_status 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 target_system System ID.
+ * @param target_component Component ID.
+ * @param pointing_a [cdeg] Pitch.
+ * @param pointing_b [cdeg] Roll.
+ * @param pointing_c [cdeg] Yaw.
+ * @param mount_mode Mount operating mode.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_mount_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint8_t target_system, uint8_t target_component, int32_t pointing_a, int32_t pointing_b, int32_t pointing_c, uint8_t mount_mode)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_MOUNT_STATUS_LEN];
+ _mav_put_int32_t(buf, 0, pointing_a);
+ _mav_put_int32_t(buf, 4, pointing_b);
+ _mav_put_int32_t(buf, 8, pointing_c);
+ _mav_put_uint8_t(buf, 12, target_system);
+ _mav_put_uint8_t(buf, 13, target_component);
+ _mav_put_uint8_t(buf, 14, mount_mode);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MOUNT_STATUS_LEN);
+#else
+ mavlink_mount_status_t packet;
+ packet.pointing_a = pointing_a;
+ packet.pointing_b = pointing_b;
+ packet.pointing_c = pointing_c;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.mount_mode = mount_mode;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MOUNT_STATUS_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_MOUNT_STATUS;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MOUNT_STATUS_MIN_LEN, MAVLINK_MSG_ID_MOUNT_STATUS_LEN, MAVLINK_MSG_ID_MOUNT_STATUS_CRC);
+}
+
+/**
+ * @brief Pack a mount_status 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 target_system System ID.
+ * @param target_component Component ID.
+ * @param pointing_a [cdeg] Pitch.
+ * @param pointing_b [cdeg] Roll.
+ * @param pointing_c [cdeg] Yaw.
+ * @param mount_mode Mount operating mode.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_mount_status_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ uint8_t target_system, uint8_t target_component, int32_t pointing_a, int32_t pointing_b, int32_t pointing_c, uint8_t mount_mode)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_MOUNT_STATUS_LEN];
+ _mav_put_int32_t(buf, 0, pointing_a);
+ _mav_put_int32_t(buf, 4, pointing_b);
+ _mav_put_int32_t(buf, 8, pointing_c);
+ _mav_put_uint8_t(buf, 12, target_system);
+ _mav_put_uint8_t(buf, 13, target_component);
+ _mav_put_uint8_t(buf, 14, mount_mode);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MOUNT_STATUS_LEN);
+#else
+ mavlink_mount_status_t packet;
+ packet.pointing_a = pointing_a;
+ packet.pointing_b = pointing_b;
+ packet.pointing_c = pointing_c;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.mount_mode = mount_mode;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MOUNT_STATUS_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_MOUNT_STATUS;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_MOUNT_STATUS_MIN_LEN, MAVLINK_MSG_ID_MOUNT_STATUS_LEN, MAVLINK_MSG_ID_MOUNT_STATUS_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_MOUNT_STATUS_MIN_LEN, MAVLINK_MSG_ID_MOUNT_STATUS_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a mount_status 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 target_system System ID.
+ * @param target_component Component ID.
+ * @param pointing_a [cdeg] Pitch.
+ * @param pointing_b [cdeg] Roll.
+ * @param pointing_c [cdeg] Yaw.
+ * @param mount_mode Mount operating mode.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_mount_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint8_t target_system,uint8_t target_component,int32_t pointing_a,int32_t pointing_b,int32_t pointing_c,uint8_t mount_mode)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_MOUNT_STATUS_LEN];
+ _mav_put_int32_t(buf, 0, pointing_a);
+ _mav_put_int32_t(buf, 4, pointing_b);
+ _mav_put_int32_t(buf, 8, pointing_c);
+ _mav_put_uint8_t(buf, 12, target_system);
+ _mav_put_uint8_t(buf, 13, target_component);
+ _mav_put_uint8_t(buf, 14, mount_mode);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MOUNT_STATUS_LEN);
+#else
+ mavlink_mount_status_t packet;
+ packet.pointing_a = pointing_a;
+ packet.pointing_b = pointing_b;
+ packet.pointing_c = pointing_c;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.mount_mode = mount_mode;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MOUNT_STATUS_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_MOUNT_STATUS;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MOUNT_STATUS_MIN_LEN, MAVLINK_MSG_ID_MOUNT_STATUS_LEN, MAVLINK_MSG_ID_MOUNT_STATUS_CRC);
+}
+
+/**
+ * @brief Encode a mount_status 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 mount_status C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_mount_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mount_status_t* mount_status)
+{
+ return mavlink_msg_mount_status_pack(system_id, component_id, msg, mount_status->target_system, mount_status->target_component, mount_status->pointing_a, mount_status->pointing_b, mount_status->pointing_c, mount_status->mount_mode);
+}
+
+/**
+ * @brief Encode a mount_status 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 mount_status C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_mount_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mount_status_t* mount_status)
+{
+ return mavlink_msg_mount_status_pack_chan(system_id, component_id, chan, msg, mount_status->target_system, mount_status->target_component, mount_status->pointing_a, mount_status->pointing_b, mount_status->pointing_c, mount_status->mount_mode);
+}
+
+/**
+ * @brief Encode a mount_status 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 mount_status C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_mount_status_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_mount_status_t* mount_status)
+{
+ return mavlink_msg_mount_status_pack_status(system_id, component_id, _status, msg, mount_status->target_system, mount_status->target_component, mount_status->pointing_a, mount_status->pointing_b, mount_status->pointing_c, mount_status->mount_mode);
+}
+
+/**
+ * @brief Send a mount_status message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param target_system System ID.
+ * @param target_component Component ID.
+ * @param pointing_a [cdeg] Pitch.
+ * @param pointing_b [cdeg] Roll.
+ * @param pointing_c [cdeg] Yaw.
+ * @param mount_mode Mount operating mode.
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_mount_status_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, int32_t pointing_a, int32_t pointing_b, int32_t pointing_c, uint8_t mount_mode)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_MOUNT_STATUS_LEN];
+ _mav_put_int32_t(buf, 0, pointing_a);
+ _mav_put_int32_t(buf, 4, pointing_b);
+ _mav_put_int32_t(buf, 8, pointing_c);
+ _mav_put_uint8_t(buf, 12, target_system);
+ _mav_put_uint8_t(buf, 13, target_component);
+ _mav_put_uint8_t(buf, 14, mount_mode);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_STATUS, buf, MAVLINK_MSG_ID_MOUNT_STATUS_MIN_LEN, MAVLINK_MSG_ID_MOUNT_STATUS_LEN, MAVLINK_MSG_ID_MOUNT_STATUS_CRC);
+#else
+ mavlink_mount_status_t packet;
+ packet.pointing_a = pointing_a;
+ packet.pointing_b = pointing_b;
+ packet.pointing_c = pointing_c;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.mount_mode = mount_mode;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_STATUS, (const char *)&packet, MAVLINK_MSG_ID_MOUNT_STATUS_MIN_LEN, MAVLINK_MSG_ID_MOUNT_STATUS_LEN, MAVLINK_MSG_ID_MOUNT_STATUS_CRC);
+#endif
+}
+
+/**
+ * @brief Send a mount_status message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_mount_status_send_struct(mavlink_channel_t chan, const mavlink_mount_status_t* mount_status)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_mount_status_send(chan, mount_status->target_system, mount_status->target_component, mount_status->pointing_a, mount_status->pointing_b, mount_status->pointing_c, mount_status->mount_mode);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_STATUS, (const char *)mount_status, MAVLINK_MSG_ID_MOUNT_STATUS_MIN_LEN, MAVLINK_MSG_ID_MOUNT_STATUS_LEN, MAVLINK_MSG_ID_MOUNT_STATUS_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_MOUNT_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_mount_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, int32_t pointing_a, int32_t pointing_b, int32_t pointing_c, uint8_t mount_mode)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_int32_t(buf, 0, pointing_a);
+ _mav_put_int32_t(buf, 4, pointing_b);
+ _mav_put_int32_t(buf, 8, pointing_c);
+ _mav_put_uint8_t(buf, 12, target_system);
+ _mav_put_uint8_t(buf, 13, target_component);
+ _mav_put_uint8_t(buf, 14, mount_mode);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_STATUS, buf, MAVLINK_MSG_ID_MOUNT_STATUS_MIN_LEN, MAVLINK_MSG_ID_MOUNT_STATUS_LEN, MAVLINK_MSG_ID_MOUNT_STATUS_CRC);
+#else
+ mavlink_mount_status_t *packet = (mavlink_mount_status_t *)msgbuf;
+ packet->pointing_a = pointing_a;
+ packet->pointing_b = pointing_b;
+ packet->pointing_c = pointing_c;
+ packet->target_system = target_system;
+ packet->target_component = target_component;
+ packet->mount_mode = mount_mode;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_STATUS, (const char *)packet, MAVLINK_MSG_ID_MOUNT_STATUS_MIN_LEN, MAVLINK_MSG_ID_MOUNT_STATUS_LEN, MAVLINK_MSG_ID_MOUNT_STATUS_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE MOUNT_STATUS UNPACKING
+
+
+/**
+ * @brief Get field target_system from mount_status message
+ *
+ * @return System ID.
+ */
+static inline uint8_t mavlink_msg_mount_status_get_target_system(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 12);
+}
+
+/**
+ * @brief Get field target_component from mount_status message
+ *
+ * @return Component ID.
+ */
+static inline uint8_t mavlink_msg_mount_status_get_target_component(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 13);
+}
+
+/**
+ * @brief Get field pointing_a from mount_status message
+ *
+ * @return [cdeg] Pitch.
+ */
+static inline int32_t mavlink_msg_mount_status_get_pointing_a(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_int32_t(msg, 0);
+}
+
+/**
+ * @brief Get field pointing_b from mount_status message
+ *
+ * @return [cdeg] Roll.
+ */
+static inline int32_t mavlink_msg_mount_status_get_pointing_b(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_int32_t(msg, 4);
+}
+
+/**
+ * @brief Get field pointing_c from mount_status message
+ *
+ * @return [cdeg] Yaw.
+ */
+static inline int32_t mavlink_msg_mount_status_get_pointing_c(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_int32_t(msg, 8);
+}
+
+/**
+ * @brief Get field mount_mode from mount_status message
+ *
+ * @return Mount operating mode.
+ */
+static inline uint8_t mavlink_msg_mount_status_get_mount_mode(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 14);
+}
+
+/**
+ * @brief Decode a mount_status message into a struct
+ *
+ * @param msg The message to decode
+ * @param mount_status C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_mount_status_decode(const mavlink_message_t* msg, mavlink_mount_status_t* mount_status)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mount_status->pointing_a = mavlink_msg_mount_status_get_pointing_a(msg);
+ mount_status->pointing_b = mavlink_msg_mount_status_get_pointing_b(msg);
+ mount_status->pointing_c = mavlink_msg_mount_status_get_pointing_c(msg);
+ mount_status->target_system = mavlink_msg_mount_status_get_target_system(msg);
+ mount_status->target_component = mavlink_msg_mount_status_get_target_component(msg);
+ mount_status->mount_mode = mavlink_msg_mount_status_get_mount_mode(msg);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_MOUNT_STATUS_LEN? msg->len : MAVLINK_MSG_ID_MOUNT_STATUS_LEN;
+ memset(mount_status, 0, MAVLINK_MSG_ID_MOUNT_STATUS_LEN);
+ memcpy(mount_status, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/ardupilotmega/mavlink_msg_named_value_string.h b/lib/main/MAVLink/ardupilotmega/mavlink_msg_named_value_string.h
new file mode 100644
index 00000000000..7db5cdeaa90
--- /dev/null
+++ b/lib/main/MAVLink/ardupilotmega/mavlink_msg_named_value_string.h
@@ -0,0 +1,307 @@
+#pragma once
+// MESSAGE NAMED_VALUE_STRING PACKING
+
+#define MAVLINK_MSG_ID_NAMED_VALUE_STRING 11060
+
+
+typedef struct __mavlink_named_value_string_t {
+ uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/
+ char name[10]; /*< Name of the debug variable*/
+ char value[64]; /*< Value of the debug variable*/
+} mavlink_named_value_string_t;
+
+#define MAVLINK_MSG_ID_NAMED_VALUE_STRING_LEN 78
+#define MAVLINK_MSG_ID_NAMED_VALUE_STRING_MIN_LEN 78
+#define MAVLINK_MSG_ID_11060_LEN 78
+#define MAVLINK_MSG_ID_11060_MIN_LEN 78
+
+#define MAVLINK_MSG_ID_NAMED_VALUE_STRING_CRC 162
+#define MAVLINK_MSG_ID_11060_CRC 162
+
+#define MAVLINK_MSG_NAMED_VALUE_STRING_FIELD_NAME_LEN 10
+#define MAVLINK_MSG_NAMED_VALUE_STRING_FIELD_VALUE_LEN 64
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_NAMED_VALUE_STRING { \
+ 11060, \
+ "NAMED_VALUE_STRING", \
+ 3, \
+ { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_named_value_string_t, time_boot_ms) }, \
+ { "name", NULL, MAVLINK_TYPE_CHAR, 10, 4, offsetof(mavlink_named_value_string_t, name) }, \
+ { "value", NULL, MAVLINK_TYPE_CHAR, 64, 14, offsetof(mavlink_named_value_string_t, value) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_NAMED_VALUE_STRING { \
+ "NAMED_VALUE_STRING", \
+ 3, \
+ { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_named_value_string_t, time_boot_ms) }, \
+ { "name", NULL, MAVLINK_TYPE_CHAR, 10, 4, offsetof(mavlink_named_value_string_t, name) }, \
+ { "value", NULL, MAVLINK_TYPE_CHAR, 64, 14, offsetof(mavlink_named_value_string_t, value) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a named_value_string 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 time_boot_ms [ms] Timestamp (time since system boot).
+ * @param name Name of the debug variable
+ * @param value Value of the debug variable
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_named_value_string_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint32_t time_boot_ms, const char *name, const char *value)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_NAMED_VALUE_STRING_LEN];
+ _mav_put_uint32_t(buf, 0, time_boot_ms);
+ _mav_put_char_array(buf, 4, name, 10);
+ _mav_put_char_array(buf, 14, value, 64);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_NAMED_VALUE_STRING_LEN);
+#else
+ mavlink_named_value_string_t packet;
+ packet.time_boot_ms = time_boot_ms;
+ mav_array_assign_char(packet.name, name, 10);
+ mav_array_assign_char(packet.value, value, 64);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_NAMED_VALUE_STRING_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_NAMED_VALUE_STRING;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_NAMED_VALUE_STRING_MIN_LEN, MAVLINK_MSG_ID_NAMED_VALUE_STRING_LEN, MAVLINK_MSG_ID_NAMED_VALUE_STRING_CRC);
+}
+
+/**
+ * @brief Pack a named_value_string 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 time_boot_ms [ms] Timestamp (time since system boot).
+ * @param name Name of the debug variable
+ * @param value Value of the debug variable
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_named_value_string_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ uint32_t time_boot_ms, const char *name, const char *value)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_NAMED_VALUE_STRING_LEN];
+ _mav_put_uint32_t(buf, 0, time_boot_ms);
+ _mav_put_char_array(buf, 4, name, 10);
+ _mav_put_char_array(buf, 14, value, 64);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_NAMED_VALUE_STRING_LEN);
+#else
+ mavlink_named_value_string_t packet;
+ packet.time_boot_ms = time_boot_ms;
+ mav_array_memcpy(packet.name, name, sizeof(char)*10);
+ mav_array_memcpy(packet.value, value, sizeof(char)*64);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_NAMED_VALUE_STRING_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_NAMED_VALUE_STRING;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_NAMED_VALUE_STRING_MIN_LEN, MAVLINK_MSG_ID_NAMED_VALUE_STRING_LEN, MAVLINK_MSG_ID_NAMED_VALUE_STRING_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_NAMED_VALUE_STRING_MIN_LEN, MAVLINK_MSG_ID_NAMED_VALUE_STRING_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a named_value_string 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 time_boot_ms [ms] Timestamp (time since system boot).
+ * @param name Name of the debug variable
+ * @param value Value of the debug variable
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_named_value_string_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint32_t time_boot_ms,const char *name,const char *value)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_NAMED_VALUE_STRING_LEN];
+ _mav_put_uint32_t(buf, 0, time_boot_ms);
+ _mav_put_char_array(buf, 4, name, 10);
+ _mav_put_char_array(buf, 14, value, 64);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_NAMED_VALUE_STRING_LEN);
+#else
+ mavlink_named_value_string_t packet;
+ packet.time_boot_ms = time_boot_ms;
+ mav_array_assign_char(packet.name, name, 10);
+ mav_array_assign_char(packet.value, value, 64);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_NAMED_VALUE_STRING_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_NAMED_VALUE_STRING;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_NAMED_VALUE_STRING_MIN_LEN, MAVLINK_MSG_ID_NAMED_VALUE_STRING_LEN, MAVLINK_MSG_ID_NAMED_VALUE_STRING_CRC);
+}
+
+/**
+ * @brief Encode a named_value_string 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 named_value_string C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_named_value_string_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_named_value_string_t* named_value_string)
+{
+ return mavlink_msg_named_value_string_pack(system_id, component_id, msg, named_value_string->time_boot_ms, named_value_string->name, named_value_string->value);
+}
+
+/**
+ * @brief Encode a named_value_string 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 named_value_string C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_named_value_string_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_named_value_string_t* named_value_string)
+{
+ return mavlink_msg_named_value_string_pack_chan(system_id, component_id, chan, msg, named_value_string->time_boot_ms, named_value_string->name, named_value_string->value);
+}
+
+/**
+ * @brief Encode a named_value_string 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 named_value_string C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_named_value_string_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_named_value_string_t* named_value_string)
+{
+ return mavlink_msg_named_value_string_pack_status(system_id, component_id, _status, msg, named_value_string->time_boot_ms, named_value_string->name, named_value_string->value);
+}
+
+/**
+ * @brief Send a named_value_string message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param time_boot_ms [ms] Timestamp (time since system boot).
+ * @param name Name of the debug variable
+ * @param value Value of the debug variable
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_named_value_string_send(mavlink_channel_t chan, uint32_t time_boot_ms, const char *name, const char *value)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_NAMED_VALUE_STRING_LEN];
+ _mav_put_uint32_t(buf, 0, time_boot_ms);
+ _mav_put_char_array(buf, 4, name, 10);
+ _mav_put_char_array(buf, 14, value, 64);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_STRING, buf, MAVLINK_MSG_ID_NAMED_VALUE_STRING_MIN_LEN, MAVLINK_MSG_ID_NAMED_VALUE_STRING_LEN, MAVLINK_MSG_ID_NAMED_VALUE_STRING_CRC);
+#else
+ mavlink_named_value_string_t packet;
+ packet.time_boot_ms = time_boot_ms;
+ mav_array_assign_char(packet.name, name, 10);
+ mav_array_assign_char(packet.value, value, 64);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_STRING, (const char *)&packet, MAVLINK_MSG_ID_NAMED_VALUE_STRING_MIN_LEN, MAVLINK_MSG_ID_NAMED_VALUE_STRING_LEN, MAVLINK_MSG_ID_NAMED_VALUE_STRING_CRC);
+#endif
+}
+
+/**
+ * @brief Send a named_value_string message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_named_value_string_send_struct(mavlink_channel_t chan, const mavlink_named_value_string_t* named_value_string)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_named_value_string_send(chan, named_value_string->time_boot_ms, named_value_string->name, named_value_string->value);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_STRING, (const char *)named_value_string, MAVLINK_MSG_ID_NAMED_VALUE_STRING_MIN_LEN, MAVLINK_MSG_ID_NAMED_VALUE_STRING_LEN, MAVLINK_MSG_ID_NAMED_VALUE_STRING_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_NAMED_VALUE_STRING_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_named_value_string_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, const char *name, const char *value)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint32_t(buf, 0, time_boot_ms);
+ _mav_put_char_array(buf, 4, name, 10);
+ _mav_put_char_array(buf, 14, value, 64);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_STRING, buf, MAVLINK_MSG_ID_NAMED_VALUE_STRING_MIN_LEN, MAVLINK_MSG_ID_NAMED_VALUE_STRING_LEN, MAVLINK_MSG_ID_NAMED_VALUE_STRING_CRC);
+#else
+ mavlink_named_value_string_t *packet = (mavlink_named_value_string_t *)msgbuf;
+ packet->time_boot_ms = time_boot_ms;
+ mav_array_assign_char(packet->name, name, 10);
+ mav_array_assign_char(packet->value, value, 64);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_STRING, (const char *)packet, MAVLINK_MSG_ID_NAMED_VALUE_STRING_MIN_LEN, MAVLINK_MSG_ID_NAMED_VALUE_STRING_LEN, MAVLINK_MSG_ID_NAMED_VALUE_STRING_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE NAMED_VALUE_STRING UNPACKING
+
+
+/**
+ * @brief Get field time_boot_ms from named_value_string message
+ *
+ * @return [ms] Timestamp (time since system boot).
+ */
+static inline uint32_t mavlink_msg_named_value_string_get_time_boot_ms(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint32_t(msg, 0);
+}
+
+/**
+ * @brief Get field name from named_value_string message
+ *
+ * @return Name of the debug variable
+ */
+static inline uint16_t mavlink_msg_named_value_string_get_name(const mavlink_message_t* msg, char *name)
+{
+ return _MAV_RETURN_char_array(msg, name, 10, 4);
+}
+
+/**
+ * @brief Get field value from named_value_string message
+ *
+ * @return Value of the debug variable
+ */
+static inline uint16_t mavlink_msg_named_value_string_get_value(const mavlink_message_t* msg, char *value)
+{
+ return _MAV_RETURN_char_array(msg, value, 64, 14);
+}
+
+/**
+ * @brief Decode a named_value_string message into a struct
+ *
+ * @param msg The message to decode
+ * @param named_value_string C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_named_value_string_decode(const mavlink_message_t* msg, mavlink_named_value_string_t* named_value_string)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ named_value_string->time_boot_ms = mavlink_msg_named_value_string_get_time_boot_ms(msg);
+ mavlink_msg_named_value_string_get_name(msg, named_value_string->name);
+ mavlink_msg_named_value_string_get_value(msg, named_value_string->value);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_NAMED_VALUE_STRING_LEN? msg->len : MAVLINK_MSG_ID_NAMED_VALUE_STRING_LEN;
+ memset(named_value_string, 0, MAVLINK_MSG_ID_NAMED_VALUE_STRING_LEN);
+ memcpy(named_value_string, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/ardupilotmega/mavlink_msg_obstacle_distance_3d.h b/lib/main/MAVLink/ardupilotmega/mavlink_msg_obstacle_distance_3d.h
new file mode 100644
index 00000000000..ba67b21b4ca
--- /dev/null
+++ b/lib/main/MAVLink/ardupilotmega/mavlink_msg_obstacle_distance_3d.h
@@ -0,0 +1,484 @@
+#pragma once
+// MESSAGE OBSTACLE_DISTANCE_3D PACKING
+
+#define MAVLINK_MSG_ID_OBSTACLE_DISTANCE_3D 11037
+
+
+typedef struct __mavlink_obstacle_distance_3d_t {
+ uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/
+ float x; /*< [m] X position of the obstacle.*/
+ float y; /*< [m] Y position of the obstacle.*/
+ float z; /*< [m] Z position of the obstacle.*/
+ float min_distance; /*< [m] Minimum distance the sensor can measure.*/
+ float max_distance; /*< [m] Maximum distance the sensor can measure.*/
+ uint16_t obstacle_id; /*< Unique ID given to each obstacle so that its movement can be tracked. Use UINT16_MAX if object ID is unknown or cannot be determined.*/
+ uint8_t sensor_type; /*< Class id of the distance sensor type.*/
+ uint8_t frame; /*< Coordinate frame of reference.*/
+} mavlink_obstacle_distance_3d_t;
+
+#define MAVLINK_MSG_ID_OBSTACLE_DISTANCE_3D_LEN 28
+#define MAVLINK_MSG_ID_OBSTACLE_DISTANCE_3D_MIN_LEN 28
+#define MAVLINK_MSG_ID_11037_LEN 28
+#define MAVLINK_MSG_ID_11037_MIN_LEN 28
+
+#define MAVLINK_MSG_ID_OBSTACLE_DISTANCE_3D_CRC 130
+#define MAVLINK_MSG_ID_11037_CRC 130
+
+
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_OBSTACLE_DISTANCE_3D { \
+ 11037, \
+ "OBSTACLE_DISTANCE_3D", \
+ 9, \
+ { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_obstacle_distance_3d_t, time_boot_ms) }, \
+ { "sensor_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_obstacle_distance_3d_t, sensor_type) }, \
+ { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 27, offsetof(mavlink_obstacle_distance_3d_t, frame) }, \
+ { "obstacle_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_obstacle_distance_3d_t, obstacle_id) }, \
+ { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_obstacle_distance_3d_t, x) }, \
+ { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_obstacle_distance_3d_t, y) }, \
+ { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_obstacle_distance_3d_t, z) }, \
+ { "min_distance", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_obstacle_distance_3d_t, min_distance) }, \
+ { "max_distance", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_obstacle_distance_3d_t, max_distance) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_OBSTACLE_DISTANCE_3D { \
+ "OBSTACLE_DISTANCE_3D", \
+ 9, \
+ { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_obstacle_distance_3d_t, time_boot_ms) }, \
+ { "sensor_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_obstacle_distance_3d_t, sensor_type) }, \
+ { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 27, offsetof(mavlink_obstacle_distance_3d_t, frame) }, \
+ { "obstacle_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_obstacle_distance_3d_t, obstacle_id) }, \
+ { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_obstacle_distance_3d_t, x) }, \
+ { "y", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_obstacle_distance_3d_t, y) }, \
+ { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_obstacle_distance_3d_t, z) }, \
+ { "min_distance", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_obstacle_distance_3d_t, min_distance) }, \
+ { "max_distance", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_obstacle_distance_3d_t, max_distance) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a obstacle_distance_3d 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 time_boot_ms [ms] Timestamp (time since system boot).
+ * @param sensor_type Class id of the distance sensor type.
+ * @param frame Coordinate frame of reference.
+ * @param obstacle_id Unique ID given to each obstacle so that its movement can be tracked. Use UINT16_MAX if object ID is unknown or cannot be determined.
+ * @param x [m] X position of the obstacle.
+ * @param y [m] Y position of the obstacle.
+ * @param z [m] Z position of the obstacle.
+ * @param min_distance [m] Minimum distance the sensor can measure.
+ * @param max_distance [m] Maximum distance the sensor can measure.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_obstacle_distance_3d_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint32_t time_boot_ms, uint8_t sensor_type, uint8_t frame, uint16_t obstacle_id, float x, float y, float z, float min_distance, float max_distance)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_OBSTACLE_DISTANCE_3D_LEN];
+ _mav_put_uint32_t(buf, 0, time_boot_ms);
+ _mav_put_float(buf, 4, x);
+ _mav_put_float(buf, 8, y);
+ _mav_put_float(buf, 12, z);
+ _mav_put_float(buf, 16, min_distance);
+ _mav_put_float(buf, 20, max_distance);
+ _mav_put_uint16_t(buf, 24, obstacle_id);
+ _mav_put_uint8_t(buf, 26, sensor_type);
+ _mav_put_uint8_t(buf, 27, frame);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OBSTACLE_DISTANCE_3D_LEN);
+#else
+ mavlink_obstacle_distance_3d_t packet;
+ packet.time_boot_ms = time_boot_ms;
+ packet.x = x;
+ packet.y = y;
+ packet.z = z;
+ packet.min_distance = min_distance;
+ packet.max_distance = max_distance;
+ packet.obstacle_id = obstacle_id;
+ packet.sensor_type = sensor_type;
+ packet.frame = frame;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OBSTACLE_DISTANCE_3D_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_OBSTACLE_DISTANCE_3D;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_OBSTACLE_DISTANCE_3D_MIN_LEN, MAVLINK_MSG_ID_OBSTACLE_DISTANCE_3D_LEN, MAVLINK_MSG_ID_OBSTACLE_DISTANCE_3D_CRC);
+}
+
+/**
+ * @brief Pack a obstacle_distance_3d 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 time_boot_ms [ms] Timestamp (time since system boot).
+ * @param sensor_type Class id of the distance sensor type.
+ * @param frame Coordinate frame of reference.
+ * @param obstacle_id Unique ID given to each obstacle so that its movement can be tracked. Use UINT16_MAX if object ID is unknown or cannot be determined.
+ * @param x [m] X position of the obstacle.
+ * @param y [m] Y position of the obstacle.
+ * @param z [m] Z position of the obstacle.
+ * @param min_distance [m] Minimum distance the sensor can measure.
+ * @param max_distance [m] Maximum distance the sensor can measure.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_obstacle_distance_3d_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ uint32_t time_boot_ms, uint8_t sensor_type, uint8_t frame, uint16_t obstacle_id, float x, float y, float z, float min_distance, float max_distance)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_OBSTACLE_DISTANCE_3D_LEN];
+ _mav_put_uint32_t(buf, 0, time_boot_ms);
+ _mav_put_float(buf, 4, x);
+ _mav_put_float(buf, 8, y);
+ _mav_put_float(buf, 12, z);
+ _mav_put_float(buf, 16, min_distance);
+ _mav_put_float(buf, 20, max_distance);
+ _mav_put_uint16_t(buf, 24, obstacle_id);
+ _mav_put_uint8_t(buf, 26, sensor_type);
+ _mav_put_uint8_t(buf, 27, frame);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OBSTACLE_DISTANCE_3D_LEN);
+#else
+ mavlink_obstacle_distance_3d_t packet;
+ packet.time_boot_ms = time_boot_ms;
+ packet.x = x;
+ packet.y = y;
+ packet.z = z;
+ packet.min_distance = min_distance;
+ packet.max_distance = max_distance;
+ packet.obstacle_id = obstacle_id;
+ packet.sensor_type = sensor_type;
+ packet.frame = frame;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OBSTACLE_DISTANCE_3D_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_OBSTACLE_DISTANCE_3D;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_OBSTACLE_DISTANCE_3D_MIN_LEN, MAVLINK_MSG_ID_OBSTACLE_DISTANCE_3D_LEN, MAVLINK_MSG_ID_OBSTACLE_DISTANCE_3D_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_OBSTACLE_DISTANCE_3D_MIN_LEN, MAVLINK_MSG_ID_OBSTACLE_DISTANCE_3D_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a obstacle_distance_3d 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 time_boot_ms [ms] Timestamp (time since system boot).
+ * @param sensor_type Class id of the distance sensor type.
+ * @param frame Coordinate frame of reference.
+ * @param obstacle_id Unique ID given to each obstacle so that its movement can be tracked. Use UINT16_MAX if object ID is unknown or cannot be determined.
+ * @param x [m] X position of the obstacle.
+ * @param y [m] Y position of the obstacle.
+ * @param z [m] Z position of the obstacle.
+ * @param min_distance [m] Minimum distance the sensor can measure.
+ * @param max_distance [m] Maximum distance the sensor can measure.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_obstacle_distance_3d_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint32_t time_boot_ms,uint8_t sensor_type,uint8_t frame,uint16_t obstacle_id,float x,float y,float z,float min_distance,float max_distance)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_OBSTACLE_DISTANCE_3D_LEN];
+ _mav_put_uint32_t(buf, 0, time_boot_ms);
+ _mav_put_float(buf, 4, x);
+ _mav_put_float(buf, 8, y);
+ _mav_put_float(buf, 12, z);
+ _mav_put_float(buf, 16, min_distance);
+ _mav_put_float(buf, 20, max_distance);
+ _mav_put_uint16_t(buf, 24, obstacle_id);
+ _mav_put_uint8_t(buf, 26, sensor_type);
+ _mav_put_uint8_t(buf, 27, frame);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OBSTACLE_DISTANCE_3D_LEN);
+#else
+ mavlink_obstacle_distance_3d_t packet;
+ packet.time_boot_ms = time_boot_ms;
+ packet.x = x;
+ packet.y = y;
+ packet.z = z;
+ packet.min_distance = min_distance;
+ packet.max_distance = max_distance;
+ packet.obstacle_id = obstacle_id;
+ packet.sensor_type = sensor_type;
+ packet.frame = frame;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OBSTACLE_DISTANCE_3D_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_OBSTACLE_DISTANCE_3D;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_OBSTACLE_DISTANCE_3D_MIN_LEN, MAVLINK_MSG_ID_OBSTACLE_DISTANCE_3D_LEN, MAVLINK_MSG_ID_OBSTACLE_DISTANCE_3D_CRC);
+}
+
+/**
+ * @brief Encode a obstacle_distance_3d 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 obstacle_distance_3d C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_obstacle_distance_3d_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_obstacle_distance_3d_t* obstacle_distance_3d)
+{
+ return mavlink_msg_obstacle_distance_3d_pack(system_id, component_id, msg, obstacle_distance_3d->time_boot_ms, obstacle_distance_3d->sensor_type, obstacle_distance_3d->frame, obstacle_distance_3d->obstacle_id, obstacle_distance_3d->x, obstacle_distance_3d->y, obstacle_distance_3d->z, obstacle_distance_3d->min_distance, obstacle_distance_3d->max_distance);
+}
+
+/**
+ * @brief Encode a obstacle_distance_3d 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 obstacle_distance_3d C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_obstacle_distance_3d_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_obstacle_distance_3d_t* obstacle_distance_3d)
+{
+ return mavlink_msg_obstacle_distance_3d_pack_chan(system_id, component_id, chan, msg, obstacle_distance_3d->time_boot_ms, obstacle_distance_3d->sensor_type, obstacle_distance_3d->frame, obstacle_distance_3d->obstacle_id, obstacle_distance_3d->x, obstacle_distance_3d->y, obstacle_distance_3d->z, obstacle_distance_3d->min_distance, obstacle_distance_3d->max_distance);
+}
+
+/**
+ * @brief Encode a obstacle_distance_3d 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 obstacle_distance_3d C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_obstacle_distance_3d_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_obstacle_distance_3d_t* obstacle_distance_3d)
+{
+ return mavlink_msg_obstacle_distance_3d_pack_status(system_id, component_id, _status, msg, obstacle_distance_3d->time_boot_ms, obstacle_distance_3d->sensor_type, obstacle_distance_3d->frame, obstacle_distance_3d->obstacle_id, obstacle_distance_3d->x, obstacle_distance_3d->y, obstacle_distance_3d->z, obstacle_distance_3d->min_distance, obstacle_distance_3d->max_distance);
+}
+
+/**
+ * @brief Send a obstacle_distance_3d message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param time_boot_ms [ms] Timestamp (time since system boot).
+ * @param sensor_type Class id of the distance sensor type.
+ * @param frame Coordinate frame of reference.
+ * @param obstacle_id Unique ID given to each obstacle so that its movement can be tracked. Use UINT16_MAX if object ID is unknown or cannot be determined.
+ * @param x [m] X position of the obstacle.
+ * @param y [m] Y position of the obstacle.
+ * @param z [m] Z position of the obstacle.
+ * @param min_distance [m] Minimum distance the sensor can measure.
+ * @param max_distance [m] Maximum distance the sensor can measure.
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_obstacle_distance_3d_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t sensor_type, uint8_t frame, uint16_t obstacle_id, float x, float y, float z, float min_distance, float max_distance)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_OBSTACLE_DISTANCE_3D_LEN];
+ _mav_put_uint32_t(buf, 0, time_boot_ms);
+ _mav_put_float(buf, 4, x);
+ _mav_put_float(buf, 8, y);
+ _mav_put_float(buf, 12, z);
+ _mav_put_float(buf, 16, min_distance);
+ _mav_put_float(buf, 20, max_distance);
+ _mav_put_uint16_t(buf, 24, obstacle_id);
+ _mav_put_uint8_t(buf, 26, sensor_type);
+ _mav_put_uint8_t(buf, 27, frame);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBSTACLE_DISTANCE_3D, buf, MAVLINK_MSG_ID_OBSTACLE_DISTANCE_3D_MIN_LEN, MAVLINK_MSG_ID_OBSTACLE_DISTANCE_3D_LEN, MAVLINK_MSG_ID_OBSTACLE_DISTANCE_3D_CRC);
+#else
+ mavlink_obstacle_distance_3d_t packet;
+ packet.time_boot_ms = time_boot_ms;
+ packet.x = x;
+ packet.y = y;
+ packet.z = z;
+ packet.min_distance = min_distance;
+ packet.max_distance = max_distance;
+ packet.obstacle_id = obstacle_id;
+ packet.sensor_type = sensor_type;
+ packet.frame = frame;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBSTACLE_DISTANCE_3D, (const char *)&packet, MAVLINK_MSG_ID_OBSTACLE_DISTANCE_3D_MIN_LEN, MAVLINK_MSG_ID_OBSTACLE_DISTANCE_3D_LEN, MAVLINK_MSG_ID_OBSTACLE_DISTANCE_3D_CRC);
+#endif
+}
+
+/**
+ * @brief Send a obstacle_distance_3d message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_obstacle_distance_3d_send_struct(mavlink_channel_t chan, const mavlink_obstacle_distance_3d_t* obstacle_distance_3d)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_obstacle_distance_3d_send(chan, obstacle_distance_3d->time_boot_ms, obstacle_distance_3d->sensor_type, obstacle_distance_3d->frame, obstacle_distance_3d->obstacle_id, obstacle_distance_3d->x, obstacle_distance_3d->y, obstacle_distance_3d->z, obstacle_distance_3d->min_distance, obstacle_distance_3d->max_distance);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBSTACLE_DISTANCE_3D, (const char *)obstacle_distance_3d, MAVLINK_MSG_ID_OBSTACLE_DISTANCE_3D_MIN_LEN, MAVLINK_MSG_ID_OBSTACLE_DISTANCE_3D_LEN, MAVLINK_MSG_ID_OBSTACLE_DISTANCE_3D_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_OBSTACLE_DISTANCE_3D_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_obstacle_distance_3d_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t sensor_type, uint8_t frame, uint16_t obstacle_id, float x, float y, float z, float min_distance, float max_distance)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint32_t(buf, 0, time_boot_ms);
+ _mav_put_float(buf, 4, x);
+ _mav_put_float(buf, 8, y);
+ _mav_put_float(buf, 12, z);
+ _mav_put_float(buf, 16, min_distance);
+ _mav_put_float(buf, 20, max_distance);
+ _mav_put_uint16_t(buf, 24, obstacle_id);
+ _mav_put_uint8_t(buf, 26, sensor_type);
+ _mav_put_uint8_t(buf, 27, frame);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBSTACLE_DISTANCE_3D, buf, MAVLINK_MSG_ID_OBSTACLE_DISTANCE_3D_MIN_LEN, MAVLINK_MSG_ID_OBSTACLE_DISTANCE_3D_LEN, MAVLINK_MSG_ID_OBSTACLE_DISTANCE_3D_CRC);
+#else
+ mavlink_obstacle_distance_3d_t *packet = (mavlink_obstacle_distance_3d_t *)msgbuf;
+ packet->time_boot_ms = time_boot_ms;
+ packet->x = x;
+ packet->y = y;
+ packet->z = z;
+ packet->min_distance = min_distance;
+ packet->max_distance = max_distance;
+ packet->obstacle_id = obstacle_id;
+ packet->sensor_type = sensor_type;
+ packet->frame = frame;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBSTACLE_DISTANCE_3D, (const char *)packet, MAVLINK_MSG_ID_OBSTACLE_DISTANCE_3D_MIN_LEN, MAVLINK_MSG_ID_OBSTACLE_DISTANCE_3D_LEN, MAVLINK_MSG_ID_OBSTACLE_DISTANCE_3D_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE OBSTACLE_DISTANCE_3D UNPACKING
+
+
+/**
+ * @brief Get field time_boot_ms from obstacle_distance_3d message
+ *
+ * @return [ms] Timestamp (time since system boot).
+ */
+static inline uint32_t mavlink_msg_obstacle_distance_3d_get_time_boot_ms(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint32_t(msg, 0);
+}
+
+/**
+ * @brief Get field sensor_type from obstacle_distance_3d message
+ *
+ * @return Class id of the distance sensor type.
+ */
+static inline uint8_t mavlink_msg_obstacle_distance_3d_get_sensor_type(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 26);
+}
+
+/**
+ * @brief Get field frame from obstacle_distance_3d message
+ *
+ * @return Coordinate frame of reference.
+ */
+static inline uint8_t mavlink_msg_obstacle_distance_3d_get_frame(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 27);
+}
+
+/**
+ * @brief Get field obstacle_id from obstacle_distance_3d message
+ *
+ * @return Unique ID given to each obstacle so that its movement can be tracked. Use UINT16_MAX if object ID is unknown or cannot be determined.
+ */
+static inline uint16_t mavlink_msg_obstacle_distance_3d_get_obstacle_id(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 24);
+}
+
+/**
+ * @brief Get field x from obstacle_distance_3d message
+ *
+ * @return [m] X position of the obstacle.
+ */
+static inline float mavlink_msg_obstacle_distance_3d_get_x(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 4);
+}
+
+/**
+ * @brief Get field y from obstacle_distance_3d message
+ *
+ * @return [m] Y position of the obstacle.
+ */
+static inline float mavlink_msg_obstacle_distance_3d_get_y(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 8);
+}
+
+/**
+ * @brief Get field z from obstacle_distance_3d message
+ *
+ * @return [m] Z position of the obstacle.
+ */
+static inline float mavlink_msg_obstacle_distance_3d_get_z(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 12);
+}
+
+/**
+ * @brief Get field min_distance from obstacle_distance_3d message
+ *
+ * @return [m] Minimum distance the sensor can measure.
+ */
+static inline float mavlink_msg_obstacle_distance_3d_get_min_distance(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 16);
+}
+
+/**
+ * @brief Get field max_distance from obstacle_distance_3d message
+ *
+ * @return [m] Maximum distance the sensor can measure.
+ */
+static inline float mavlink_msg_obstacle_distance_3d_get_max_distance(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 20);
+}
+
+/**
+ * @brief Decode a obstacle_distance_3d message into a struct
+ *
+ * @param msg The message to decode
+ * @param obstacle_distance_3d C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_obstacle_distance_3d_decode(const mavlink_message_t* msg, mavlink_obstacle_distance_3d_t* obstacle_distance_3d)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ obstacle_distance_3d->time_boot_ms = mavlink_msg_obstacle_distance_3d_get_time_boot_ms(msg);
+ obstacle_distance_3d->x = mavlink_msg_obstacle_distance_3d_get_x(msg);
+ obstacle_distance_3d->y = mavlink_msg_obstacle_distance_3d_get_y(msg);
+ obstacle_distance_3d->z = mavlink_msg_obstacle_distance_3d_get_z(msg);
+ obstacle_distance_3d->min_distance = mavlink_msg_obstacle_distance_3d_get_min_distance(msg);
+ obstacle_distance_3d->max_distance = mavlink_msg_obstacle_distance_3d_get_max_distance(msg);
+ obstacle_distance_3d->obstacle_id = mavlink_msg_obstacle_distance_3d_get_obstacle_id(msg);
+ obstacle_distance_3d->sensor_type = mavlink_msg_obstacle_distance_3d_get_sensor_type(msg);
+ obstacle_distance_3d->frame = mavlink_msg_obstacle_distance_3d_get_frame(msg);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_OBSTACLE_DISTANCE_3D_LEN? msg->len : MAVLINK_MSG_ID_OBSTACLE_DISTANCE_3D_LEN;
+ memset(obstacle_distance_3d, 0, MAVLINK_MSG_ID_OBSTACLE_DISTANCE_3D_LEN);
+ memcpy(obstacle_distance_3d, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/ardupilotmega/mavlink_msg_osd_param_config.h b/lib/main/MAVLink/ardupilotmega/mavlink_msg_osd_param_config.h
new file mode 100644
index 00000000000..c9d8800e548
--- /dev/null
+++ b/lib/main/MAVLink/ardupilotmega/mavlink_msg_osd_param_config.h
@@ -0,0 +1,502 @@
+#pragma once
+// MESSAGE OSD_PARAM_CONFIG PACKING
+
+#define MAVLINK_MSG_ID_OSD_PARAM_CONFIG 11033
+
+
+typedef struct __mavlink_osd_param_config_t {
+ uint32_t request_id; /*< Request ID - copied to reply.*/
+ float min_value; /*< OSD parameter minimum value.*/
+ float max_value; /*< OSD parameter maximum value.*/
+ float increment; /*< OSD parameter increment.*/
+ uint8_t target_system; /*< System ID.*/
+ uint8_t target_component; /*< Component ID.*/
+ uint8_t osd_screen; /*< OSD parameter screen index.*/
+ uint8_t osd_index; /*< OSD parameter display index.*/
+ char param_id[16]; /*< Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string*/
+ uint8_t config_type; /*< Config type.*/
+} mavlink_osd_param_config_t;
+
+#define MAVLINK_MSG_ID_OSD_PARAM_CONFIG_LEN 37
+#define MAVLINK_MSG_ID_OSD_PARAM_CONFIG_MIN_LEN 37
+#define MAVLINK_MSG_ID_11033_LEN 37
+#define MAVLINK_MSG_ID_11033_MIN_LEN 37
+
+#define MAVLINK_MSG_ID_OSD_PARAM_CONFIG_CRC 195
+#define MAVLINK_MSG_ID_11033_CRC 195
+
+#define MAVLINK_MSG_OSD_PARAM_CONFIG_FIELD_PARAM_ID_LEN 16
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_OSD_PARAM_CONFIG { \
+ 11033, \
+ "OSD_PARAM_CONFIG", \
+ 10, \
+ { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_osd_param_config_t, target_system) }, \
+ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_osd_param_config_t, target_component) }, \
+ { "request_id", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_osd_param_config_t, request_id) }, \
+ { "osd_screen", NULL, MAVLINK_TYPE_UINT8_T, 0, 18, offsetof(mavlink_osd_param_config_t, osd_screen) }, \
+ { "osd_index", NULL, MAVLINK_TYPE_UINT8_T, 0, 19, offsetof(mavlink_osd_param_config_t, osd_index) }, \
+ { "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 20, offsetof(mavlink_osd_param_config_t, param_id) }, \
+ { "config_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_osd_param_config_t, config_type) }, \
+ { "min_value", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_osd_param_config_t, min_value) }, \
+ { "max_value", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_osd_param_config_t, max_value) }, \
+ { "increment", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_osd_param_config_t, increment) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_OSD_PARAM_CONFIG { \
+ "OSD_PARAM_CONFIG", \
+ 10, \
+ { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_osd_param_config_t, target_system) }, \
+ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_osd_param_config_t, target_component) }, \
+ { "request_id", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_osd_param_config_t, request_id) }, \
+ { "osd_screen", NULL, MAVLINK_TYPE_UINT8_T, 0, 18, offsetof(mavlink_osd_param_config_t, osd_screen) }, \
+ { "osd_index", NULL, MAVLINK_TYPE_UINT8_T, 0, 19, offsetof(mavlink_osd_param_config_t, osd_index) }, \
+ { "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 20, offsetof(mavlink_osd_param_config_t, param_id) }, \
+ { "config_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_osd_param_config_t, config_type) }, \
+ { "min_value", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_osd_param_config_t, min_value) }, \
+ { "max_value", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_osd_param_config_t, max_value) }, \
+ { "increment", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_osd_param_config_t, increment) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a osd_param_config 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 target_system System ID.
+ * @param target_component Component ID.
+ * @param request_id Request ID - copied to reply.
+ * @param osd_screen OSD parameter screen index.
+ * @param osd_index OSD parameter display index.
+ * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
+ * @param config_type Config type.
+ * @param min_value OSD parameter minimum value.
+ * @param max_value OSD parameter maximum value.
+ * @param increment OSD parameter increment.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_osd_param_config_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint8_t target_system, uint8_t target_component, uint32_t request_id, uint8_t osd_screen, uint8_t osd_index, const char *param_id, uint8_t config_type, float min_value, float max_value, float increment)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_OSD_PARAM_CONFIG_LEN];
+ _mav_put_uint32_t(buf, 0, request_id);
+ _mav_put_float(buf, 4, min_value);
+ _mav_put_float(buf, 8, max_value);
+ _mav_put_float(buf, 12, increment);
+ _mav_put_uint8_t(buf, 16, target_system);
+ _mav_put_uint8_t(buf, 17, target_component);
+ _mav_put_uint8_t(buf, 18, osd_screen);
+ _mav_put_uint8_t(buf, 19, osd_index);
+ _mav_put_uint8_t(buf, 36, config_type);
+ _mav_put_char_array(buf, 20, param_id, 16);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OSD_PARAM_CONFIG_LEN);
+#else
+ mavlink_osd_param_config_t packet;
+ packet.request_id = request_id;
+ packet.min_value = min_value;
+ packet.max_value = max_value;
+ packet.increment = increment;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.osd_screen = osd_screen;
+ packet.osd_index = osd_index;
+ packet.config_type = config_type;
+ mav_array_assign_char(packet.param_id, param_id, 16);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OSD_PARAM_CONFIG_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_OSD_PARAM_CONFIG;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_OSD_PARAM_CONFIG_MIN_LEN, MAVLINK_MSG_ID_OSD_PARAM_CONFIG_LEN, MAVLINK_MSG_ID_OSD_PARAM_CONFIG_CRC);
+}
+
+/**
+ * @brief Pack a osd_param_config 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 target_system System ID.
+ * @param target_component Component ID.
+ * @param request_id Request ID - copied to reply.
+ * @param osd_screen OSD parameter screen index.
+ * @param osd_index OSD parameter display index.
+ * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
+ * @param config_type Config type.
+ * @param min_value OSD parameter minimum value.
+ * @param max_value OSD parameter maximum value.
+ * @param increment OSD parameter increment.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_osd_param_config_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ uint8_t target_system, uint8_t target_component, uint32_t request_id, uint8_t osd_screen, uint8_t osd_index, const char *param_id, uint8_t config_type, float min_value, float max_value, float increment)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_OSD_PARAM_CONFIG_LEN];
+ _mav_put_uint32_t(buf, 0, request_id);
+ _mav_put_float(buf, 4, min_value);
+ _mav_put_float(buf, 8, max_value);
+ _mav_put_float(buf, 12, increment);
+ _mav_put_uint8_t(buf, 16, target_system);
+ _mav_put_uint8_t(buf, 17, target_component);
+ _mav_put_uint8_t(buf, 18, osd_screen);
+ _mav_put_uint8_t(buf, 19, osd_index);
+ _mav_put_uint8_t(buf, 36, config_type);
+ _mav_put_char_array(buf, 20, param_id, 16);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OSD_PARAM_CONFIG_LEN);
+#else
+ mavlink_osd_param_config_t packet;
+ packet.request_id = request_id;
+ packet.min_value = min_value;
+ packet.max_value = max_value;
+ packet.increment = increment;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.osd_screen = osd_screen;
+ packet.osd_index = osd_index;
+ packet.config_type = config_type;
+ mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OSD_PARAM_CONFIG_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_OSD_PARAM_CONFIG;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_OSD_PARAM_CONFIG_MIN_LEN, MAVLINK_MSG_ID_OSD_PARAM_CONFIG_LEN, MAVLINK_MSG_ID_OSD_PARAM_CONFIG_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_OSD_PARAM_CONFIG_MIN_LEN, MAVLINK_MSG_ID_OSD_PARAM_CONFIG_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a osd_param_config 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 target_system System ID.
+ * @param target_component Component ID.
+ * @param request_id Request ID - copied to reply.
+ * @param osd_screen OSD parameter screen index.
+ * @param osd_index OSD parameter display index.
+ * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
+ * @param config_type Config type.
+ * @param min_value OSD parameter minimum value.
+ * @param max_value OSD parameter maximum value.
+ * @param increment OSD parameter increment.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_osd_param_config_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint8_t target_system,uint8_t target_component,uint32_t request_id,uint8_t osd_screen,uint8_t osd_index,const char *param_id,uint8_t config_type,float min_value,float max_value,float increment)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_OSD_PARAM_CONFIG_LEN];
+ _mav_put_uint32_t(buf, 0, request_id);
+ _mav_put_float(buf, 4, min_value);
+ _mav_put_float(buf, 8, max_value);
+ _mav_put_float(buf, 12, increment);
+ _mav_put_uint8_t(buf, 16, target_system);
+ _mav_put_uint8_t(buf, 17, target_component);
+ _mav_put_uint8_t(buf, 18, osd_screen);
+ _mav_put_uint8_t(buf, 19, osd_index);
+ _mav_put_uint8_t(buf, 36, config_type);
+ _mav_put_char_array(buf, 20, param_id, 16);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OSD_PARAM_CONFIG_LEN);
+#else
+ mavlink_osd_param_config_t packet;
+ packet.request_id = request_id;
+ packet.min_value = min_value;
+ packet.max_value = max_value;
+ packet.increment = increment;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.osd_screen = osd_screen;
+ packet.osd_index = osd_index;
+ packet.config_type = config_type;
+ mav_array_assign_char(packet.param_id, param_id, 16);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OSD_PARAM_CONFIG_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_OSD_PARAM_CONFIG;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_OSD_PARAM_CONFIG_MIN_LEN, MAVLINK_MSG_ID_OSD_PARAM_CONFIG_LEN, MAVLINK_MSG_ID_OSD_PARAM_CONFIG_CRC);
+}
+
+/**
+ * @brief Encode a osd_param_config 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 osd_param_config C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_osd_param_config_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_osd_param_config_t* osd_param_config)
+{
+ return mavlink_msg_osd_param_config_pack(system_id, component_id, msg, osd_param_config->target_system, osd_param_config->target_component, osd_param_config->request_id, osd_param_config->osd_screen, osd_param_config->osd_index, osd_param_config->param_id, osd_param_config->config_type, osd_param_config->min_value, osd_param_config->max_value, osd_param_config->increment);
+}
+
+/**
+ * @brief Encode a osd_param_config 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 osd_param_config C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_osd_param_config_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_osd_param_config_t* osd_param_config)
+{
+ return mavlink_msg_osd_param_config_pack_chan(system_id, component_id, chan, msg, osd_param_config->target_system, osd_param_config->target_component, osd_param_config->request_id, osd_param_config->osd_screen, osd_param_config->osd_index, osd_param_config->param_id, osd_param_config->config_type, osd_param_config->min_value, osd_param_config->max_value, osd_param_config->increment);
+}
+
+/**
+ * @brief Encode a osd_param_config 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 osd_param_config C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_osd_param_config_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_osd_param_config_t* osd_param_config)
+{
+ return mavlink_msg_osd_param_config_pack_status(system_id, component_id, _status, msg, osd_param_config->target_system, osd_param_config->target_component, osd_param_config->request_id, osd_param_config->osd_screen, osd_param_config->osd_index, osd_param_config->param_id, osd_param_config->config_type, osd_param_config->min_value, osd_param_config->max_value, osd_param_config->increment);
+}
+
+/**
+ * @brief Send a osd_param_config message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param target_system System ID.
+ * @param target_component Component ID.
+ * @param request_id Request ID - copied to reply.
+ * @param osd_screen OSD parameter screen index.
+ * @param osd_index OSD parameter display index.
+ * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
+ * @param config_type Config type.
+ * @param min_value OSD parameter minimum value.
+ * @param max_value OSD parameter maximum value.
+ * @param increment OSD parameter increment.
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_osd_param_config_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint32_t request_id, uint8_t osd_screen, uint8_t osd_index, const char *param_id, uint8_t config_type, float min_value, float max_value, float increment)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_OSD_PARAM_CONFIG_LEN];
+ _mav_put_uint32_t(buf, 0, request_id);
+ _mav_put_float(buf, 4, min_value);
+ _mav_put_float(buf, 8, max_value);
+ _mav_put_float(buf, 12, increment);
+ _mav_put_uint8_t(buf, 16, target_system);
+ _mav_put_uint8_t(buf, 17, target_component);
+ _mav_put_uint8_t(buf, 18, osd_screen);
+ _mav_put_uint8_t(buf, 19, osd_index);
+ _mav_put_uint8_t(buf, 36, config_type);
+ _mav_put_char_array(buf, 20, param_id, 16);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OSD_PARAM_CONFIG, buf, MAVLINK_MSG_ID_OSD_PARAM_CONFIG_MIN_LEN, MAVLINK_MSG_ID_OSD_PARAM_CONFIG_LEN, MAVLINK_MSG_ID_OSD_PARAM_CONFIG_CRC);
+#else
+ mavlink_osd_param_config_t packet;
+ packet.request_id = request_id;
+ packet.min_value = min_value;
+ packet.max_value = max_value;
+ packet.increment = increment;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.osd_screen = osd_screen;
+ packet.osd_index = osd_index;
+ packet.config_type = config_type;
+ mav_array_assign_char(packet.param_id, param_id, 16);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OSD_PARAM_CONFIG, (const char *)&packet, MAVLINK_MSG_ID_OSD_PARAM_CONFIG_MIN_LEN, MAVLINK_MSG_ID_OSD_PARAM_CONFIG_LEN, MAVLINK_MSG_ID_OSD_PARAM_CONFIG_CRC);
+#endif
+}
+
+/**
+ * @brief Send a osd_param_config message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_osd_param_config_send_struct(mavlink_channel_t chan, const mavlink_osd_param_config_t* osd_param_config)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_osd_param_config_send(chan, osd_param_config->target_system, osd_param_config->target_component, osd_param_config->request_id, osd_param_config->osd_screen, osd_param_config->osd_index, osd_param_config->param_id, osd_param_config->config_type, osd_param_config->min_value, osd_param_config->max_value, osd_param_config->increment);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OSD_PARAM_CONFIG, (const char *)osd_param_config, MAVLINK_MSG_ID_OSD_PARAM_CONFIG_MIN_LEN, MAVLINK_MSG_ID_OSD_PARAM_CONFIG_LEN, MAVLINK_MSG_ID_OSD_PARAM_CONFIG_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_OSD_PARAM_CONFIG_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_osd_param_config_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint32_t request_id, uint8_t osd_screen, uint8_t osd_index, const char *param_id, uint8_t config_type, float min_value, float max_value, float increment)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint32_t(buf, 0, request_id);
+ _mav_put_float(buf, 4, min_value);
+ _mav_put_float(buf, 8, max_value);
+ _mav_put_float(buf, 12, increment);
+ _mav_put_uint8_t(buf, 16, target_system);
+ _mav_put_uint8_t(buf, 17, target_component);
+ _mav_put_uint8_t(buf, 18, osd_screen);
+ _mav_put_uint8_t(buf, 19, osd_index);
+ _mav_put_uint8_t(buf, 36, config_type);
+ _mav_put_char_array(buf, 20, param_id, 16);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OSD_PARAM_CONFIG, buf, MAVLINK_MSG_ID_OSD_PARAM_CONFIG_MIN_LEN, MAVLINK_MSG_ID_OSD_PARAM_CONFIG_LEN, MAVLINK_MSG_ID_OSD_PARAM_CONFIG_CRC);
+#else
+ mavlink_osd_param_config_t *packet = (mavlink_osd_param_config_t *)msgbuf;
+ packet->request_id = request_id;
+ packet->min_value = min_value;
+ packet->max_value = max_value;
+ packet->increment = increment;
+ packet->target_system = target_system;
+ packet->target_component = target_component;
+ packet->osd_screen = osd_screen;
+ packet->osd_index = osd_index;
+ packet->config_type = config_type;
+ mav_array_assign_char(packet->param_id, param_id, 16);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OSD_PARAM_CONFIG, (const char *)packet, MAVLINK_MSG_ID_OSD_PARAM_CONFIG_MIN_LEN, MAVLINK_MSG_ID_OSD_PARAM_CONFIG_LEN, MAVLINK_MSG_ID_OSD_PARAM_CONFIG_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE OSD_PARAM_CONFIG UNPACKING
+
+
+/**
+ * @brief Get field target_system from osd_param_config message
+ *
+ * @return System ID.
+ */
+static inline uint8_t mavlink_msg_osd_param_config_get_target_system(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 16);
+}
+
+/**
+ * @brief Get field target_component from osd_param_config message
+ *
+ * @return Component ID.
+ */
+static inline uint8_t mavlink_msg_osd_param_config_get_target_component(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 17);
+}
+
+/**
+ * @brief Get field request_id from osd_param_config message
+ *
+ * @return Request ID - copied to reply.
+ */
+static inline uint32_t mavlink_msg_osd_param_config_get_request_id(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint32_t(msg, 0);
+}
+
+/**
+ * @brief Get field osd_screen from osd_param_config message
+ *
+ * @return OSD parameter screen index.
+ */
+static inline uint8_t mavlink_msg_osd_param_config_get_osd_screen(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 18);
+}
+
+/**
+ * @brief Get field osd_index from osd_param_config message
+ *
+ * @return OSD parameter display index.
+ */
+static inline uint8_t mavlink_msg_osd_param_config_get_osd_index(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 19);
+}
+
+/**
+ * @brief Get field param_id from osd_param_config message
+ *
+ * @return Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
+ */
+static inline uint16_t mavlink_msg_osd_param_config_get_param_id(const mavlink_message_t* msg, char *param_id)
+{
+ return _MAV_RETURN_char_array(msg, param_id, 16, 20);
+}
+
+/**
+ * @brief Get field config_type from osd_param_config message
+ *
+ * @return Config type.
+ */
+static inline uint8_t mavlink_msg_osd_param_config_get_config_type(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 36);
+}
+
+/**
+ * @brief Get field min_value from osd_param_config message
+ *
+ * @return OSD parameter minimum value.
+ */
+static inline float mavlink_msg_osd_param_config_get_min_value(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 4);
+}
+
+/**
+ * @brief Get field max_value from osd_param_config message
+ *
+ * @return OSD parameter maximum value.
+ */
+static inline float mavlink_msg_osd_param_config_get_max_value(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 8);
+}
+
+/**
+ * @brief Get field increment from osd_param_config message
+ *
+ * @return OSD parameter increment.
+ */
+static inline float mavlink_msg_osd_param_config_get_increment(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 12);
+}
+
+/**
+ * @brief Decode a osd_param_config message into a struct
+ *
+ * @param msg The message to decode
+ * @param osd_param_config C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_osd_param_config_decode(const mavlink_message_t* msg, mavlink_osd_param_config_t* osd_param_config)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ osd_param_config->request_id = mavlink_msg_osd_param_config_get_request_id(msg);
+ osd_param_config->min_value = mavlink_msg_osd_param_config_get_min_value(msg);
+ osd_param_config->max_value = mavlink_msg_osd_param_config_get_max_value(msg);
+ osd_param_config->increment = mavlink_msg_osd_param_config_get_increment(msg);
+ osd_param_config->target_system = mavlink_msg_osd_param_config_get_target_system(msg);
+ osd_param_config->target_component = mavlink_msg_osd_param_config_get_target_component(msg);
+ osd_param_config->osd_screen = mavlink_msg_osd_param_config_get_osd_screen(msg);
+ osd_param_config->osd_index = mavlink_msg_osd_param_config_get_osd_index(msg);
+ mavlink_msg_osd_param_config_get_param_id(msg, osd_param_config->param_id);
+ osd_param_config->config_type = mavlink_msg_osd_param_config_get_config_type(msg);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_OSD_PARAM_CONFIG_LEN? msg->len : MAVLINK_MSG_ID_OSD_PARAM_CONFIG_LEN;
+ memset(osd_param_config, 0, MAVLINK_MSG_ID_OSD_PARAM_CONFIG_LEN);
+ memcpy(osd_param_config, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/ardupilotmega/mavlink_msg_osd_param_config_reply.h b/lib/main/MAVLink/ardupilotmega/mavlink_msg_osd_param_config_reply.h
new file mode 100644
index 00000000000..b816660eb32
--- /dev/null
+++ b/lib/main/MAVLink/ardupilotmega/mavlink_msg_osd_param_config_reply.h
@@ -0,0 +1,288 @@
+#pragma once
+// MESSAGE OSD_PARAM_CONFIG_REPLY PACKING
+
+#define MAVLINK_MSG_ID_OSD_PARAM_CONFIG_REPLY 11034
+
+
+typedef struct __mavlink_osd_param_config_reply_t {
+ uint32_t request_id; /*< Request ID - copied from request.*/
+ uint8_t result; /*< Config error type.*/
+} mavlink_osd_param_config_reply_t;
+
+#define MAVLINK_MSG_ID_OSD_PARAM_CONFIG_REPLY_LEN 5
+#define MAVLINK_MSG_ID_OSD_PARAM_CONFIG_REPLY_MIN_LEN 5
+#define MAVLINK_MSG_ID_11034_LEN 5
+#define MAVLINK_MSG_ID_11034_MIN_LEN 5
+
+#define MAVLINK_MSG_ID_OSD_PARAM_CONFIG_REPLY_CRC 79
+#define MAVLINK_MSG_ID_11034_CRC 79
+
+
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_OSD_PARAM_CONFIG_REPLY { \
+ 11034, \
+ "OSD_PARAM_CONFIG_REPLY", \
+ 2, \
+ { { "request_id", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_osd_param_config_reply_t, request_id) }, \
+ { "result", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_osd_param_config_reply_t, result) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_OSD_PARAM_CONFIG_REPLY { \
+ "OSD_PARAM_CONFIG_REPLY", \
+ 2, \
+ { { "request_id", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_osd_param_config_reply_t, request_id) }, \
+ { "result", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_osd_param_config_reply_t, result) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a osd_param_config_reply 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 request_id Request ID - copied from request.
+ * @param result Config error type.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_osd_param_config_reply_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint32_t request_id, uint8_t result)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_OSD_PARAM_CONFIG_REPLY_LEN];
+ _mav_put_uint32_t(buf, 0, request_id);
+ _mav_put_uint8_t(buf, 4, result);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OSD_PARAM_CONFIG_REPLY_LEN);
+#else
+ mavlink_osd_param_config_reply_t packet;
+ packet.request_id = request_id;
+ packet.result = result;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OSD_PARAM_CONFIG_REPLY_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_OSD_PARAM_CONFIG_REPLY;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_OSD_PARAM_CONFIG_REPLY_MIN_LEN, MAVLINK_MSG_ID_OSD_PARAM_CONFIG_REPLY_LEN, MAVLINK_MSG_ID_OSD_PARAM_CONFIG_REPLY_CRC);
+}
+
+/**
+ * @brief Pack a osd_param_config_reply 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 request_id Request ID - copied from request.
+ * @param result Config error type.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_osd_param_config_reply_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ uint32_t request_id, uint8_t result)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_OSD_PARAM_CONFIG_REPLY_LEN];
+ _mav_put_uint32_t(buf, 0, request_id);
+ _mav_put_uint8_t(buf, 4, result);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OSD_PARAM_CONFIG_REPLY_LEN);
+#else
+ mavlink_osd_param_config_reply_t packet;
+ packet.request_id = request_id;
+ packet.result = result;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OSD_PARAM_CONFIG_REPLY_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_OSD_PARAM_CONFIG_REPLY;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_OSD_PARAM_CONFIG_REPLY_MIN_LEN, MAVLINK_MSG_ID_OSD_PARAM_CONFIG_REPLY_LEN, MAVLINK_MSG_ID_OSD_PARAM_CONFIG_REPLY_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_OSD_PARAM_CONFIG_REPLY_MIN_LEN, MAVLINK_MSG_ID_OSD_PARAM_CONFIG_REPLY_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a osd_param_config_reply 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 request_id Request ID - copied from request.
+ * @param result Config error type.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_osd_param_config_reply_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint32_t request_id,uint8_t result)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_OSD_PARAM_CONFIG_REPLY_LEN];
+ _mav_put_uint32_t(buf, 0, request_id);
+ _mav_put_uint8_t(buf, 4, result);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OSD_PARAM_CONFIG_REPLY_LEN);
+#else
+ mavlink_osd_param_config_reply_t packet;
+ packet.request_id = request_id;
+ packet.result = result;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OSD_PARAM_CONFIG_REPLY_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_OSD_PARAM_CONFIG_REPLY;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_OSD_PARAM_CONFIG_REPLY_MIN_LEN, MAVLINK_MSG_ID_OSD_PARAM_CONFIG_REPLY_LEN, MAVLINK_MSG_ID_OSD_PARAM_CONFIG_REPLY_CRC);
+}
+
+/**
+ * @brief Encode a osd_param_config_reply 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 osd_param_config_reply C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_osd_param_config_reply_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_osd_param_config_reply_t* osd_param_config_reply)
+{
+ return mavlink_msg_osd_param_config_reply_pack(system_id, component_id, msg, osd_param_config_reply->request_id, osd_param_config_reply->result);
+}
+
+/**
+ * @brief Encode a osd_param_config_reply 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 osd_param_config_reply C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_osd_param_config_reply_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_osd_param_config_reply_t* osd_param_config_reply)
+{
+ return mavlink_msg_osd_param_config_reply_pack_chan(system_id, component_id, chan, msg, osd_param_config_reply->request_id, osd_param_config_reply->result);
+}
+
+/**
+ * @brief Encode a osd_param_config_reply 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 osd_param_config_reply C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_osd_param_config_reply_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_osd_param_config_reply_t* osd_param_config_reply)
+{
+ return mavlink_msg_osd_param_config_reply_pack_status(system_id, component_id, _status, msg, osd_param_config_reply->request_id, osd_param_config_reply->result);
+}
+
+/**
+ * @brief Send a osd_param_config_reply message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param request_id Request ID - copied from request.
+ * @param result Config error type.
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_osd_param_config_reply_send(mavlink_channel_t chan, uint32_t request_id, uint8_t result)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_OSD_PARAM_CONFIG_REPLY_LEN];
+ _mav_put_uint32_t(buf, 0, request_id);
+ _mav_put_uint8_t(buf, 4, result);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OSD_PARAM_CONFIG_REPLY, buf, MAVLINK_MSG_ID_OSD_PARAM_CONFIG_REPLY_MIN_LEN, MAVLINK_MSG_ID_OSD_PARAM_CONFIG_REPLY_LEN, MAVLINK_MSG_ID_OSD_PARAM_CONFIG_REPLY_CRC);
+#else
+ mavlink_osd_param_config_reply_t packet;
+ packet.request_id = request_id;
+ packet.result = result;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OSD_PARAM_CONFIG_REPLY, (const char *)&packet, MAVLINK_MSG_ID_OSD_PARAM_CONFIG_REPLY_MIN_LEN, MAVLINK_MSG_ID_OSD_PARAM_CONFIG_REPLY_LEN, MAVLINK_MSG_ID_OSD_PARAM_CONFIG_REPLY_CRC);
+#endif
+}
+
+/**
+ * @brief Send a osd_param_config_reply message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_osd_param_config_reply_send_struct(mavlink_channel_t chan, const mavlink_osd_param_config_reply_t* osd_param_config_reply)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_osd_param_config_reply_send(chan, osd_param_config_reply->request_id, osd_param_config_reply->result);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OSD_PARAM_CONFIG_REPLY, (const char *)osd_param_config_reply, MAVLINK_MSG_ID_OSD_PARAM_CONFIG_REPLY_MIN_LEN, MAVLINK_MSG_ID_OSD_PARAM_CONFIG_REPLY_LEN, MAVLINK_MSG_ID_OSD_PARAM_CONFIG_REPLY_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_OSD_PARAM_CONFIG_REPLY_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_osd_param_config_reply_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t request_id, uint8_t result)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint32_t(buf, 0, request_id);
+ _mav_put_uint8_t(buf, 4, result);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OSD_PARAM_CONFIG_REPLY, buf, MAVLINK_MSG_ID_OSD_PARAM_CONFIG_REPLY_MIN_LEN, MAVLINK_MSG_ID_OSD_PARAM_CONFIG_REPLY_LEN, MAVLINK_MSG_ID_OSD_PARAM_CONFIG_REPLY_CRC);
+#else
+ mavlink_osd_param_config_reply_t *packet = (mavlink_osd_param_config_reply_t *)msgbuf;
+ packet->request_id = request_id;
+ packet->result = result;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OSD_PARAM_CONFIG_REPLY, (const char *)packet, MAVLINK_MSG_ID_OSD_PARAM_CONFIG_REPLY_MIN_LEN, MAVLINK_MSG_ID_OSD_PARAM_CONFIG_REPLY_LEN, MAVLINK_MSG_ID_OSD_PARAM_CONFIG_REPLY_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE OSD_PARAM_CONFIG_REPLY UNPACKING
+
+
+/**
+ * @brief Get field request_id from osd_param_config_reply message
+ *
+ * @return Request ID - copied from request.
+ */
+static inline uint32_t mavlink_msg_osd_param_config_reply_get_request_id(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint32_t(msg, 0);
+}
+
+/**
+ * @brief Get field result from osd_param_config_reply message
+ *
+ * @return Config error type.
+ */
+static inline uint8_t mavlink_msg_osd_param_config_reply_get_result(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 4);
+}
+
+/**
+ * @brief Decode a osd_param_config_reply message into a struct
+ *
+ * @param msg The message to decode
+ * @param osd_param_config_reply C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_osd_param_config_reply_decode(const mavlink_message_t* msg, mavlink_osd_param_config_reply_t* osd_param_config_reply)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ osd_param_config_reply->request_id = mavlink_msg_osd_param_config_reply_get_request_id(msg);
+ osd_param_config_reply->result = mavlink_msg_osd_param_config_reply_get_result(msg);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_OSD_PARAM_CONFIG_REPLY_LEN? msg->len : MAVLINK_MSG_ID_OSD_PARAM_CONFIG_REPLY_LEN;
+ memset(osd_param_config_reply, 0, MAVLINK_MSG_ID_OSD_PARAM_CONFIG_REPLY_LEN);
+ memcpy(osd_param_config_reply, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/ardupilotmega/mavlink_msg_osd_param_show_config.h b/lib/main/MAVLink/ardupilotmega/mavlink_msg_osd_param_show_config.h
new file mode 100644
index 00000000000..086c65e5b0e
--- /dev/null
+++ b/lib/main/MAVLink/ardupilotmega/mavlink_msg_osd_param_show_config.h
@@ -0,0 +1,372 @@
+#pragma once
+// MESSAGE OSD_PARAM_SHOW_CONFIG PACKING
+
+#define MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG 11035
+
+
+typedef struct __mavlink_osd_param_show_config_t {
+ uint32_t request_id; /*< Request ID - copied to reply.*/
+ uint8_t target_system; /*< System ID.*/
+ uint8_t target_component; /*< Component ID.*/
+ uint8_t osd_screen; /*< OSD parameter screen index.*/
+ uint8_t osd_index; /*< OSD parameter display index.*/
+} mavlink_osd_param_show_config_t;
+
+#define MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_LEN 8
+#define MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_MIN_LEN 8
+#define MAVLINK_MSG_ID_11035_LEN 8
+#define MAVLINK_MSG_ID_11035_MIN_LEN 8
+
+#define MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_CRC 128
+#define MAVLINK_MSG_ID_11035_CRC 128
+
+
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_OSD_PARAM_SHOW_CONFIG { \
+ 11035, \
+ "OSD_PARAM_SHOW_CONFIG", \
+ 5, \
+ { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_osd_param_show_config_t, target_system) }, \
+ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_osd_param_show_config_t, target_component) }, \
+ { "request_id", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_osd_param_show_config_t, request_id) }, \
+ { "osd_screen", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_osd_param_show_config_t, osd_screen) }, \
+ { "osd_index", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_osd_param_show_config_t, osd_index) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_OSD_PARAM_SHOW_CONFIG { \
+ "OSD_PARAM_SHOW_CONFIG", \
+ 5, \
+ { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_osd_param_show_config_t, target_system) }, \
+ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_osd_param_show_config_t, target_component) }, \
+ { "request_id", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_osd_param_show_config_t, request_id) }, \
+ { "osd_screen", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_osd_param_show_config_t, osd_screen) }, \
+ { "osd_index", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_osd_param_show_config_t, osd_index) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a osd_param_show_config 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 target_system System ID.
+ * @param target_component Component ID.
+ * @param request_id Request ID - copied to reply.
+ * @param osd_screen OSD parameter screen index.
+ * @param osd_index OSD parameter display index.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_osd_param_show_config_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint8_t target_system, uint8_t target_component, uint32_t request_id, uint8_t osd_screen, uint8_t osd_index)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_LEN];
+ _mav_put_uint32_t(buf, 0, request_id);
+ _mav_put_uint8_t(buf, 4, target_system);
+ _mav_put_uint8_t(buf, 5, target_component);
+ _mav_put_uint8_t(buf, 6, osd_screen);
+ _mav_put_uint8_t(buf, 7, osd_index);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_LEN);
+#else
+ mavlink_osd_param_show_config_t packet;
+ packet.request_id = request_id;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.osd_screen = osd_screen;
+ packet.osd_index = osd_index;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_MIN_LEN, MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_LEN, MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_CRC);
+}
+
+/**
+ * @brief Pack a osd_param_show_config 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 target_system System ID.
+ * @param target_component Component ID.
+ * @param request_id Request ID - copied to reply.
+ * @param osd_screen OSD parameter screen index.
+ * @param osd_index OSD parameter display index.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_osd_param_show_config_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ uint8_t target_system, uint8_t target_component, uint32_t request_id, uint8_t osd_screen, uint8_t osd_index)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_LEN];
+ _mav_put_uint32_t(buf, 0, request_id);
+ _mav_put_uint8_t(buf, 4, target_system);
+ _mav_put_uint8_t(buf, 5, target_component);
+ _mav_put_uint8_t(buf, 6, osd_screen);
+ _mav_put_uint8_t(buf, 7, osd_index);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_LEN);
+#else
+ mavlink_osd_param_show_config_t packet;
+ packet.request_id = request_id;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.osd_screen = osd_screen;
+ packet.osd_index = osd_index;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_MIN_LEN, MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_LEN, MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_MIN_LEN, MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a osd_param_show_config 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 target_system System ID.
+ * @param target_component Component ID.
+ * @param request_id Request ID - copied to reply.
+ * @param osd_screen OSD parameter screen index.
+ * @param osd_index OSD parameter display index.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_osd_param_show_config_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint8_t target_system,uint8_t target_component,uint32_t request_id,uint8_t osd_screen,uint8_t osd_index)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_LEN];
+ _mav_put_uint32_t(buf, 0, request_id);
+ _mav_put_uint8_t(buf, 4, target_system);
+ _mav_put_uint8_t(buf, 5, target_component);
+ _mav_put_uint8_t(buf, 6, osd_screen);
+ _mav_put_uint8_t(buf, 7, osd_index);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_LEN);
+#else
+ mavlink_osd_param_show_config_t packet;
+ packet.request_id = request_id;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.osd_screen = osd_screen;
+ packet.osd_index = osd_index;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_MIN_LEN, MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_LEN, MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_CRC);
+}
+
+/**
+ * @brief Encode a osd_param_show_config 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 osd_param_show_config C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_osd_param_show_config_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_osd_param_show_config_t* osd_param_show_config)
+{
+ return mavlink_msg_osd_param_show_config_pack(system_id, component_id, msg, osd_param_show_config->target_system, osd_param_show_config->target_component, osd_param_show_config->request_id, osd_param_show_config->osd_screen, osd_param_show_config->osd_index);
+}
+
+/**
+ * @brief Encode a osd_param_show_config 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 osd_param_show_config C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_osd_param_show_config_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_osd_param_show_config_t* osd_param_show_config)
+{
+ return mavlink_msg_osd_param_show_config_pack_chan(system_id, component_id, chan, msg, osd_param_show_config->target_system, osd_param_show_config->target_component, osd_param_show_config->request_id, osd_param_show_config->osd_screen, osd_param_show_config->osd_index);
+}
+
+/**
+ * @brief Encode a osd_param_show_config 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 osd_param_show_config C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_osd_param_show_config_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_osd_param_show_config_t* osd_param_show_config)
+{
+ return mavlink_msg_osd_param_show_config_pack_status(system_id, component_id, _status, msg, osd_param_show_config->target_system, osd_param_show_config->target_component, osd_param_show_config->request_id, osd_param_show_config->osd_screen, osd_param_show_config->osd_index);
+}
+
+/**
+ * @brief Send a osd_param_show_config message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param target_system System ID.
+ * @param target_component Component ID.
+ * @param request_id Request ID - copied to reply.
+ * @param osd_screen OSD parameter screen index.
+ * @param osd_index OSD parameter display index.
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_osd_param_show_config_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint32_t request_id, uint8_t osd_screen, uint8_t osd_index)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_LEN];
+ _mav_put_uint32_t(buf, 0, request_id);
+ _mav_put_uint8_t(buf, 4, target_system);
+ _mav_put_uint8_t(buf, 5, target_component);
+ _mav_put_uint8_t(buf, 6, osd_screen);
+ _mav_put_uint8_t(buf, 7, osd_index);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG, buf, MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_MIN_LEN, MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_LEN, MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_CRC);
+#else
+ mavlink_osd_param_show_config_t packet;
+ packet.request_id = request_id;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.osd_screen = osd_screen;
+ packet.osd_index = osd_index;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG, (const char *)&packet, MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_MIN_LEN, MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_LEN, MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_CRC);
+#endif
+}
+
+/**
+ * @brief Send a osd_param_show_config message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_osd_param_show_config_send_struct(mavlink_channel_t chan, const mavlink_osd_param_show_config_t* osd_param_show_config)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_osd_param_show_config_send(chan, osd_param_show_config->target_system, osd_param_show_config->target_component, osd_param_show_config->request_id, osd_param_show_config->osd_screen, osd_param_show_config->osd_index);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG, (const char *)osd_param_show_config, MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_MIN_LEN, MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_LEN, MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_osd_param_show_config_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint32_t request_id, uint8_t osd_screen, uint8_t osd_index)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint32_t(buf, 0, request_id);
+ _mav_put_uint8_t(buf, 4, target_system);
+ _mav_put_uint8_t(buf, 5, target_component);
+ _mav_put_uint8_t(buf, 6, osd_screen);
+ _mav_put_uint8_t(buf, 7, osd_index);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG, buf, MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_MIN_LEN, MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_LEN, MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_CRC);
+#else
+ mavlink_osd_param_show_config_t *packet = (mavlink_osd_param_show_config_t *)msgbuf;
+ packet->request_id = request_id;
+ packet->target_system = target_system;
+ packet->target_component = target_component;
+ packet->osd_screen = osd_screen;
+ packet->osd_index = osd_index;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG, (const char *)packet, MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_MIN_LEN, MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_LEN, MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE OSD_PARAM_SHOW_CONFIG UNPACKING
+
+
+/**
+ * @brief Get field target_system from osd_param_show_config message
+ *
+ * @return System ID.
+ */
+static inline uint8_t mavlink_msg_osd_param_show_config_get_target_system(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 4);
+}
+
+/**
+ * @brief Get field target_component from osd_param_show_config message
+ *
+ * @return Component ID.
+ */
+static inline uint8_t mavlink_msg_osd_param_show_config_get_target_component(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 5);
+}
+
+/**
+ * @brief Get field request_id from osd_param_show_config message
+ *
+ * @return Request ID - copied to reply.
+ */
+static inline uint32_t mavlink_msg_osd_param_show_config_get_request_id(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint32_t(msg, 0);
+}
+
+/**
+ * @brief Get field osd_screen from osd_param_show_config message
+ *
+ * @return OSD parameter screen index.
+ */
+static inline uint8_t mavlink_msg_osd_param_show_config_get_osd_screen(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 6);
+}
+
+/**
+ * @brief Get field osd_index from osd_param_show_config message
+ *
+ * @return OSD parameter display index.
+ */
+static inline uint8_t mavlink_msg_osd_param_show_config_get_osd_index(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 7);
+}
+
+/**
+ * @brief Decode a osd_param_show_config message into a struct
+ *
+ * @param msg The message to decode
+ * @param osd_param_show_config C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_osd_param_show_config_decode(const mavlink_message_t* msg, mavlink_osd_param_show_config_t* osd_param_show_config)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ osd_param_show_config->request_id = mavlink_msg_osd_param_show_config_get_request_id(msg);
+ osd_param_show_config->target_system = mavlink_msg_osd_param_show_config_get_target_system(msg);
+ osd_param_show_config->target_component = mavlink_msg_osd_param_show_config_get_target_component(msg);
+ osd_param_show_config->osd_screen = mavlink_msg_osd_param_show_config_get_osd_screen(msg);
+ osd_param_show_config->osd_index = mavlink_msg_osd_param_show_config_get_osd_index(msg);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_LEN? msg->len : MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_LEN;
+ memset(osd_param_show_config, 0, MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_LEN);
+ memcpy(osd_param_show_config, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/ardupilotmega/mavlink_msg_osd_param_show_config_reply.h b/lib/main/MAVLink/ardupilotmega/mavlink_msg_osd_param_show_config_reply.h
new file mode 100644
index 00000000000..216120a985b
--- /dev/null
+++ b/lib/main/MAVLink/ardupilotmega/mavlink_msg_osd_param_show_config_reply.h
@@ -0,0 +1,418 @@
+#pragma once
+// MESSAGE OSD_PARAM_SHOW_CONFIG_REPLY PACKING
+
+#define MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_REPLY 11036
+
+
+typedef struct __mavlink_osd_param_show_config_reply_t {
+ uint32_t request_id; /*< Request ID - copied from request.*/
+ float min_value; /*< OSD parameter minimum value.*/
+ float max_value; /*< OSD parameter maximum value.*/
+ float increment; /*< OSD parameter increment.*/
+ uint8_t result; /*< Config error type.*/
+ char param_id[16]; /*< Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string*/
+ uint8_t config_type; /*< Config type.*/
+} mavlink_osd_param_show_config_reply_t;
+
+#define MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_REPLY_LEN 34
+#define MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_REPLY_MIN_LEN 34
+#define MAVLINK_MSG_ID_11036_LEN 34
+#define MAVLINK_MSG_ID_11036_MIN_LEN 34
+
+#define MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_REPLY_CRC 177
+#define MAVLINK_MSG_ID_11036_CRC 177
+
+#define MAVLINK_MSG_OSD_PARAM_SHOW_CONFIG_REPLY_FIELD_PARAM_ID_LEN 16
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_OSD_PARAM_SHOW_CONFIG_REPLY { \
+ 11036, \
+ "OSD_PARAM_SHOW_CONFIG_REPLY", \
+ 7, \
+ { { "request_id", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_osd_param_show_config_reply_t, request_id) }, \
+ { "result", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_osd_param_show_config_reply_t, result) }, \
+ { "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 17, offsetof(mavlink_osd_param_show_config_reply_t, param_id) }, \
+ { "config_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_osd_param_show_config_reply_t, config_type) }, \
+ { "min_value", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_osd_param_show_config_reply_t, min_value) }, \
+ { "max_value", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_osd_param_show_config_reply_t, max_value) }, \
+ { "increment", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_osd_param_show_config_reply_t, increment) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_OSD_PARAM_SHOW_CONFIG_REPLY { \
+ "OSD_PARAM_SHOW_CONFIG_REPLY", \
+ 7, \
+ { { "request_id", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_osd_param_show_config_reply_t, request_id) }, \
+ { "result", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_osd_param_show_config_reply_t, result) }, \
+ { "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 17, offsetof(mavlink_osd_param_show_config_reply_t, param_id) }, \
+ { "config_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_osd_param_show_config_reply_t, config_type) }, \
+ { "min_value", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_osd_param_show_config_reply_t, min_value) }, \
+ { "max_value", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_osd_param_show_config_reply_t, max_value) }, \
+ { "increment", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_osd_param_show_config_reply_t, increment) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a osd_param_show_config_reply 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 request_id Request ID - copied from request.
+ * @param result Config error type.
+ * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
+ * @param config_type Config type.
+ * @param min_value OSD parameter minimum value.
+ * @param max_value OSD parameter maximum value.
+ * @param increment OSD parameter increment.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_osd_param_show_config_reply_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint32_t request_id, uint8_t result, const char *param_id, uint8_t config_type, float min_value, float max_value, float increment)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_REPLY_LEN];
+ _mav_put_uint32_t(buf, 0, request_id);
+ _mav_put_float(buf, 4, min_value);
+ _mav_put_float(buf, 8, max_value);
+ _mav_put_float(buf, 12, increment);
+ _mav_put_uint8_t(buf, 16, result);
+ _mav_put_uint8_t(buf, 33, config_type);
+ _mav_put_char_array(buf, 17, param_id, 16);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_REPLY_LEN);
+#else
+ mavlink_osd_param_show_config_reply_t packet;
+ packet.request_id = request_id;
+ packet.min_value = min_value;
+ packet.max_value = max_value;
+ packet.increment = increment;
+ packet.result = result;
+ packet.config_type = config_type;
+ mav_array_assign_char(packet.param_id, param_id, 16);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_REPLY_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_REPLY;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_REPLY_MIN_LEN, MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_REPLY_LEN, MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_REPLY_CRC);
+}
+
+/**
+ * @brief Pack a osd_param_show_config_reply 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 request_id Request ID - copied from request.
+ * @param result Config error type.
+ * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
+ * @param config_type Config type.
+ * @param min_value OSD parameter minimum value.
+ * @param max_value OSD parameter maximum value.
+ * @param increment OSD parameter increment.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_osd_param_show_config_reply_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ uint32_t request_id, uint8_t result, const char *param_id, uint8_t config_type, float min_value, float max_value, float increment)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_REPLY_LEN];
+ _mav_put_uint32_t(buf, 0, request_id);
+ _mav_put_float(buf, 4, min_value);
+ _mav_put_float(buf, 8, max_value);
+ _mav_put_float(buf, 12, increment);
+ _mav_put_uint8_t(buf, 16, result);
+ _mav_put_uint8_t(buf, 33, config_type);
+ _mav_put_char_array(buf, 17, param_id, 16);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_REPLY_LEN);
+#else
+ mavlink_osd_param_show_config_reply_t packet;
+ packet.request_id = request_id;
+ packet.min_value = min_value;
+ packet.max_value = max_value;
+ packet.increment = increment;
+ packet.result = result;
+ packet.config_type = config_type;
+ mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_REPLY_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_REPLY;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_REPLY_MIN_LEN, MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_REPLY_LEN, MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_REPLY_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_REPLY_MIN_LEN, MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_REPLY_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a osd_param_show_config_reply 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 request_id Request ID - copied from request.
+ * @param result Config error type.
+ * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
+ * @param config_type Config type.
+ * @param min_value OSD parameter minimum value.
+ * @param max_value OSD parameter maximum value.
+ * @param increment OSD parameter increment.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_osd_param_show_config_reply_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint32_t request_id,uint8_t result,const char *param_id,uint8_t config_type,float min_value,float max_value,float increment)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_REPLY_LEN];
+ _mav_put_uint32_t(buf, 0, request_id);
+ _mav_put_float(buf, 4, min_value);
+ _mav_put_float(buf, 8, max_value);
+ _mav_put_float(buf, 12, increment);
+ _mav_put_uint8_t(buf, 16, result);
+ _mav_put_uint8_t(buf, 33, config_type);
+ _mav_put_char_array(buf, 17, param_id, 16);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_REPLY_LEN);
+#else
+ mavlink_osd_param_show_config_reply_t packet;
+ packet.request_id = request_id;
+ packet.min_value = min_value;
+ packet.max_value = max_value;
+ packet.increment = increment;
+ packet.result = result;
+ packet.config_type = config_type;
+ mav_array_assign_char(packet.param_id, param_id, 16);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_REPLY_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_REPLY;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_REPLY_MIN_LEN, MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_REPLY_LEN, MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_REPLY_CRC);
+}
+
+/**
+ * @brief Encode a osd_param_show_config_reply 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 osd_param_show_config_reply C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_osd_param_show_config_reply_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_osd_param_show_config_reply_t* osd_param_show_config_reply)
+{
+ return mavlink_msg_osd_param_show_config_reply_pack(system_id, component_id, msg, osd_param_show_config_reply->request_id, osd_param_show_config_reply->result, osd_param_show_config_reply->param_id, osd_param_show_config_reply->config_type, osd_param_show_config_reply->min_value, osd_param_show_config_reply->max_value, osd_param_show_config_reply->increment);
+}
+
+/**
+ * @brief Encode a osd_param_show_config_reply 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 osd_param_show_config_reply C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_osd_param_show_config_reply_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_osd_param_show_config_reply_t* osd_param_show_config_reply)
+{
+ return mavlink_msg_osd_param_show_config_reply_pack_chan(system_id, component_id, chan, msg, osd_param_show_config_reply->request_id, osd_param_show_config_reply->result, osd_param_show_config_reply->param_id, osd_param_show_config_reply->config_type, osd_param_show_config_reply->min_value, osd_param_show_config_reply->max_value, osd_param_show_config_reply->increment);
+}
+
+/**
+ * @brief Encode a osd_param_show_config_reply 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 osd_param_show_config_reply C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_osd_param_show_config_reply_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_osd_param_show_config_reply_t* osd_param_show_config_reply)
+{
+ return mavlink_msg_osd_param_show_config_reply_pack_status(system_id, component_id, _status, msg, osd_param_show_config_reply->request_id, osd_param_show_config_reply->result, osd_param_show_config_reply->param_id, osd_param_show_config_reply->config_type, osd_param_show_config_reply->min_value, osd_param_show_config_reply->max_value, osd_param_show_config_reply->increment);
+}
+
+/**
+ * @brief Send a osd_param_show_config_reply message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param request_id Request ID - copied from request.
+ * @param result Config error type.
+ * @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
+ * @param config_type Config type.
+ * @param min_value OSD parameter minimum value.
+ * @param max_value OSD parameter maximum value.
+ * @param increment OSD parameter increment.
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_osd_param_show_config_reply_send(mavlink_channel_t chan, uint32_t request_id, uint8_t result, const char *param_id, uint8_t config_type, float min_value, float max_value, float increment)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_REPLY_LEN];
+ _mav_put_uint32_t(buf, 0, request_id);
+ _mav_put_float(buf, 4, min_value);
+ _mav_put_float(buf, 8, max_value);
+ _mav_put_float(buf, 12, increment);
+ _mav_put_uint8_t(buf, 16, result);
+ _mav_put_uint8_t(buf, 33, config_type);
+ _mav_put_char_array(buf, 17, param_id, 16);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_REPLY, buf, MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_REPLY_MIN_LEN, MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_REPLY_LEN, MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_REPLY_CRC);
+#else
+ mavlink_osd_param_show_config_reply_t packet;
+ packet.request_id = request_id;
+ packet.min_value = min_value;
+ packet.max_value = max_value;
+ packet.increment = increment;
+ packet.result = result;
+ packet.config_type = config_type;
+ mav_array_assign_char(packet.param_id, param_id, 16);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_REPLY, (const char *)&packet, MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_REPLY_MIN_LEN, MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_REPLY_LEN, MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_REPLY_CRC);
+#endif
+}
+
+/**
+ * @brief Send a osd_param_show_config_reply message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_osd_param_show_config_reply_send_struct(mavlink_channel_t chan, const mavlink_osd_param_show_config_reply_t* osd_param_show_config_reply)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_osd_param_show_config_reply_send(chan, osd_param_show_config_reply->request_id, osd_param_show_config_reply->result, osd_param_show_config_reply->param_id, osd_param_show_config_reply->config_type, osd_param_show_config_reply->min_value, osd_param_show_config_reply->max_value, osd_param_show_config_reply->increment);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_REPLY, (const char *)osd_param_show_config_reply, MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_REPLY_MIN_LEN, MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_REPLY_LEN, MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_REPLY_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_REPLY_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_osd_param_show_config_reply_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t request_id, uint8_t result, const char *param_id, uint8_t config_type, float min_value, float max_value, float increment)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint32_t(buf, 0, request_id);
+ _mav_put_float(buf, 4, min_value);
+ _mav_put_float(buf, 8, max_value);
+ _mav_put_float(buf, 12, increment);
+ _mav_put_uint8_t(buf, 16, result);
+ _mav_put_uint8_t(buf, 33, config_type);
+ _mav_put_char_array(buf, 17, param_id, 16);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_REPLY, buf, MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_REPLY_MIN_LEN, MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_REPLY_LEN, MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_REPLY_CRC);
+#else
+ mavlink_osd_param_show_config_reply_t *packet = (mavlink_osd_param_show_config_reply_t *)msgbuf;
+ packet->request_id = request_id;
+ packet->min_value = min_value;
+ packet->max_value = max_value;
+ packet->increment = increment;
+ packet->result = result;
+ packet->config_type = config_type;
+ mav_array_assign_char(packet->param_id, param_id, 16);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_REPLY, (const char *)packet, MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_REPLY_MIN_LEN, MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_REPLY_LEN, MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_REPLY_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE OSD_PARAM_SHOW_CONFIG_REPLY UNPACKING
+
+
+/**
+ * @brief Get field request_id from osd_param_show_config_reply message
+ *
+ * @return Request ID - copied from request.
+ */
+static inline uint32_t mavlink_msg_osd_param_show_config_reply_get_request_id(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint32_t(msg, 0);
+}
+
+/**
+ * @brief Get field result from osd_param_show_config_reply message
+ *
+ * @return Config error type.
+ */
+static inline uint8_t mavlink_msg_osd_param_show_config_reply_get_result(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 16);
+}
+
+/**
+ * @brief Get field param_id from osd_param_show_config_reply message
+ *
+ * @return Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
+ */
+static inline uint16_t mavlink_msg_osd_param_show_config_reply_get_param_id(const mavlink_message_t* msg, char *param_id)
+{
+ return _MAV_RETURN_char_array(msg, param_id, 16, 17);
+}
+
+/**
+ * @brief Get field config_type from osd_param_show_config_reply message
+ *
+ * @return Config type.
+ */
+static inline uint8_t mavlink_msg_osd_param_show_config_reply_get_config_type(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 33);
+}
+
+/**
+ * @brief Get field min_value from osd_param_show_config_reply message
+ *
+ * @return OSD parameter minimum value.
+ */
+static inline float mavlink_msg_osd_param_show_config_reply_get_min_value(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 4);
+}
+
+/**
+ * @brief Get field max_value from osd_param_show_config_reply message
+ *
+ * @return OSD parameter maximum value.
+ */
+static inline float mavlink_msg_osd_param_show_config_reply_get_max_value(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 8);
+}
+
+/**
+ * @brief Get field increment from osd_param_show_config_reply message
+ *
+ * @return OSD parameter increment.
+ */
+static inline float mavlink_msg_osd_param_show_config_reply_get_increment(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 12);
+}
+
+/**
+ * @brief Decode a osd_param_show_config_reply message into a struct
+ *
+ * @param msg The message to decode
+ * @param osd_param_show_config_reply C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_osd_param_show_config_reply_decode(const mavlink_message_t* msg, mavlink_osd_param_show_config_reply_t* osd_param_show_config_reply)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ osd_param_show_config_reply->request_id = mavlink_msg_osd_param_show_config_reply_get_request_id(msg);
+ osd_param_show_config_reply->min_value = mavlink_msg_osd_param_show_config_reply_get_min_value(msg);
+ osd_param_show_config_reply->max_value = mavlink_msg_osd_param_show_config_reply_get_max_value(msg);
+ osd_param_show_config_reply->increment = mavlink_msg_osd_param_show_config_reply_get_increment(msg);
+ osd_param_show_config_reply->result = mavlink_msg_osd_param_show_config_reply_get_result(msg);
+ mavlink_msg_osd_param_show_config_reply_get_param_id(msg, osd_param_show_config_reply->param_id);
+ osd_param_show_config_reply->config_type = mavlink_msg_osd_param_show_config_reply_get_config_type(msg);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_REPLY_LEN? msg->len : MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_REPLY_LEN;
+ memset(osd_param_show_config_reply, 0, MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_REPLY_LEN);
+ memcpy(osd_param_show_config_reply, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/ardupilotmega/mavlink_msg_pid_tuning.h b/lib/main/MAVLink/ardupilotmega/mavlink_msg_pid_tuning.h
new file mode 100644
index 00000000000..45f2d6503cd
--- /dev/null
+++ b/lib/main/MAVLink/ardupilotmega/mavlink_msg_pid_tuning.h
@@ -0,0 +1,484 @@
+#pragma once
+// MESSAGE PID_TUNING PACKING
+
+#define MAVLINK_MSG_ID_PID_TUNING 194
+
+MAVPACKED(
+typedef struct __mavlink_pid_tuning_t {
+ float desired; /*< Desired rate.*/
+ float achieved; /*< Achieved rate.*/
+ float FF; /*< FF component.*/
+ float P; /*< P component.*/
+ float I; /*< I component.*/
+ float D; /*< D component.*/
+ uint8_t axis; /*< Axis.*/
+ float SRate; /*< Slew rate.*/
+ float PDmod; /*< P/D oscillation modifier.*/
+}) mavlink_pid_tuning_t;
+
+#define MAVLINK_MSG_ID_PID_TUNING_LEN 33
+#define MAVLINK_MSG_ID_PID_TUNING_MIN_LEN 25
+#define MAVLINK_MSG_ID_194_LEN 33
+#define MAVLINK_MSG_ID_194_MIN_LEN 25
+
+#define MAVLINK_MSG_ID_PID_TUNING_CRC 98
+#define MAVLINK_MSG_ID_194_CRC 98
+
+
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_PID_TUNING { \
+ 194, \
+ "PID_TUNING", \
+ 9, \
+ { { "axis", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_pid_tuning_t, axis) }, \
+ { "desired", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_pid_tuning_t, desired) }, \
+ { "achieved", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_pid_tuning_t, achieved) }, \
+ { "FF", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_pid_tuning_t, FF) }, \
+ { "P", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_pid_tuning_t, P) }, \
+ { "I", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_pid_tuning_t, I) }, \
+ { "D", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_pid_tuning_t, D) }, \
+ { "SRate", NULL, MAVLINK_TYPE_FLOAT, 0, 25, offsetof(mavlink_pid_tuning_t, SRate) }, \
+ { "PDmod", NULL, MAVLINK_TYPE_FLOAT, 0, 29, offsetof(mavlink_pid_tuning_t, PDmod) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_PID_TUNING { \
+ "PID_TUNING", \
+ 9, \
+ { { "axis", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_pid_tuning_t, axis) }, \
+ { "desired", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_pid_tuning_t, desired) }, \
+ { "achieved", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_pid_tuning_t, achieved) }, \
+ { "FF", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_pid_tuning_t, FF) }, \
+ { "P", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_pid_tuning_t, P) }, \
+ { "I", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_pid_tuning_t, I) }, \
+ { "D", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_pid_tuning_t, D) }, \
+ { "SRate", NULL, MAVLINK_TYPE_FLOAT, 0, 25, offsetof(mavlink_pid_tuning_t, SRate) }, \
+ { "PDmod", NULL, MAVLINK_TYPE_FLOAT, 0, 29, offsetof(mavlink_pid_tuning_t, PDmod) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a pid_tuning 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 axis Axis.
+ * @param desired Desired rate.
+ * @param achieved Achieved rate.
+ * @param FF FF component.
+ * @param P P component.
+ * @param I I component.
+ * @param D D component.
+ * @param SRate Slew rate.
+ * @param PDmod P/D oscillation modifier.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_pid_tuning_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint8_t axis, float desired, float achieved, float FF, float P, float I, float D, float SRate, float PDmod)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_PID_TUNING_LEN];
+ _mav_put_float(buf, 0, desired);
+ _mav_put_float(buf, 4, achieved);
+ _mav_put_float(buf, 8, FF);
+ _mav_put_float(buf, 12, P);
+ _mav_put_float(buf, 16, I);
+ _mav_put_float(buf, 20, D);
+ _mav_put_uint8_t(buf, 24, axis);
+ _mav_put_float(buf, 25, SRate);
+ _mav_put_float(buf, 29, PDmod);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PID_TUNING_LEN);
+#else
+ mavlink_pid_tuning_t packet;
+ packet.desired = desired;
+ packet.achieved = achieved;
+ packet.FF = FF;
+ packet.P = P;
+ packet.I = I;
+ packet.D = D;
+ packet.axis = axis;
+ packet.SRate = SRate;
+ packet.PDmod = PDmod;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PID_TUNING_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_PID_TUNING;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PID_TUNING_MIN_LEN, MAVLINK_MSG_ID_PID_TUNING_LEN, MAVLINK_MSG_ID_PID_TUNING_CRC);
+}
+
+/**
+ * @brief Pack a pid_tuning 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 axis Axis.
+ * @param desired Desired rate.
+ * @param achieved Achieved rate.
+ * @param FF FF component.
+ * @param P P component.
+ * @param I I component.
+ * @param D D component.
+ * @param SRate Slew rate.
+ * @param PDmod P/D oscillation modifier.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_pid_tuning_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ uint8_t axis, float desired, float achieved, float FF, float P, float I, float D, float SRate, float PDmod)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_PID_TUNING_LEN];
+ _mav_put_float(buf, 0, desired);
+ _mav_put_float(buf, 4, achieved);
+ _mav_put_float(buf, 8, FF);
+ _mav_put_float(buf, 12, P);
+ _mav_put_float(buf, 16, I);
+ _mav_put_float(buf, 20, D);
+ _mav_put_uint8_t(buf, 24, axis);
+ _mav_put_float(buf, 25, SRate);
+ _mav_put_float(buf, 29, PDmod);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PID_TUNING_LEN);
+#else
+ mavlink_pid_tuning_t packet;
+ packet.desired = desired;
+ packet.achieved = achieved;
+ packet.FF = FF;
+ packet.P = P;
+ packet.I = I;
+ packet.D = D;
+ packet.axis = axis;
+ packet.SRate = SRate;
+ packet.PDmod = PDmod;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PID_TUNING_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_PID_TUNING;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_PID_TUNING_MIN_LEN, MAVLINK_MSG_ID_PID_TUNING_LEN, MAVLINK_MSG_ID_PID_TUNING_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_PID_TUNING_MIN_LEN, MAVLINK_MSG_ID_PID_TUNING_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a pid_tuning 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 axis Axis.
+ * @param desired Desired rate.
+ * @param achieved Achieved rate.
+ * @param FF FF component.
+ * @param P P component.
+ * @param I I component.
+ * @param D D component.
+ * @param SRate Slew rate.
+ * @param PDmod P/D oscillation modifier.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_pid_tuning_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint8_t axis,float desired,float achieved,float FF,float P,float I,float D,float SRate,float PDmod)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_PID_TUNING_LEN];
+ _mav_put_float(buf, 0, desired);
+ _mav_put_float(buf, 4, achieved);
+ _mav_put_float(buf, 8, FF);
+ _mav_put_float(buf, 12, P);
+ _mav_put_float(buf, 16, I);
+ _mav_put_float(buf, 20, D);
+ _mav_put_uint8_t(buf, 24, axis);
+ _mav_put_float(buf, 25, SRate);
+ _mav_put_float(buf, 29, PDmod);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PID_TUNING_LEN);
+#else
+ mavlink_pid_tuning_t packet;
+ packet.desired = desired;
+ packet.achieved = achieved;
+ packet.FF = FF;
+ packet.P = P;
+ packet.I = I;
+ packet.D = D;
+ packet.axis = axis;
+ packet.SRate = SRate;
+ packet.PDmod = PDmod;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PID_TUNING_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_PID_TUNING;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PID_TUNING_MIN_LEN, MAVLINK_MSG_ID_PID_TUNING_LEN, MAVLINK_MSG_ID_PID_TUNING_CRC);
+}
+
+/**
+ * @brief Encode a pid_tuning 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 pid_tuning C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_pid_tuning_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_pid_tuning_t* pid_tuning)
+{
+ return mavlink_msg_pid_tuning_pack(system_id, component_id, msg, pid_tuning->axis, pid_tuning->desired, pid_tuning->achieved, pid_tuning->FF, pid_tuning->P, pid_tuning->I, pid_tuning->D, pid_tuning->SRate, pid_tuning->PDmod);
+}
+
+/**
+ * @brief Encode a pid_tuning 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 pid_tuning C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_pid_tuning_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_pid_tuning_t* pid_tuning)
+{
+ return mavlink_msg_pid_tuning_pack_chan(system_id, component_id, chan, msg, pid_tuning->axis, pid_tuning->desired, pid_tuning->achieved, pid_tuning->FF, pid_tuning->P, pid_tuning->I, pid_tuning->D, pid_tuning->SRate, pid_tuning->PDmod);
+}
+
+/**
+ * @brief Encode a pid_tuning 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 pid_tuning C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_pid_tuning_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_pid_tuning_t* pid_tuning)
+{
+ return mavlink_msg_pid_tuning_pack_status(system_id, component_id, _status, msg, pid_tuning->axis, pid_tuning->desired, pid_tuning->achieved, pid_tuning->FF, pid_tuning->P, pid_tuning->I, pid_tuning->D, pid_tuning->SRate, pid_tuning->PDmod);
+}
+
+/**
+ * @brief Send a pid_tuning message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param axis Axis.
+ * @param desired Desired rate.
+ * @param achieved Achieved rate.
+ * @param FF FF component.
+ * @param P P component.
+ * @param I I component.
+ * @param D D component.
+ * @param SRate Slew rate.
+ * @param PDmod P/D oscillation modifier.
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_pid_tuning_send(mavlink_channel_t chan, uint8_t axis, float desired, float achieved, float FF, float P, float I, float D, float SRate, float PDmod)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_PID_TUNING_LEN];
+ _mav_put_float(buf, 0, desired);
+ _mav_put_float(buf, 4, achieved);
+ _mav_put_float(buf, 8, FF);
+ _mav_put_float(buf, 12, P);
+ _mav_put_float(buf, 16, I);
+ _mav_put_float(buf, 20, D);
+ _mav_put_uint8_t(buf, 24, axis);
+ _mav_put_float(buf, 25, SRate);
+ _mav_put_float(buf, 29, PDmod);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PID_TUNING, buf, MAVLINK_MSG_ID_PID_TUNING_MIN_LEN, MAVLINK_MSG_ID_PID_TUNING_LEN, MAVLINK_MSG_ID_PID_TUNING_CRC);
+#else
+ mavlink_pid_tuning_t packet;
+ packet.desired = desired;
+ packet.achieved = achieved;
+ packet.FF = FF;
+ packet.P = P;
+ packet.I = I;
+ packet.D = D;
+ packet.axis = axis;
+ packet.SRate = SRate;
+ packet.PDmod = PDmod;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PID_TUNING, (const char *)&packet, MAVLINK_MSG_ID_PID_TUNING_MIN_LEN, MAVLINK_MSG_ID_PID_TUNING_LEN, MAVLINK_MSG_ID_PID_TUNING_CRC);
+#endif
+}
+
+/**
+ * @brief Send a pid_tuning message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_pid_tuning_send_struct(mavlink_channel_t chan, const mavlink_pid_tuning_t* pid_tuning)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_pid_tuning_send(chan, pid_tuning->axis, pid_tuning->desired, pid_tuning->achieved, pid_tuning->FF, pid_tuning->P, pid_tuning->I, pid_tuning->D, pid_tuning->SRate, pid_tuning->PDmod);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PID_TUNING, (const char *)pid_tuning, MAVLINK_MSG_ID_PID_TUNING_MIN_LEN, MAVLINK_MSG_ID_PID_TUNING_LEN, MAVLINK_MSG_ID_PID_TUNING_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_PID_TUNING_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_pid_tuning_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t axis, float desired, float achieved, float FF, float P, float I, float D, float SRate, float PDmod)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_float(buf, 0, desired);
+ _mav_put_float(buf, 4, achieved);
+ _mav_put_float(buf, 8, FF);
+ _mav_put_float(buf, 12, P);
+ _mav_put_float(buf, 16, I);
+ _mav_put_float(buf, 20, D);
+ _mav_put_uint8_t(buf, 24, axis);
+ _mav_put_float(buf, 25, SRate);
+ _mav_put_float(buf, 29, PDmod);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PID_TUNING, buf, MAVLINK_MSG_ID_PID_TUNING_MIN_LEN, MAVLINK_MSG_ID_PID_TUNING_LEN, MAVLINK_MSG_ID_PID_TUNING_CRC);
+#else
+ mavlink_pid_tuning_t *packet = (mavlink_pid_tuning_t *)msgbuf;
+ packet->desired = desired;
+ packet->achieved = achieved;
+ packet->FF = FF;
+ packet->P = P;
+ packet->I = I;
+ packet->D = D;
+ packet->axis = axis;
+ packet->SRate = SRate;
+ packet->PDmod = PDmod;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PID_TUNING, (const char *)packet, MAVLINK_MSG_ID_PID_TUNING_MIN_LEN, MAVLINK_MSG_ID_PID_TUNING_LEN, MAVLINK_MSG_ID_PID_TUNING_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE PID_TUNING UNPACKING
+
+
+/**
+ * @brief Get field axis from pid_tuning message
+ *
+ * @return Axis.
+ */
+static inline uint8_t mavlink_msg_pid_tuning_get_axis(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 24);
+}
+
+/**
+ * @brief Get field desired from pid_tuning message
+ *
+ * @return Desired rate.
+ */
+static inline float mavlink_msg_pid_tuning_get_desired(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 0);
+}
+
+/**
+ * @brief Get field achieved from pid_tuning message
+ *
+ * @return Achieved rate.
+ */
+static inline float mavlink_msg_pid_tuning_get_achieved(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 4);
+}
+
+/**
+ * @brief Get field FF from pid_tuning message
+ *
+ * @return FF component.
+ */
+static inline float mavlink_msg_pid_tuning_get_FF(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 8);
+}
+
+/**
+ * @brief Get field P from pid_tuning message
+ *
+ * @return P component.
+ */
+static inline float mavlink_msg_pid_tuning_get_P(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 12);
+}
+
+/**
+ * @brief Get field I from pid_tuning message
+ *
+ * @return I component.
+ */
+static inline float mavlink_msg_pid_tuning_get_I(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 16);
+}
+
+/**
+ * @brief Get field D from pid_tuning message
+ *
+ * @return D component.
+ */
+static inline float mavlink_msg_pid_tuning_get_D(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 20);
+}
+
+/**
+ * @brief Get field SRate from pid_tuning message
+ *
+ * @return Slew rate.
+ */
+static inline float mavlink_msg_pid_tuning_get_SRate(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 25);
+}
+
+/**
+ * @brief Get field PDmod from pid_tuning message
+ *
+ * @return P/D oscillation modifier.
+ */
+static inline float mavlink_msg_pid_tuning_get_PDmod(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 29);
+}
+
+/**
+ * @brief Decode a pid_tuning message into a struct
+ *
+ * @param msg The message to decode
+ * @param pid_tuning C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_pid_tuning_decode(const mavlink_message_t* msg, mavlink_pid_tuning_t* pid_tuning)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ pid_tuning->desired = mavlink_msg_pid_tuning_get_desired(msg);
+ pid_tuning->achieved = mavlink_msg_pid_tuning_get_achieved(msg);
+ pid_tuning->FF = mavlink_msg_pid_tuning_get_FF(msg);
+ pid_tuning->P = mavlink_msg_pid_tuning_get_P(msg);
+ pid_tuning->I = mavlink_msg_pid_tuning_get_I(msg);
+ pid_tuning->D = mavlink_msg_pid_tuning_get_D(msg);
+ pid_tuning->axis = mavlink_msg_pid_tuning_get_axis(msg);
+ pid_tuning->SRate = mavlink_msg_pid_tuning_get_SRate(msg);
+ pid_tuning->PDmod = mavlink_msg_pid_tuning_get_PDmod(msg);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_PID_TUNING_LEN? msg->len : MAVLINK_MSG_ID_PID_TUNING_LEN;
+ memset(pid_tuning, 0, MAVLINK_MSG_ID_PID_TUNING_LEN);
+ memcpy(pid_tuning, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/ardupilotmega/mavlink_msg_radio.h b/lib/main/MAVLink/ardupilotmega/mavlink_msg_radio.h
new file mode 100644
index 00000000000..a0e516da94a
--- /dev/null
+++ b/lib/main/MAVLink/ardupilotmega/mavlink_msg_radio.h
@@ -0,0 +1,428 @@
+#pragma once
+// MESSAGE RADIO PACKING
+
+#define MAVLINK_MSG_ID_RADIO 166
+
+
+typedef struct __mavlink_radio_t {
+ uint16_t rxerrors; /*< Receive errors.*/
+ uint16_t fixed; /*< Count of error corrected packets.*/
+ uint8_t rssi; /*< Local signal strength.*/
+ uint8_t remrssi; /*< Remote signal strength.*/
+ uint8_t txbuf; /*< [%] How full the tx buffer is.*/
+ uint8_t noise; /*< Background noise level.*/
+ uint8_t remnoise; /*< Remote background noise level.*/
+} mavlink_radio_t;
+
+#define MAVLINK_MSG_ID_RADIO_LEN 9
+#define MAVLINK_MSG_ID_RADIO_MIN_LEN 9
+#define MAVLINK_MSG_ID_166_LEN 9
+#define MAVLINK_MSG_ID_166_MIN_LEN 9
+
+#define MAVLINK_MSG_ID_RADIO_CRC 21
+#define MAVLINK_MSG_ID_166_CRC 21
+
+
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_RADIO { \
+ 166, \
+ "RADIO", \
+ 7, \
+ { { "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_radio_t, rssi) }, \
+ { "remrssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_radio_t, remrssi) }, \
+ { "txbuf", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_radio_t, txbuf) }, \
+ { "noise", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_radio_t, noise) }, \
+ { "remnoise", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_radio_t, remnoise) }, \
+ { "rxerrors", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_radio_t, rxerrors) }, \
+ { "fixed", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_radio_t, fixed) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_RADIO { \
+ "RADIO", \
+ 7, \
+ { { "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_radio_t, rssi) }, \
+ { "remrssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_radio_t, remrssi) }, \
+ { "txbuf", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_radio_t, txbuf) }, \
+ { "noise", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_radio_t, noise) }, \
+ { "remnoise", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_radio_t, remnoise) }, \
+ { "rxerrors", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_radio_t, rxerrors) }, \
+ { "fixed", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_radio_t, fixed) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a radio 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 rssi Local signal strength.
+ * @param remrssi Remote signal strength.
+ * @param txbuf [%] How full the tx buffer is.
+ * @param noise Background noise level.
+ * @param remnoise Remote background noise level.
+ * @param rxerrors Receive errors.
+ * @param fixed Count of error corrected packets.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_radio_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint8_t rssi, uint8_t remrssi, uint8_t txbuf, uint8_t noise, uint8_t remnoise, uint16_t rxerrors, uint16_t fixed)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_RADIO_LEN];
+ _mav_put_uint16_t(buf, 0, rxerrors);
+ _mav_put_uint16_t(buf, 2, fixed);
+ _mav_put_uint8_t(buf, 4, rssi);
+ _mav_put_uint8_t(buf, 5, remrssi);
+ _mav_put_uint8_t(buf, 6, txbuf);
+ _mav_put_uint8_t(buf, 7, noise);
+ _mav_put_uint8_t(buf, 8, remnoise);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RADIO_LEN);
+#else
+ mavlink_radio_t packet;
+ packet.rxerrors = rxerrors;
+ packet.fixed = fixed;
+ packet.rssi = rssi;
+ packet.remrssi = remrssi;
+ packet.txbuf = txbuf;
+ packet.noise = noise;
+ packet.remnoise = remnoise;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RADIO_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_RADIO;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RADIO_MIN_LEN, MAVLINK_MSG_ID_RADIO_LEN, MAVLINK_MSG_ID_RADIO_CRC);
+}
+
+/**
+ * @brief Pack a radio 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 rssi Local signal strength.
+ * @param remrssi Remote signal strength.
+ * @param txbuf [%] How full the tx buffer is.
+ * @param noise Background noise level.
+ * @param remnoise Remote background noise level.
+ * @param rxerrors Receive errors.
+ * @param fixed Count of error corrected packets.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_radio_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ uint8_t rssi, uint8_t remrssi, uint8_t txbuf, uint8_t noise, uint8_t remnoise, uint16_t rxerrors, uint16_t fixed)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_RADIO_LEN];
+ _mav_put_uint16_t(buf, 0, rxerrors);
+ _mav_put_uint16_t(buf, 2, fixed);
+ _mav_put_uint8_t(buf, 4, rssi);
+ _mav_put_uint8_t(buf, 5, remrssi);
+ _mav_put_uint8_t(buf, 6, txbuf);
+ _mav_put_uint8_t(buf, 7, noise);
+ _mav_put_uint8_t(buf, 8, remnoise);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RADIO_LEN);
+#else
+ mavlink_radio_t packet;
+ packet.rxerrors = rxerrors;
+ packet.fixed = fixed;
+ packet.rssi = rssi;
+ packet.remrssi = remrssi;
+ packet.txbuf = txbuf;
+ packet.noise = noise;
+ packet.remnoise = remnoise;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RADIO_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_RADIO;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_RADIO_MIN_LEN, MAVLINK_MSG_ID_RADIO_LEN, MAVLINK_MSG_ID_RADIO_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_RADIO_MIN_LEN, MAVLINK_MSG_ID_RADIO_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a radio 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 rssi Local signal strength.
+ * @param remrssi Remote signal strength.
+ * @param txbuf [%] How full the tx buffer is.
+ * @param noise Background noise level.
+ * @param remnoise Remote background noise level.
+ * @param rxerrors Receive errors.
+ * @param fixed Count of error corrected packets.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_radio_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint8_t rssi,uint8_t remrssi,uint8_t txbuf,uint8_t noise,uint8_t remnoise,uint16_t rxerrors,uint16_t fixed)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_RADIO_LEN];
+ _mav_put_uint16_t(buf, 0, rxerrors);
+ _mav_put_uint16_t(buf, 2, fixed);
+ _mav_put_uint8_t(buf, 4, rssi);
+ _mav_put_uint8_t(buf, 5, remrssi);
+ _mav_put_uint8_t(buf, 6, txbuf);
+ _mav_put_uint8_t(buf, 7, noise);
+ _mav_put_uint8_t(buf, 8, remnoise);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RADIO_LEN);
+#else
+ mavlink_radio_t packet;
+ packet.rxerrors = rxerrors;
+ packet.fixed = fixed;
+ packet.rssi = rssi;
+ packet.remrssi = remrssi;
+ packet.txbuf = txbuf;
+ packet.noise = noise;
+ packet.remnoise = remnoise;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RADIO_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_RADIO;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RADIO_MIN_LEN, MAVLINK_MSG_ID_RADIO_LEN, MAVLINK_MSG_ID_RADIO_CRC);
+}
+
+/**
+ * @brief Encode a radio 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 radio C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_radio_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_radio_t* radio)
+{
+ return mavlink_msg_radio_pack(system_id, component_id, msg, radio->rssi, radio->remrssi, radio->txbuf, radio->noise, radio->remnoise, radio->rxerrors, radio->fixed);
+}
+
+/**
+ * @brief Encode a radio 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 radio C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_radio_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_radio_t* radio)
+{
+ return mavlink_msg_radio_pack_chan(system_id, component_id, chan, msg, radio->rssi, radio->remrssi, radio->txbuf, radio->noise, radio->remnoise, radio->rxerrors, radio->fixed);
+}
+
+/**
+ * @brief Encode a radio 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 radio C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_radio_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_radio_t* radio)
+{
+ return mavlink_msg_radio_pack_status(system_id, component_id, _status, msg, radio->rssi, radio->remrssi, radio->txbuf, radio->noise, radio->remnoise, radio->rxerrors, radio->fixed);
+}
+
+/**
+ * @brief Send a radio message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param rssi Local signal strength.
+ * @param remrssi Remote signal strength.
+ * @param txbuf [%] How full the tx buffer is.
+ * @param noise Background noise level.
+ * @param remnoise Remote background noise level.
+ * @param rxerrors Receive errors.
+ * @param fixed Count of error corrected packets.
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_radio_send(mavlink_channel_t chan, uint8_t rssi, uint8_t remrssi, uint8_t txbuf, uint8_t noise, uint8_t remnoise, uint16_t rxerrors, uint16_t fixed)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_RADIO_LEN];
+ _mav_put_uint16_t(buf, 0, rxerrors);
+ _mav_put_uint16_t(buf, 2, fixed);
+ _mav_put_uint8_t(buf, 4, rssi);
+ _mav_put_uint8_t(buf, 5, remrssi);
+ _mav_put_uint8_t(buf, 6, txbuf);
+ _mav_put_uint8_t(buf, 7, noise);
+ _mav_put_uint8_t(buf, 8, remnoise);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO, buf, MAVLINK_MSG_ID_RADIO_MIN_LEN, MAVLINK_MSG_ID_RADIO_LEN, MAVLINK_MSG_ID_RADIO_CRC);
+#else
+ mavlink_radio_t packet;
+ packet.rxerrors = rxerrors;
+ packet.fixed = fixed;
+ packet.rssi = rssi;
+ packet.remrssi = remrssi;
+ packet.txbuf = txbuf;
+ packet.noise = noise;
+ packet.remnoise = remnoise;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO, (const char *)&packet, MAVLINK_MSG_ID_RADIO_MIN_LEN, MAVLINK_MSG_ID_RADIO_LEN, MAVLINK_MSG_ID_RADIO_CRC);
+#endif
+}
+
+/**
+ * @brief Send a radio message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_radio_send_struct(mavlink_channel_t chan, const mavlink_radio_t* radio)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_radio_send(chan, radio->rssi, radio->remrssi, radio->txbuf, radio->noise, radio->remnoise, radio->rxerrors, radio->fixed);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO, (const char *)radio, MAVLINK_MSG_ID_RADIO_MIN_LEN, MAVLINK_MSG_ID_RADIO_LEN, MAVLINK_MSG_ID_RADIO_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_RADIO_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_radio_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t rssi, uint8_t remrssi, uint8_t txbuf, uint8_t noise, uint8_t remnoise, uint16_t rxerrors, uint16_t fixed)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint16_t(buf, 0, rxerrors);
+ _mav_put_uint16_t(buf, 2, fixed);
+ _mav_put_uint8_t(buf, 4, rssi);
+ _mav_put_uint8_t(buf, 5, remrssi);
+ _mav_put_uint8_t(buf, 6, txbuf);
+ _mav_put_uint8_t(buf, 7, noise);
+ _mav_put_uint8_t(buf, 8, remnoise);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO, buf, MAVLINK_MSG_ID_RADIO_MIN_LEN, MAVLINK_MSG_ID_RADIO_LEN, MAVLINK_MSG_ID_RADIO_CRC);
+#else
+ mavlink_radio_t *packet = (mavlink_radio_t *)msgbuf;
+ packet->rxerrors = rxerrors;
+ packet->fixed = fixed;
+ packet->rssi = rssi;
+ packet->remrssi = remrssi;
+ packet->txbuf = txbuf;
+ packet->noise = noise;
+ packet->remnoise = remnoise;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO, (const char *)packet, MAVLINK_MSG_ID_RADIO_MIN_LEN, MAVLINK_MSG_ID_RADIO_LEN, MAVLINK_MSG_ID_RADIO_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE RADIO UNPACKING
+
+
+/**
+ * @brief Get field rssi from radio message
+ *
+ * @return Local signal strength.
+ */
+static inline uint8_t mavlink_msg_radio_get_rssi(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 4);
+}
+
+/**
+ * @brief Get field remrssi from radio message
+ *
+ * @return Remote signal strength.
+ */
+static inline uint8_t mavlink_msg_radio_get_remrssi(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 5);
+}
+
+/**
+ * @brief Get field txbuf from radio message
+ *
+ * @return [%] How full the tx buffer is.
+ */
+static inline uint8_t mavlink_msg_radio_get_txbuf(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 6);
+}
+
+/**
+ * @brief Get field noise from radio message
+ *
+ * @return Background noise level.
+ */
+static inline uint8_t mavlink_msg_radio_get_noise(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 7);
+}
+
+/**
+ * @brief Get field remnoise from radio message
+ *
+ * @return Remote background noise level.
+ */
+static inline uint8_t mavlink_msg_radio_get_remnoise(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 8);
+}
+
+/**
+ * @brief Get field rxerrors from radio message
+ *
+ * @return Receive errors.
+ */
+static inline uint16_t mavlink_msg_radio_get_rxerrors(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 0);
+}
+
+/**
+ * @brief Get field fixed from radio message
+ *
+ * @return Count of error corrected packets.
+ */
+static inline uint16_t mavlink_msg_radio_get_fixed(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 2);
+}
+
+/**
+ * @brief Decode a radio message into a struct
+ *
+ * @param msg The message to decode
+ * @param radio C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_radio_decode(const mavlink_message_t* msg, mavlink_radio_t* radio)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ radio->rxerrors = mavlink_msg_radio_get_rxerrors(msg);
+ radio->fixed = mavlink_msg_radio_get_fixed(msg);
+ radio->rssi = mavlink_msg_radio_get_rssi(msg);
+ radio->remrssi = mavlink_msg_radio_get_remrssi(msg);
+ radio->txbuf = mavlink_msg_radio_get_txbuf(msg);
+ radio->noise = mavlink_msg_radio_get_noise(msg);
+ radio->remnoise = mavlink_msg_radio_get_remnoise(msg);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_RADIO_LEN? msg->len : MAVLINK_MSG_ID_RADIO_LEN;
+ memset(radio, 0, MAVLINK_MSG_ID_RADIO_LEN);
+ memcpy(radio, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/ardupilotmega/mavlink_msg_rally_fetch_point.h b/lib/main/MAVLink/ardupilotmega/mavlink_msg_rally_fetch_point.h
new file mode 100644
index 00000000000..e302fdbc2f8
--- /dev/null
+++ b/lib/main/MAVLink/ardupilotmega/mavlink_msg_rally_fetch_point.h
@@ -0,0 +1,316 @@
+#pragma once
+// MESSAGE RALLY_FETCH_POINT PACKING
+
+#define MAVLINK_MSG_ID_RALLY_FETCH_POINT 176
+
+
+typedef struct __mavlink_rally_fetch_point_t {
+ uint8_t target_system; /*< System ID.*/
+ uint8_t target_component; /*< Component ID.*/
+ uint8_t idx; /*< Point index (first point is 0).*/
+} mavlink_rally_fetch_point_t;
+
+#define MAVLINK_MSG_ID_RALLY_FETCH_POINT_LEN 3
+#define MAVLINK_MSG_ID_RALLY_FETCH_POINT_MIN_LEN 3
+#define MAVLINK_MSG_ID_176_LEN 3
+#define MAVLINK_MSG_ID_176_MIN_LEN 3
+
+#define MAVLINK_MSG_ID_RALLY_FETCH_POINT_CRC 234
+#define MAVLINK_MSG_ID_176_CRC 234
+
+
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_RALLY_FETCH_POINT { \
+ 176, \
+ "RALLY_FETCH_POINT", \
+ 3, \
+ { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_rally_fetch_point_t, target_system) }, \
+ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_rally_fetch_point_t, target_component) }, \
+ { "idx", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_rally_fetch_point_t, idx) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_RALLY_FETCH_POINT { \
+ "RALLY_FETCH_POINT", \
+ 3, \
+ { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_rally_fetch_point_t, target_system) }, \
+ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_rally_fetch_point_t, target_component) }, \
+ { "idx", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_rally_fetch_point_t, idx) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a rally_fetch_point 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 target_system System ID.
+ * @param target_component Component ID.
+ * @param idx Point index (first point is 0).
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_rally_fetch_point_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint8_t target_system, uint8_t target_component, uint8_t idx)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_RALLY_FETCH_POINT_LEN];
+ _mav_put_uint8_t(buf, 0, target_system);
+ _mav_put_uint8_t(buf, 1, target_component);
+ _mav_put_uint8_t(buf, 2, idx);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RALLY_FETCH_POINT_LEN);
+#else
+ mavlink_rally_fetch_point_t packet;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.idx = idx;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RALLY_FETCH_POINT_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_RALLY_FETCH_POINT;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RALLY_FETCH_POINT_MIN_LEN, MAVLINK_MSG_ID_RALLY_FETCH_POINT_LEN, MAVLINK_MSG_ID_RALLY_FETCH_POINT_CRC);
+}
+
+/**
+ * @brief Pack a rally_fetch_point 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 target_system System ID.
+ * @param target_component Component ID.
+ * @param idx Point index (first point is 0).
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_rally_fetch_point_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ uint8_t target_system, uint8_t target_component, uint8_t idx)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_RALLY_FETCH_POINT_LEN];
+ _mav_put_uint8_t(buf, 0, target_system);
+ _mav_put_uint8_t(buf, 1, target_component);
+ _mav_put_uint8_t(buf, 2, idx);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RALLY_FETCH_POINT_LEN);
+#else
+ mavlink_rally_fetch_point_t packet;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.idx = idx;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RALLY_FETCH_POINT_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_RALLY_FETCH_POINT;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_RALLY_FETCH_POINT_MIN_LEN, MAVLINK_MSG_ID_RALLY_FETCH_POINT_LEN, MAVLINK_MSG_ID_RALLY_FETCH_POINT_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_RALLY_FETCH_POINT_MIN_LEN, MAVLINK_MSG_ID_RALLY_FETCH_POINT_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a rally_fetch_point 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 target_system System ID.
+ * @param target_component Component ID.
+ * @param idx Point index (first point is 0).
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_rally_fetch_point_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint8_t target_system,uint8_t target_component,uint8_t idx)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_RALLY_FETCH_POINT_LEN];
+ _mav_put_uint8_t(buf, 0, target_system);
+ _mav_put_uint8_t(buf, 1, target_component);
+ _mav_put_uint8_t(buf, 2, idx);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RALLY_FETCH_POINT_LEN);
+#else
+ mavlink_rally_fetch_point_t packet;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.idx = idx;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RALLY_FETCH_POINT_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_RALLY_FETCH_POINT;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RALLY_FETCH_POINT_MIN_LEN, MAVLINK_MSG_ID_RALLY_FETCH_POINT_LEN, MAVLINK_MSG_ID_RALLY_FETCH_POINT_CRC);
+}
+
+/**
+ * @brief Encode a rally_fetch_point 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 rally_fetch_point C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_rally_fetch_point_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rally_fetch_point_t* rally_fetch_point)
+{
+ return mavlink_msg_rally_fetch_point_pack(system_id, component_id, msg, rally_fetch_point->target_system, rally_fetch_point->target_component, rally_fetch_point->idx);
+}
+
+/**
+ * @brief Encode a rally_fetch_point 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 rally_fetch_point C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_rally_fetch_point_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_rally_fetch_point_t* rally_fetch_point)
+{
+ return mavlink_msg_rally_fetch_point_pack_chan(system_id, component_id, chan, msg, rally_fetch_point->target_system, rally_fetch_point->target_component, rally_fetch_point->idx);
+}
+
+/**
+ * @brief Encode a rally_fetch_point 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 rally_fetch_point C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_rally_fetch_point_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_rally_fetch_point_t* rally_fetch_point)
+{
+ return mavlink_msg_rally_fetch_point_pack_status(system_id, component_id, _status, msg, rally_fetch_point->target_system, rally_fetch_point->target_component, rally_fetch_point->idx);
+}
+
+/**
+ * @brief Send a rally_fetch_point message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param target_system System ID.
+ * @param target_component Component ID.
+ * @param idx Point index (first point is 0).
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_rally_fetch_point_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t idx)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_RALLY_FETCH_POINT_LEN];
+ _mav_put_uint8_t(buf, 0, target_system);
+ _mav_put_uint8_t(buf, 1, target_component);
+ _mav_put_uint8_t(buf, 2, idx);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RALLY_FETCH_POINT, buf, MAVLINK_MSG_ID_RALLY_FETCH_POINT_MIN_LEN, MAVLINK_MSG_ID_RALLY_FETCH_POINT_LEN, MAVLINK_MSG_ID_RALLY_FETCH_POINT_CRC);
+#else
+ mavlink_rally_fetch_point_t packet;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.idx = idx;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RALLY_FETCH_POINT, (const char *)&packet, MAVLINK_MSG_ID_RALLY_FETCH_POINT_MIN_LEN, MAVLINK_MSG_ID_RALLY_FETCH_POINT_LEN, MAVLINK_MSG_ID_RALLY_FETCH_POINT_CRC);
+#endif
+}
+
+/**
+ * @brief Send a rally_fetch_point message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_rally_fetch_point_send_struct(mavlink_channel_t chan, const mavlink_rally_fetch_point_t* rally_fetch_point)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_rally_fetch_point_send(chan, rally_fetch_point->target_system, rally_fetch_point->target_component, rally_fetch_point->idx);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RALLY_FETCH_POINT, (const char *)rally_fetch_point, MAVLINK_MSG_ID_RALLY_FETCH_POINT_MIN_LEN, MAVLINK_MSG_ID_RALLY_FETCH_POINT_LEN, MAVLINK_MSG_ID_RALLY_FETCH_POINT_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_RALLY_FETCH_POINT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_rally_fetch_point_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t idx)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint8_t(buf, 0, target_system);
+ _mav_put_uint8_t(buf, 1, target_component);
+ _mav_put_uint8_t(buf, 2, idx);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RALLY_FETCH_POINT, buf, MAVLINK_MSG_ID_RALLY_FETCH_POINT_MIN_LEN, MAVLINK_MSG_ID_RALLY_FETCH_POINT_LEN, MAVLINK_MSG_ID_RALLY_FETCH_POINT_CRC);
+#else
+ mavlink_rally_fetch_point_t *packet = (mavlink_rally_fetch_point_t *)msgbuf;
+ packet->target_system = target_system;
+ packet->target_component = target_component;
+ packet->idx = idx;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RALLY_FETCH_POINT, (const char *)packet, MAVLINK_MSG_ID_RALLY_FETCH_POINT_MIN_LEN, MAVLINK_MSG_ID_RALLY_FETCH_POINT_LEN, MAVLINK_MSG_ID_RALLY_FETCH_POINT_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE RALLY_FETCH_POINT UNPACKING
+
+
+/**
+ * @brief Get field target_system from rally_fetch_point message
+ *
+ * @return System ID.
+ */
+static inline uint8_t mavlink_msg_rally_fetch_point_get_target_system(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 0);
+}
+
+/**
+ * @brief Get field target_component from rally_fetch_point message
+ *
+ * @return Component ID.
+ */
+static inline uint8_t mavlink_msg_rally_fetch_point_get_target_component(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 1);
+}
+
+/**
+ * @brief Get field idx from rally_fetch_point message
+ *
+ * @return Point index (first point is 0).
+ */
+static inline uint8_t mavlink_msg_rally_fetch_point_get_idx(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 2);
+}
+
+/**
+ * @brief Decode a rally_fetch_point message into a struct
+ *
+ * @param msg The message to decode
+ * @param rally_fetch_point C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_rally_fetch_point_decode(const mavlink_message_t* msg, mavlink_rally_fetch_point_t* rally_fetch_point)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ rally_fetch_point->target_system = mavlink_msg_rally_fetch_point_get_target_system(msg);
+ rally_fetch_point->target_component = mavlink_msg_rally_fetch_point_get_target_component(msg);
+ rally_fetch_point->idx = mavlink_msg_rally_fetch_point_get_idx(msg);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_RALLY_FETCH_POINT_LEN? msg->len : MAVLINK_MSG_ID_RALLY_FETCH_POINT_LEN;
+ memset(rally_fetch_point, 0, MAVLINK_MSG_ID_RALLY_FETCH_POINT_LEN);
+ memcpy(rally_fetch_point, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/ardupilotmega/mavlink_msg_rally_point.h b/lib/main/MAVLink/ardupilotmega/mavlink_msg_rally_point.h
new file mode 100644
index 00000000000..1472fc40c7d
--- /dev/null
+++ b/lib/main/MAVLink/ardupilotmega/mavlink_msg_rally_point.h
@@ -0,0 +1,512 @@
+#pragma once
+// MESSAGE RALLY_POINT PACKING
+
+#define MAVLINK_MSG_ID_RALLY_POINT 175
+
+
+typedef struct __mavlink_rally_point_t {
+ int32_t lat; /*< [degE7] Latitude of point.*/
+ int32_t lng; /*< [degE7] Longitude of point.*/
+ int16_t alt; /*< [m] Transit / loiter altitude relative to home.*/
+ int16_t break_alt; /*< [m] Break altitude relative to home.*/
+ uint16_t land_dir; /*< [cdeg] Heading to aim for when landing.*/
+ uint8_t target_system; /*< System ID.*/
+ uint8_t target_component; /*< Component ID.*/
+ uint8_t idx; /*< Point index (first point is 0).*/
+ uint8_t count; /*< Total number of points (for sanity checking).*/
+ uint8_t flags; /*< Configuration flags.*/
+} mavlink_rally_point_t;
+
+#define MAVLINK_MSG_ID_RALLY_POINT_LEN 19
+#define MAVLINK_MSG_ID_RALLY_POINT_MIN_LEN 19
+#define MAVLINK_MSG_ID_175_LEN 19
+#define MAVLINK_MSG_ID_175_MIN_LEN 19
+
+#define MAVLINK_MSG_ID_RALLY_POINT_CRC 138
+#define MAVLINK_MSG_ID_175_CRC 138
+
+
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_RALLY_POINT { \
+ 175, \
+ "RALLY_POINT", \
+ 10, \
+ { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 14, offsetof(mavlink_rally_point_t, target_system) }, \
+ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 15, offsetof(mavlink_rally_point_t, target_component) }, \
+ { "idx", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_rally_point_t, idx) }, \
+ { "count", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_rally_point_t, count) }, \
+ { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_rally_point_t, lat) }, \
+ { "lng", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_rally_point_t, lng) }, \
+ { "alt", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_rally_point_t, alt) }, \
+ { "break_alt", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_rally_point_t, break_alt) }, \
+ { "land_dir", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_rally_point_t, land_dir) }, \
+ { "flags", NULL, MAVLINK_TYPE_UINT8_T, 0, 18, offsetof(mavlink_rally_point_t, flags) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_RALLY_POINT { \
+ "RALLY_POINT", \
+ 10, \
+ { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 14, offsetof(mavlink_rally_point_t, target_system) }, \
+ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 15, offsetof(mavlink_rally_point_t, target_component) }, \
+ { "idx", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_rally_point_t, idx) }, \
+ { "count", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_rally_point_t, count) }, \
+ { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_rally_point_t, lat) }, \
+ { "lng", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_rally_point_t, lng) }, \
+ { "alt", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_rally_point_t, alt) }, \
+ { "break_alt", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_rally_point_t, break_alt) }, \
+ { "land_dir", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_rally_point_t, land_dir) }, \
+ { "flags", NULL, MAVLINK_TYPE_UINT8_T, 0, 18, offsetof(mavlink_rally_point_t, flags) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a rally_point 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 target_system System ID.
+ * @param target_component Component ID.
+ * @param idx Point index (first point is 0).
+ * @param count Total number of points (for sanity checking).
+ * @param lat [degE7] Latitude of point.
+ * @param lng [degE7] Longitude of point.
+ * @param alt [m] Transit / loiter altitude relative to home.
+ * @param break_alt [m] Break altitude relative to home.
+ * @param land_dir [cdeg] Heading to aim for when landing.
+ * @param flags Configuration flags.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_rally_point_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint8_t target_system, uint8_t target_component, uint8_t idx, uint8_t count, int32_t lat, int32_t lng, int16_t alt, int16_t break_alt, uint16_t land_dir, uint8_t flags)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_RALLY_POINT_LEN];
+ _mav_put_int32_t(buf, 0, lat);
+ _mav_put_int32_t(buf, 4, lng);
+ _mav_put_int16_t(buf, 8, alt);
+ _mav_put_int16_t(buf, 10, break_alt);
+ _mav_put_uint16_t(buf, 12, land_dir);
+ _mav_put_uint8_t(buf, 14, target_system);
+ _mav_put_uint8_t(buf, 15, target_component);
+ _mav_put_uint8_t(buf, 16, idx);
+ _mav_put_uint8_t(buf, 17, count);
+ _mav_put_uint8_t(buf, 18, flags);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RALLY_POINT_LEN);
+#else
+ mavlink_rally_point_t packet;
+ packet.lat = lat;
+ packet.lng = lng;
+ packet.alt = alt;
+ packet.break_alt = break_alt;
+ packet.land_dir = land_dir;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.idx = idx;
+ packet.count = count;
+ packet.flags = flags;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RALLY_POINT_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_RALLY_POINT;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RALLY_POINT_MIN_LEN, MAVLINK_MSG_ID_RALLY_POINT_LEN, MAVLINK_MSG_ID_RALLY_POINT_CRC);
+}
+
+/**
+ * @brief Pack a rally_point 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 target_system System ID.
+ * @param target_component Component ID.
+ * @param idx Point index (first point is 0).
+ * @param count Total number of points (for sanity checking).
+ * @param lat [degE7] Latitude of point.
+ * @param lng [degE7] Longitude of point.
+ * @param alt [m] Transit / loiter altitude relative to home.
+ * @param break_alt [m] Break altitude relative to home.
+ * @param land_dir [cdeg] Heading to aim for when landing.
+ * @param flags Configuration flags.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_rally_point_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ uint8_t target_system, uint8_t target_component, uint8_t idx, uint8_t count, int32_t lat, int32_t lng, int16_t alt, int16_t break_alt, uint16_t land_dir, uint8_t flags)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_RALLY_POINT_LEN];
+ _mav_put_int32_t(buf, 0, lat);
+ _mav_put_int32_t(buf, 4, lng);
+ _mav_put_int16_t(buf, 8, alt);
+ _mav_put_int16_t(buf, 10, break_alt);
+ _mav_put_uint16_t(buf, 12, land_dir);
+ _mav_put_uint8_t(buf, 14, target_system);
+ _mav_put_uint8_t(buf, 15, target_component);
+ _mav_put_uint8_t(buf, 16, idx);
+ _mav_put_uint8_t(buf, 17, count);
+ _mav_put_uint8_t(buf, 18, flags);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RALLY_POINT_LEN);
+#else
+ mavlink_rally_point_t packet;
+ packet.lat = lat;
+ packet.lng = lng;
+ packet.alt = alt;
+ packet.break_alt = break_alt;
+ packet.land_dir = land_dir;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.idx = idx;
+ packet.count = count;
+ packet.flags = flags;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RALLY_POINT_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_RALLY_POINT;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_RALLY_POINT_MIN_LEN, MAVLINK_MSG_ID_RALLY_POINT_LEN, MAVLINK_MSG_ID_RALLY_POINT_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_RALLY_POINT_MIN_LEN, MAVLINK_MSG_ID_RALLY_POINT_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a rally_point 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 target_system System ID.
+ * @param target_component Component ID.
+ * @param idx Point index (first point is 0).
+ * @param count Total number of points (for sanity checking).
+ * @param lat [degE7] Latitude of point.
+ * @param lng [degE7] Longitude of point.
+ * @param alt [m] Transit / loiter altitude relative to home.
+ * @param break_alt [m] Break altitude relative to home.
+ * @param land_dir [cdeg] Heading to aim for when landing.
+ * @param flags Configuration flags.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_rally_point_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint8_t target_system,uint8_t target_component,uint8_t idx,uint8_t count,int32_t lat,int32_t lng,int16_t alt,int16_t break_alt,uint16_t land_dir,uint8_t flags)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_RALLY_POINT_LEN];
+ _mav_put_int32_t(buf, 0, lat);
+ _mav_put_int32_t(buf, 4, lng);
+ _mav_put_int16_t(buf, 8, alt);
+ _mav_put_int16_t(buf, 10, break_alt);
+ _mav_put_uint16_t(buf, 12, land_dir);
+ _mav_put_uint8_t(buf, 14, target_system);
+ _mav_put_uint8_t(buf, 15, target_component);
+ _mav_put_uint8_t(buf, 16, idx);
+ _mav_put_uint8_t(buf, 17, count);
+ _mav_put_uint8_t(buf, 18, flags);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RALLY_POINT_LEN);
+#else
+ mavlink_rally_point_t packet;
+ packet.lat = lat;
+ packet.lng = lng;
+ packet.alt = alt;
+ packet.break_alt = break_alt;
+ packet.land_dir = land_dir;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.idx = idx;
+ packet.count = count;
+ packet.flags = flags;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RALLY_POINT_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_RALLY_POINT;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RALLY_POINT_MIN_LEN, MAVLINK_MSG_ID_RALLY_POINT_LEN, MAVLINK_MSG_ID_RALLY_POINT_CRC);
+}
+
+/**
+ * @brief Encode a rally_point 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 rally_point C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_rally_point_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rally_point_t* rally_point)
+{
+ return mavlink_msg_rally_point_pack(system_id, component_id, msg, rally_point->target_system, rally_point->target_component, rally_point->idx, rally_point->count, rally_point->lat, rally_point->lng, rally_point->alt, rally_point->break_alt, rally_point->land_dir, rally_point->flags);
+}
+
+/**
+ * @brief Encode a rally_point 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 rally_point C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_rally_point_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_rally_point_t* rally_point)
+{
+ return mavlink_msg_rally_point_pack_chan(system_id, component_id, chan, msg, rally_point->target_system, rally_point->target_component, rally_point->idx, rally_point->count, rally_point->lat, rally_point->lng, rally_point->alt, rally_point->break_alt, rally_point->land_dir, rally_point->flags);
+}
+
+/**
+ * @brief Encode a rally_point 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 rally_point C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_rally_point_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_rally_point_t* rally_point)
+{
+ return mavlink_msg_rally_point_pack_status(system_id, component_id, _status, msg, rally_point->target_system, rally_point->target_component, rally_point->idx, rally_point->count, rally_point->lat, rally_point->lng, rally_point->alt, rally_point->break_alt, rally_point->land_dir, rally_point->flags);
+}
+
+/**
+ * @brief Send a rally_point message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param target_system System ID.
+ * @param target_component Component ID.
+ * @param idx Point index (first point is 0).
+ * @param count Total number of points (for sanity checking).
+ * @param lat [degE7] Latitude of point.
+ * @param lng [degE7] Longitude of point.
+ * @param alt [m] Transit / loiter altitude relative to home.
+ * @param break_alt [m] Break altitude relative to home.
+ * @param land_dir [cdeg] Heading to aim for when landing.
+ * @param flags Configuration flags.
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_rally_point_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t idx, uint8_t count, int32_t lat, int32_t lng, int16_t alt, int16_t break_alt, uint16_t land_dir, uint8_t flags)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_RALLY_POINT_LEN];
+ _mav_put_int32_t(buf, 0, lat);
+ _mav_put_int32_t(buf, 4, lng);
+ _mav_put_int16_t(buf, 8, alt);
+ _mav_put_int16_t(buf, 10, break_alt);
+ _mav_put_uint16_t(buf, 12, land_dir);
+ _mav_put_uint8_t(buf, 14, target_system);
+ _mav_put_uint8_t(buf, 15, target_component);
+ _mav_put_uint8_t(buf, 16, idx);
+ _mav_put_uint8_t(buf, 17, count);
+ _mav_put_uint8_t(buf, 18, flags);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RALLY_POINT, buf, MAVLINK_MSG_ID_RALLY_POINT_MIN_LEN, MAVLINK_MSG_ID_RALLY_POINT_LEN, MAVLINK_MSG_ID_RALLY_POINT_CRC);
+#else
+ mavlink_rally_point_t packet;
+ packet.lat = lat;
+ packet.lng = lng;
+ packet.alt = alt;
+ packet.break_alt = break_alt;
+ packet.land_dir = land_dir;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.idx = idx;
+ packet.count = count;
+ packet.flags = flags;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RALLY_POINT, (const char *)&packet, MAVLINK_MSG_ID_RALLY_POINT_MIN_LEN, MAVLINK_MSG_ID_RALLY_POINT_LEN, MAVLINK_MSG_ID_RALLY_POINT_CRC);
+#endif
+}
+
+/**
+ * @brief Send a rally_point message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_rally_point_send_struct(mavlink_channel_t chan, const mavlink_rally_point_t* rally_point)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_rally_point_send(chan, rally_point->target_system, rally_point->target_component, rally_point->idx, rally_point->count, rally_point->lat, rally_point->lng, rally_point->alt, rally_point->break_alt, rally_point->land_dir, rally_point->flags);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RALLY_POINT, (const char *)rally_point, MAVLINK_MSG_ID_RALLY_POINT_MIN_LEN, MAVLINK_MSG_ID_RALLY_POINT_LEN, MAVLINK_MSG_ID_RALLY_POINT_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_RALLY_POINT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_rally_point_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t idx, uint8_t count, int32_t lat, int32_t lng, int16_t alt, int16_t break_alt, uint16_t land_dir, uint8_t flags)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_int32_t(buf, 0, lat);
+ _mav_put_int32_t(buf, 4, lng);
+ _mav_put_int16_t(buf, 8, alt);
+ _mav_put_int16_t(buf, 10, break_alt);
+ _mav_put_uint16_t(buf, 12, land_dir);
+ _mav_put_uint8_t(buf, 14, target_system);
+ _mav_put_uint8_t(buf, 15, target_component);
+ _mav_put_uint8_t(buf, 16, idx);
+ _mav_put_uint8_t(buf, 17, count);
+ _mav_put_uint8_t(buf, 18, flags);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RALLY_POINT, buf, MAVLINK_MSG_ID_RALLY_POINT_MIN_LEN, MAVLINK_MSG_ID_RALLY_POINT_LEN, MAVLINK_MSG_ID_RALLY_POINT_CRC);
+#else
+ mavlink_rally_point_t *packet = (mavlink_rally_point_t *)msgbuf;
+ packet->lat = lat;
+ packet->lng = lng;
+ packet->alt = alt;
+ packet->break_alt = break_alt;
+ packet->land_dir = land_dir;
+ packet->target_system = target_system;
+ packet->target_component = target_component;
+ packet->idx = idx;
+ packet->count = count;
+ packet->flags = flags;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RALLY_POINT, (const char *)packet, MAVLINK_MSG_ID_RALLY_POINT_MIN_LEN, MAVLINK_MSG_ID_RALLY_POINT_LEN, MAVLINK_MSG_ID_RALLY_POINT_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE RALLY_POINT UNPACKING
+
+
+/**
+ * @brief Get field target_system from rally_point message
+ *
+ * @return System ID.
+ */
+static inline uint8_t mavlink_msg_rally_point_get_target_system(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 14);
+}
+
+/**
+ * @brief Get field target_component from rally_point message
+ *
+ * @return Component ID.
+ */
+static inline uint8_t mavlink_msg_rally_point_get_target_component(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 15);
+}
+
+/**
+ * @brief Get field idx from rally_point message
+ *
+ * @return Point index (first point is 0).
+ */
+static inline uint8_t mavlink_msg_rally_point_get_idx(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 16);
+}
+
+/**
+ * @brief Get field count from rally_point message
+ *
+ * @return Total number of points (for sanity checking).
+ */
+static inline uint8_t mavlink_msg_rally_point_get_count(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 17);
+}
+
+/**
+ * @brief Get field lat from rally_point message
+ *
+ * @return [degE7] Latitude of point.
+ */
+static inline int32_t mavlink_msg_rally_point_get_lat(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_int32_t(msg, 0);
+}
+
+/**
+ * @brief Get field lng from rally_point message
+ *
+ * @return [degE7] Longitude of point.
+ */
+static inline int32_t mavlink_msg_rally_point_get_lng(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_int32_t(msg, 4);
+}
+
+/**
+ * @brief Get field alt from rally_point message
+ *
+ * @return [m] Transit / loiter altitude relative to home.
+ */
+static inline int16_t mavlink_msg_rally_point_get_alt(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_int16_t(msg, 8);
+}
+
+/**
+ * @brief Get field break_alt from rally_point message
+ *
+ * @return [m] Break altitude relative to home.
+ */
+static inline int16_t mavlink_msg_rally_point_get_break_alt(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_int16_t(msg, 10);
+}
+
+/**
+ * @brief Get field land_dir from rally_point message
+ *
+ * @return [cdeg] Heading to aim for when landing.
+ */
+static inline uint16_t mavlink_msg_rally_point_get_land_dir(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 12);
+}
+
+/**
+ * @brief Get field flags from rally_point message
+ *
+ * @return Configuration flags.
+ */
+static inline uint8_t mavlink_msg_rally_point_get_flags(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 18);
+}
+
+/**
+ * @brief Decode a rally_point message into a struct
+ *
+ * @param msg The message to decode
+ * @param rally_point C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_rally_point_decode(const mavlink_message_t* msg, mavlink_rally_point_t* rally_point)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ rally_point->lat = mavlink_msg_rally_point_get_lat(msg);
+ rally_point->lng = mavlink_msg_rally_point_get_lng(msg);
+ rally_point->alt = mavlink_msg_rally_point_get_alt(msg);
+ rally_point->break_alt = mavlink_msg_rally_point_get_break_alt(msg);
+ rally_point->land_dir = mavlink_msg_rally_point_get_land_dir(msg);
+ rally_point->target_system = mavlink_msg_rally_point_get_target_system(msg);
+ rally_point->target_component = mavlink_msg_rally_point_get_target_component(msg);
+ rally_point->idx = mavlink_msg_rally_point_get_idx(msg);
+ rally_point->count = mavlink_msg_rally_point_get_count(msg);
+ rally_point->flags = mavlink_msg_rally_point_get_flags(msg);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_RALLY_POINT_LEN? msg->len : MAVLINK_MSG_ID_RALLY_POINT_LEN;
+ memset(rally_point, 0, MAVLINK_MSG_ID_RALLY_POINT_LEN);
+ memcpy(rally_point, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/ardupilotmega/mavlink_msg_rangefinder.h b/lib/main/MAVLink/ardupilotmega/mavlink_msg_rangefinder.h
new file mode 100644
index 00000000000..518fd8f0914
--- /dev/null
+++ b/lib/main/MAVLink/ardupilotmega/mavlink_msg_rangefinder.h
@@ -0,0 +1,288 @@
+#pragma once
+// MESSAGE RANGEFINDER PACKING
+
+#define MAVLINK_MSG_ID_RANGEFINDER 173
+
+
+typedef struct __mavlink_rangefinder_t {
+ float distance; /*< [m] Distance.*/
+ float voltage; /*< [V] Raw voltage if available, zero otherwise.*/
+} mavlink_rangefinder_t;
+
+#define MAVLINK_MSG_ID_RANGEFINDER_LEN 8
+#define MAVLINK_MSG_ID_RANGEFINDER_MIN_LEN 8
+#define MAVLINK_MSG_ID_173_LEN 8
+#define MAVLINK_MSG_ID_173_MIN_LEN 8
+
+#define MAVLINK_MSG_ID_RANGEFINDER_CRC 83
+#define MAVLINK_MSG_ID_173_CRC 83
+
+
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_RANGEFINDER { \
+ 173, \
+ "RANGEFINDER", \
+ 2, \
+ { { "distance", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_rangefinder_t, distance) }, \
+ { "voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_rangefinder_t, voltage) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_RANGEFINDER { \
+ "RANGEFINDER", \
+ 2, \
+ { { "distance", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_rangefinder_t, distance) }, \
+ { "voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_rangefinder_t, voltage) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a rangefinder 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 distance [m] Distance.
+ * @param voltage [V] Raw voltage if available, zero otherwise.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_rangefinder_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ float distance, float voltage)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_RANGEFINDER_LEN];
+ _mav_put_float(buf, 0, distance);
+ _mav_put_float(buf, 4, voltage);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RANGEFINDER_LEN);
+#else
+ mavlink_rangefinder_t packet;
+ packet.distance = distance;
+ packet.voltage = voltage;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RANGEFINDER_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_RANGEFINDER;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RANGEFINDER_MIN_LEN, MAVLINK_MSG_ID_RANGEFINDER_LEN, MAVLINK_MSG_ID_RANGEFINDER_CRC);
+}
+
+/**
+ * @brief Pack a rangefinder 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 distance [m] Distance.
+ * @param voltage [V] Raw voltage if available, zero otherwise.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_rangefinder_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ float distance, float voltage)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_RANGEFINDER_LEN];
+ _mav_put_float(buf, 0, distance);
+ _mav_put_float(buf, 4, voltage);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RANGEFINDER_LEN);
+#else
+ mavlink_rangefinder_t packet;
+ packet.distance = distance;
+ packet.voltage = voltage;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RANGEFINDER_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_RANGEFINDER;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_RANGEFINDER_MIN_LEN, MAVLINK_MSG_ID_RANGEFINDER_LEN, MAVLINK_MSG_ID_RANGEFINDER_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_RANGEFINDER_MIN_LEN, MAVLINK_MSG_ID_RANGEFINDER_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a rangefinder 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 distance [m] Distance.
+ * @param voltage [V] Raw voltage if available, zero otherwise.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_rangefinder_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ float distance,float voltage)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_RANGEFINDER_LEN];
+ _mav_put_float(buf, 0, distance);
+ _mav_put_float(buf, 4, voltage);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RANGEFINDER_LEN);
+#else
+ mavlink_rangefinder_t packet;
+ packet.distance = distance;
+ packet.voltage = voltage;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RANGEFINDER_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_RANGEFINDER;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RANGEFINDER_MIN_LEN, MAVLINK_MSG_ID_RANGEFINDER_LEN, MAVLINK_MSG_ID_RANGEFINDER_CRC);
+}
+
+/**
+ * @brief Encode a rangefinder 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 rangefinder C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_rangefinder_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rangefinder_t* rangefinder)
+{
+ return mavlink_msg_rangefinder_pack(system_id, component_id, msg, rangefinder->distance, rangefinder->voltage);
+}
+
+/**
+ * @brief Encode a rangefinder 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 rangefinder C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_rangefinder_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_rangefinder_t* rangefinder)
+{
+ return mavlink_msg_rangefinder_pack_chan(system_id, component_id, chan, msg, rangefinder->distance, rangefinder->voltage);
+}
+
+/**
+ * @brief Encode a rangefinder 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 rangefinder C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_rangefinder_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_rangefinder_t* rangefinder)
+{
+ return mavlink_msg_rangefinder_pack_status(system_id, component_id, _status, msg, rangefinder->distance, rangefinder->voltage);
+}
+
+/**
+ * @brief Send a rangefinder message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param distance [m] Distance.
+ * @param voltage [V] Raw voltage if available, zero otherwise.
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_rangefinder_send(mavlink_channel_t chan, float distance, float voltage)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_RANGEFINDER_LEN];
+ _mav_put_float(buf, 0, distance);
+ _mav_put_float(buf, 4, voltage);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RANGEFINDER, buf, MAVLINK_MSG_ID_RANGEFINDER_MIN_LEN, MAVLINK_MSG_ID_RANGEFINDER_LEN, MAVLINK_MSG_ID_RANGEFINDER_CRC);
+#else
+ mavlink_rangefinder_t packet;
+ packet.distance = distance;
+ packet.voltage = voltage;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RANGEFINDER, (const char *)&packet, MAVLINK_MSG_ID_RANGEFINDER_MIN_LEN, MAVLINK_MSG_ID_RANGEFINDER_LEN, MAVLINK_MSG_ID_RANGEFINDER_CRC);
+#endif
+}
+
+/**
+ * @brief Send a rangefinder message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_rangefinder_send_struct(mavlink_channel_t chan, const mavlink_rangefinder_t* rangefinder)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_rangefinder_send(chan, rangefinder->distance, rangefinder->voltage);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RANGEFINDER, (const char *)rangefinder, MAVLINK_MSG_ID_RANGEFINDER_MIN_LEN, MAVLINK_MSG_ID_RANGEFINDER_LEN, MAVLINK_MSG_ID_RANGEFINDER_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_RANGEFINDER_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_rangefinder_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float distance, float voltage)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_float(buf, 0, distance);
+ _mav_put_float(buf, 4, voltage);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RANGEFINDER, buf, MAVLINK_MSG_ID_RANGEFINDER_MIN_LEN, MAVLINK_MSG_ID_RANGEFINDER_LEN, MAVLINK_MSG_ID_RANGEFINDER_CRC);
+#else
+ mavlink_rangefinder_t *packet = (mavlink_rangefinder_t *)msgbuf;
+ packet->distance = distance;
+ packet->voltage = voltage;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RANGEFINDER, (const char *)packet, MAVLINK_MSG_ID_RANGEFINDER_MIN_LEN, MAVLINK_MSG_ID_RANGEFINDER_LEN, MAVLINK_MSG_ID_RANGEFINDER_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE RANGEFINDER UNPACKING
+
+
+/**
+ * @brief Get field distance from rangefinder message
+ *
+ * @return [m] Distance.
+ */
+static inline float mavlink_msg_rangefinder_get_distance(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 0);
+}
+
+/**
+ * @brief Get field voltage from rangefinder message
+ *
+ * @return [V] Raw voltage if available, zero otherwise.
+ */
+static inline float mavlink_msg_rangefinder_get_voltage(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 4);
+}
+
+/**
+ * @brief Decode a rangefinder message into a struct
+ *
+ * @param msg The message to decode
+ * @param rangefinder C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_rangefinder_decode(const mavlink_message_t* msg, mavlink_rangefinder_t* rangefinder)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ rangefinder->distance = mavlink_msg_rangefinder_get_distance(msg);
+ rangefinder->voltage = mavlink_msg_rangefinder_get_voltage(msg);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_RANGEFINDER_LEN? msg->len : MAVLINK_MSG_ID_RANGEFINDER_LEN;
+ memset(rangefinder, 0, MAVLINK_MSG_ID_RANGEFINDER_LEN);
+ memcpy(rangefinder, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/ardupilotmega/mavlink_msg_remote_log_block_status.h b/lib/main/MAVLink/ardupilotmega/mavlink_msg_remote_log_block_status.h
new file mode 100644
index 00000000000..81b2437235d
--- /dev/null
+++ b/lib/main/MAVLink/ardupilotmega/mavlink_msg_remote_log_block_status.h
@@ -0,0 +1,344 @@
+#pragma once
+// MESSAGE REMOTE_LOG_BLOCK_STATUS PACKING
+
+#define MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS 185
+
+
+typedef struct __mavlink_remote_log_block_status_t {
+ uint32_t seqno; /*< Log data block sequence number.*/
+ uint8_t target_system; /*< System ID.*/
+ uint8_t target_component; /*< Component ID.*/
+ uint8_t status; /*< Log data block status.*/
+} mavlink_remote_log_block_status_t;
+
+#define MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS_LEN 7
+#define MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS_MIN_LEN 7
+#define MAVLINK_MSG_ID_185_LEN 7
+#define MAVLINK_MSG_ID_185_MIN_LEN 7
+
+#define MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS_CRC 186
+#define MAVLINK_MSG_ID_185_CRC 186
+
+
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_REMOTE_LOG_BLOCK_STATUS { \
+ 185, \
+ "REMOTE_LOG_BLOCK_STATUS", \
+ 4, \
+ { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_remote_log_block_status_t, target_system) }, \
+ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_remote_log_block_status_t, target_component) }, \
+ { "seqno", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_remote_log_block_status_t, seqno) }, \
+ { "status", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_remote_log_block_status_t, status) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_REMOTE_LOG_BLOCK_STATUS { \
+ "REMOTE_LOG_BLOCK_STATUS", \
+ 4, \
+ { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_remote_log_block_status_t, target_system) }, \
+ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_remote_log_block_status_t, target_component) }, \
+ { "seqno", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_remote_log_block_status_t, seqno) }, \
+ { "status", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_remote_log_block_status_t, status) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a remote_log_block_status 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 target_system System ID.
+ * @param target_component Component ID.
+ * @param seqno Log data block sequence number.
+ * @param status Log data block status.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_remote_log_block_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint8_t target_system, uint8_t target_component, uint32_t seqno, uint8_t status)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS_LEN];
+ _mav_put_uint32_t(buf, 0, seqno);
+ _mav_put_uint8_t(buf, 4, target_system);
+ _mav_put_uint8_t(buf, 5, target_component);
+ _mav_put_uint8_t(buf, 6, status);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS_LEN);
+#else
+ mavlink_remote_log_block_status_t packet;
+ packet.seqno = seqno;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.status = status;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS_MIN_LEN, MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS_LEN, MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS_CRC);
+}
+
+/**
+ * @brief Pack a remote_log_block_status 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 target_system System ID.
+ * @param target_component Component ID.
+ * @param seqno Log data block sequence number.
+ * @param status Log data block status.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_remote_log_block_status_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ uint8_t target_system, uint8_t target_component, uint32_t seqno, uint8_t status)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS_LEN];
+ _mav_put_uint32_t(buf, 0, seqno);
+ _mav_put_uint8_t(buf, 4, target_system);
+ _mav_put_uint8_t(buf, 5, target_component);
+ _mav_put_uint8_t(buf, 6, status);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS_LEN);
+#else
+ mavlink_remote_log_block_status_t packet;
+ packet.seqno = seqno;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.status = status;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS_MIN_LEN, MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS_LEN, MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS_MIN_LEN, MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a remote_log_block_status 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 target_system System ID.
+ * @param target_component Component ID.
+ * @param seqno Log data block sequence number.
+ * @param status Log data block status.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_remote_log_block_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint8_t target_system,uint8_t target_component,uint32_t seqno,uint8_t status)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS_LEN];
+ _mav_put_uint32_t(buf, 0, seqno);
+ _mav_put_uint8_t(buf, 4, target_system);
+ _mav_put_uint8_t(buf, 5, target_component);
+ _mav_put_uint8_t(buf, 6, status);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS_LEN);
+#else
+ mavlink_remote_log_block_status_t packet;
+ packet.seqno = seqno;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.status = status;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS_MIN_LEN, MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS_LEN, MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS_CRC);
+}
+
+/**
+ * @brief Encode a remote_log_block_status 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 remote_log_block_status C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_remote_log_block_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_remote_log_block_status_t* remote_log_block_status)
+{
+ return mavlink_msg_remote_log_block_status_pack(system_id, component_id, msg, remote_log_block_status->target_system, remote_log_block_status->target_component, remote_log_block_status->seqno, remote_log_block_status->status);
+}
+
+/**
+ * @brief Encode a remote_log_block_status 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 remote_log_block_status C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_remote_log_block_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_remote_log_block_status_t* remote_log_block_status)
+{
+ return mavlink_msg_remote_log_block_status_pack_chan(system_id, component_id, chan, msg, remote_log_block_status->target_system, remote_log_block_status->target_component, remote_log_block_status->seqno, remote_log_block_status->status);
+}
+
+/**
+ * @brief Encode a remote_log_block_status 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 remote_log_block_status C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_remote_log_block_status_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_remote_log_block_status_t* remote_log_block_status)
+{
+ return mavlink_msg_remote_log_block_status_pack_status(system_id, component_id, _status, msg, remote_log_block_status->target_system, remote_log_block_status->target_component, remote_log_block_status->seqno, remote_log_block_status->status);
+}
+
+/**
+ * @brief Send a remote_log_block_status message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param target_system System ID.
+ * @param target_component Component ID.
+ * @param seqno Log data block sequence number.
+ * @param status Log data block status.
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_remote_log_block_status_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint32_t seqno, uint8_t status)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS_LEN];
+ _mav_put_uint32_t(buf, 0, seqno);
+ _mav_put_uint8_t(buf, 4, target_system);
+ _mav_put_uint8_t(buf, 5, target_component);
+ _mav_put_uint8_t(buf, 6, status);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS, buf, MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS_MIN_LEN, MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS_LEN, MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS_CRC);
+#else
+ mavlink_remote_log_block_status_t packet;
+ packet.seqno = seqno;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.status = status;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS, (const char *)&packet, MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS_MIN_LEN, MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS_LEN, MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS_CRC);
+#endif
+}
+
+/**
+ * @brief Send a remote_log_block_status message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_remote_log_block_status_send_struct(mavlink_channel_t chan, const mavlink_remote_log_block_status_t* remote_log_block_status)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_remote_log_block_status_send(chan, remote_log_block_status->target_system, remote_log_block_status->target_component, remote_log_block_status->seqno, remote_log_block_status->status);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS, (const char *)remote_log_block_status, MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS_MIN_LEN, MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS_LEN, MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_remote_log_block_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint32_t seqno, uint8_t status)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint32_t(buf, 0, seqno);
+ _mav_put_uint8_t(buf, 4, target_system);
+ _mav_put_uint8_t(buf, 5, target_component);
+ _mav_put_uint8_t(buf, 6, status);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS, buf, MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS_MIN_LEN, MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS_LEN, MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS_CRC);
+#else
+ mavlink_remote_log_block_status_t *packet = (mavlink_remote_log_block_status_t *)msgbuf;
+ packet->seqno = seqno;
+ packet->target_system = target_system;
+ packet->target_component = target_component;
+ packet->status = status;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS, (const char *)packet, MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS_MIN_LEN, MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS_LEN, MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE REMOTE_LOG_BLOCK_STATUS UNPACKING
+
+
+/**
+ * @brief Get field target_system from remote_log_block_status message
+ *
+ * @return System ID.
+ */
+static inline uint8_t mavlink_msg_remote_log_block_status_get_target_system(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 4);
+}
+
+/**
+ * @brief Get field target_component from remote_log_block_status message
+ *
+ * @return Component ID.
+ */
+static inline uint8_t mavlink_msg_remote_log_block_status_get_target_component(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 5);
+}
+
+/**
+ * @brief Get field seqno from remote_log_block_status message
+ *
+ * @return Log data block sequence number.
+ */
+static inline uint32_t mavlink_msg_remote_log_block_status_get_seqno(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint32_t(msg, 0);
+}
+
+/**
+ * @brief Get field status from remote_log_block_status message
+ *
+ * @return Log data block status.
+ */
+static inline uint8_t mavlink_msg_remote_log_block_status_get_status(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 6);
+}
+
+/**
+ * @brief Decode a remote_log_block_status message into a struct
+ *
+ * @param msg The message to decode
+ * @param remote_log_block_status C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_remote_log_block_status_decode(const mavlink_message_t* msg, mavlink_remote_log_block_status_t* remote_log_block_status)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ remote_log_block_status->seqno = mavlink_msg_remote_log_block_status_get_seqno(msg);
+ remote_log_block_status->target_system = mavlink_msg_remote_log_block_status_get_target_system(msg);
+ remote_log_block_status->target_component = mavlink_msg_remote_log_block_status_get_target_component(msg);
+ remote_log_block_status->status = mavlink_msg_remote_log_block_status_get_status(msg);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS_LEN? msg->len : MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS_LEN;
+ memset(remote_log_block_status, 0, MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS_LEN);
+ memcpy(remote_log_block_status, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/ardupilotmega/mavlink_msg_remote_log_data_block.h b/lib/main/MAVLink/ardupilotmega/mavlink_msg_remote_log_data_block.h
new file mode 100644
index 00000000000..747e79aae1b
--- /dev/null
+++ b/lib/main/MAVLink/ardupilotmega/mavlink_msg_remote_log_data_block.h
@@ -0,0 +1,334 @@
+#pragma once
+// MESSAGE REMOTE_LOG_DATA_BLOCK PACKING
+
+#define MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK 184
+
+
+typedef struct __mavlink_remote_log_data_block_t {
+ uint32_t seqno; /*< Log data block sequence number.*/
+ uint8_t target_system; /*< System ID.*/
+ uint8_t target_component; /*< Component ID.*/
+ uint8_t data[200]; /*< Log data block.*/
+} mavlink_remote_log_data_block_t;
+
+#define MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK_LEN 206
+#define MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK_MIN_LEN 206
+#define MAVLINK_MSG_ID_184_LEN 206
+#define MAVLINK_MSG_ID_184_MIN_LEN 206
+
+#define MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK_CRC 159
+#define MAVLINK_MSG_ID_184_CRC 159
+
+#define MAVLINK_MSG_REMOTE_LOG_DATA_BLOCK_FIELD_DATA_LEN 200
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_REMOTE_LOG_DATA_BLOCK { \
+ 184, \
+ "REMOTE_LOG_DATA_BLOCK", \
+ 4, \
+ { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_remote_log_data_block_t, target_system) }, \
+ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_remote_log_data_block_t, target_component) }, \
+ { "seqno", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_remote_log_data_block_t, seqno) }, \
+ { "data", NULL, MAVLINK_TYPE_UINT8_T, 200, 6, offsetof(mavlink_remote_log_data_block_t, data) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_REMOTE_LOG_DATA_BLOCK { \
+ "REMOTE_LOG_DATA_BLOCK", \
+ 4, \
+ { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_remote_log_data_block_t, target_system) }, \
+ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_remote_log_data_block_t, target_component) }, \
+ { "seqno", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_remote_log_data_block_t, seqno) }, \
+ { "data", NULL, MAVLINK_TYPE_UINT8_T, 200, 6, offsetof(mavlink_remote_log_data_block_t, data) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a remote_log_data_block 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 target_system System ID.
+ * @param target_component Component ID.
+ * @param seqno Log data block sequence number.
+ * @param data Log data block.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_remote_log_data_block_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint8_t target_system, uint8_t target_component, uint32_t seqno, const uint8_t *data)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK_LEN];
+ _mav_put_uint32_t(buf, 0, seqno);
+ _mav_put_uint8_t(buf, 4, target_system);
+ _mav_put_uint8_t(buf, 5, target_component);
+ _mav_put_uint8_t_array(buf, 6, data, 200);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK_LEN);
+#else
+ mavlink_remote_log_data_block_t packet;
+ packet.seqno = seqno;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ mav_array_assign_uint8_t(packet.data, data, 200);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK_MIN_LEN, MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK_LEN, MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK_CRC);
+}
+
+/**
+ * @brief Pack a remote_log_data_block 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 target_system System ID.
+ * @param target_component Component ID.
+ * @param seqno Log data block sequence number.
+ * @param data Log data block.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_remote_log_data_block_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ uint8_t target_system, uint8_t target_component, uint32_t seqno, const uint8_t *data)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK_LEN];
+ _mav_put_uint32_t(buf, 0, seqno);
+ _mav_put_uint8_t(buf, 4, target_system);
+ _mav_put_uint8_t(buf, 5, target_component);
+ _mav_put_uint8_t_array(buf, 6, data, 200);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK_LEN);
+#else
+ mavlink_remote_log_data_block_t packet;
+ packet.seqno = seqno;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ mav_array_memcpy(packet.data, data, sizeof(uint8_t)*200);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK_MIN_LEN, MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK_LEN, MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK_MIN_LEN, MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a remote_log_data_block 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 target_system System ID.
+ * @param target_component Component ID.
+ * @param seqno Log data block sequence number.
+ * @param data Log data block.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_remote_log_data_block_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint8_t target_system,uint8_t target_component,uint32_t seqno,const uint8_t *data)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK_LEN];
+ _mav_put_uint32_t(buf, 0, seqno);
+ _mav_put_uint8_t(buf, 4, target_system);
+ _mav_put_uint8_t(buf, 5, target_component);
+ _mav_put_uint8_t_array(buf, 6, data, 200);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK_LEN);
+#else
+ mavlink_remote_log_data_block_t packet;
+ packet.seqno = seqno;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ mav_array_assign_uint8_t(packet.data, data, 200);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK_MIN_LEN, MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK_LEN, MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK_CRC);
+}
+
+/**
+ * @brief Encode a remote_log_data_block 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 remote_log_data_block C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_remote_log_data_block_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_remote_log_data_block_t* remote_log_data_block)
+{
+ return mavlink_msg_remote_log_data_block_pack(system_id, component_id, msg, remote_log_data_block->target_system, remote_log_data_block->target_component, remote_log_data_block->seqno, remote_log_data_block->data);
+}
+
+/**
+ * @brief Encode a remote_log_data_block 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 remote_log_data_block C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_remote_log_data_block_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_remote_log_data_block_t* remote_log_data_block)
+{
+ return mavlink_msg_remote_log_data_block_pack_chan(system_id, component_id, chan, msg, remote_log_data_block->target_system, remote_log_data_block->target_component, remote_log_data_block->seqno, remote_log_data_block->data);
+}
+
+/**
+ * @brief Encode a remote_log_data_block 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 remote_log_data_block C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_remote_log_data_block_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_remote_log_data_block_t* remote_log_data_block)
+{
+ return mavlink_msg_remote_log_data_block_pack_status(system_id, component_id, _status, msg, remote_log_data_block->target_system, remote_log_data_block->target_component, remote_log_data_block->seqno, remote_log_data_block->data);
+}
+
+/**
+ * @brief Send a remote_log_data_block message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param target_system System ID.
+ * @param target_component Component ID.
+ * @param seqno Log data block sequence number.
+ * @param data Log data block.
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_remote_log_data_block_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint32_t seqno, const uint8_t *data)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK_LEN];
+ _mav_put_uint32_t(buf, 0, seqno);
+ _mav_put_uint8_t(buf, 4, target_system);
+ _mav_put_uint8_t(buf, 5, target_component);
+ _mav_put_uint8_t_array(buf, 6, data, 200);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK, buf, MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK_MIN_LEN, MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK_LEN, MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK_CRC);
+#else
+ mavlink_remote_log_data_block_t packet;
+ packet.seqno = seqno;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ mav_array_assign_uint8_t(packet.data, data, 200);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK, (const char *)&packet, MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK_MIN_LEN, MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK_LEN, MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK_CRC);
+#endif
+}
+
+/**
+ * @brief Send a remote_log_data_block message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_remote_log_data_block_send_struct(mavlink_channel_t chan, const mavlink_remote_log_data_block_t* remote_log_data_block)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_remote_log_data_block_send(chan, remote_log_data_block->target_system, remote_log_data_block->target_component, remote_log_data_block->seqno, remote_log_data_block->data);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK, (const char *)remote_log_data_block, MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK_MIN_LEN, MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK_LEN, MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_remote_log_data_block_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint32_t seqno, const uint8_t *data)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint32_t(buf, 0, seqno);
+ _mav_put_uint8_t(buf, 4, target_system);
+ _mav_put_uint8_t(buf, 5, target_component);
+ _mav_put_uint8_t_array(buf, 6, data, 200);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK, buf, MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK_MIN_LEN, MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK_LEN, MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK_CRC);
+#else
+ mavlink_remote_log_data_block_t *packet = (mavlink_remote_log_data_block_t *)msgbuf;
+ packet->seqno = seqno;
+ packet->target_system = target_system;
+ packet->target_component = target_component;
+ mav_array_assign_uint8_t(packet->data, data, 200);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK, (const char *)packet, MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK_MIN_LEN, MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK_LEN, MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE REMOTE_LOG_DATA_BLOCK UNPACKING
+
+
+/**
+ * @brief Get field target_system from remote_log_data_block message
+ *
+ * @return System ID.
+ */
+static inline uint8_t mavlink_msg_remote_log_data_block_get_target_system(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 4);
+}
+
+/**
+ * @brief Get field target_component from remote_log_data_block message
+ *
+ * @return Component ID.
+ */
+static inline uint8_t mavlink_msg_remote_log_data_block_get_target_component(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 5);
+}
+
+/**
+ * @brief Get field seqno from remote_log_data_block message
+ *
+ * @return Log data block sequence number.
+ */
+static inline uint32_t mavlink_msg_remote_log_data_block_get_seqno(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint32_t(msg, 0);
+}
+
+/**
+ * @brief Get field data from remote_log_data_block message
+ *
+ * @return Log data block.
+ */
+static inline uint16_t mavlink_msg_remote_log_data_block_get_data(const mavlink_message_t* msg, uint8_t *data)
+{
+ return _MAV_RETURN_uint8_t_array(msg, data, 200, 6);
+}
+
+/**
+ * @brief Decode a remote_log_data_block message into a struct
+ *
+ * @param msg The message to decode
+ * @param remote_log_data_block C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_remote_log_data_block_decode(const mavlink_message_t* msg, mavlink_remote_log_data_block_t* remote_log_data_block)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ remote_log_data_block->seqno = mavlink_msg_remote_log_data_block_get_seqno(msg);
+ remote_log_data_block->target_system = mavlink_msg_remote_log_data_block_get_target_system(msg);
+ remote_log_data_block->target_component = mavlink_msg_remote_log_data_block_get_target_component(msg);
+ mavlink_msg_remote_log_data_block_get_data(msg, remote_log_data_block->data);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK_LEN? msg->len : MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK_LEN;
+ memset(remote_log_data_block, 0, MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK_LEN);
+ memcpy(remote_log_data_block, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/ardupilotmega/mavlink_msg_rpm.h b/lib/main/MAVLink/ardupilotmega/mavlink_msg_rpm.h
new file mode 100644
index 00000000000..c5bb31313b5
--- /dev/null
+++ b/lib/main/MAVLink/ardupilotmega/mavlink_msg_rpm.h
@@ -0,0 +1,288 @@
+#pragma once
+// MESSAGE RPM PACKING
+
+#define MAVLINK_MSG_ID_RPM 226
+
+
+typedef struct __mavlink_rpm_t {
+ float rpm1; /*< RPM Sensor1.*/
+ float rpm2; /*< RPM Sensor2.*/
+} mavlink_rpm_t;
+
+#define MAVLINK_MSG_ID_RPM_LEN 8
+#define MAVLINK_MSG_ID_RPM_MIN_LEN 8
+#define MAVLINK_MSG_ID_226_LEN 8
+#define MAVLINK_MSG_ID_226_MIN_LEN 8
+
+#define MAVLINK_MSG_ID_RPM_CRC 207
+#define MAVLINK_MSG_ID_226_CRC 207
+
+
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_RPM { \
+ 226, \
+ "RPM", \
+ 2, \
+ { { "rpm1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_rpm_t, rpm1) }, \
+ { "rpm2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_rpm_t, rpm2) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_RPM { \
+ "RPM", \
+ 2, \
+ { { "rpm1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_rpm_t, rpm1) }, \
+ { "rpm2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_rpm_t, rpm2) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a rpm 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 rpm1 RPM Sensor1.
+ * @param rpm2 RPM Sensor2.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_rpm_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ float rpm1, float rpm2)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_RPM_LEN];
+ _mav_put_float(buf, 0, rpm1);
+ _mav_put_float(buf, 4, rpm2);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RPM_LEN);
+#else
+ mavlink_rpm_t packet;
+ packet.rpm1 = rpm1;
+ packet.rpm2 = rpm2;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RPM_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_RPM;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RPM_MIN_LEN, MAVLINK_MSG_ID_RPM_LEN, MAVLINK_MSG_ID_RPM_CRC);
+}
+
+/**
+ * @brief Pack a rpm 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 rpm1 RPM Sensor1.
+ * @param rpm2 RPM Sensor2.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_rpm_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ float rpm1, float rpm2)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_RPM_LEN];
+ _mav_put_float(buf, 0, rpm1);
+ _mav_put_float(buf, 4, rpm2);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RPM_LEN);
+#else
+ mavlink_rpm_t packet;
+ packet.rpm1 = rpm1;
+ packet.rpm2 = rpm2;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RPM_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_RPM;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_RPM_MIN_LEN, MAVLINK_MSG_ID_RPM_LEN, MAVLINK_MSG_ID_RPM_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_RPM_MIN_LEN, MAVLINK_MSG_ID_RPM_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a rpm 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 rpm1 RPM Sensor1.
+ * @param rpm2 RPM Sensor2.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_rpm_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ float rpm1,float rpm2)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_RPM_LEN];
+ _mav_put_float(buf, 0, rpm1);
+ _mav_put_float(buf, 4, rpm2);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RPM_LEN);
+#else
+ mavlink_rpm_t packet;
+ packet.rpm1 = rpm1;
+ packet.rpm2 = rpm2;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RPM_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_RPM;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RPM_MIN_LEN, MAVLINK_MSG_ID_RPM_LEN, MAVLINK_MSG_ID_RPM_CRC);
+}
+
+/**
+ * @brief Encode a rpm 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 rpm C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_rpm_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rpm_t* rpm)
+{
+ return mavlink_msg_rpm_pack(system_id, component_id, msg, rpm->rpm1, rpm->rpm2);
+}
+
+/**
+ * @brief Encode a rpm 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 rpm C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_rpm_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_rpm_t* rpm)
+{
+ return mavlink_msg_rpm_pack_chan(system_id, component_id, chan, msg, rpm->rpm1, rpm->rpm2);
+}
+
+/**
+ * @brief Encode a rpm 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 rpm C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_rpm_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_rpm_t* rpm)
+{
+ return mavlink_msg_rpm_pack_status(system_id, component_id, _status, msg, rpm->rpm1, rpm->rpm2);
+}
+
+/**
+ * @brief Send a rpm message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param rpm1 RPM Sensor1.
+ * @param rpm2 RPM Sensor2.
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_rpm_send(mavlink_channel_t chan, float rpm1, float rpm2)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_RPM_LEN];
+ _mav_put_float(buf, 0, rpm1);
+ _mav_put_float(buf, 4, rpm2);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RPM, buf, MAVLINK_MSG_ID_RPM_MIN_LEN, MAVLINK_MSG_ID_RPM_LEN, MAVLINK_MSG_ID_RPM_CRC);
+#else
+ mavlink_rpm_t packet;
+ packet.rpm1 = rpm1;
+ packet.rpm2 = rpm2;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RPM, (const char *)&packet, MAVLINK_MSG_ID_RPM_MIN_LEN, MAVLINK_MSG_ID_RPM_LEN, MAVLINK_MSG_ID_RPM_CRC);
+#endif
+}
+
+/**
+ * @brief Send a rpm message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_rpm_send_struct(mavlink_channel_t chan, const mavlink_rpm_t* rpm)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_rpm_send(chan, rpm->rpm1, rpm->rpm2);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RPM, (const char *)rpm, MAVLINK_MSG_ID_RPM_MIN_LEN, MAVLINK_MSG_ID_RPM_LEN, MAVLINK_MSG_ID_RPM_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_RPM_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_rpm_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float rpm1, float rpm2)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_float(buf, 0, rpm1);
+ _mav_put_float(buf, 4, rpm2);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RPM, buf, MAVLINK_MSG_ID_RPM_MIN_LEN, MAVLINK_MSG_ID_RPM_LEN, MAVLINK_MSG_ID_RPM_CRC);
+#else
+ mavlink_rpm_t *packet = (mavlink_rpm_t *)msgbuf;
+ packet->rpm1 = rpm1;
+ packet->rpm2 = rpm2;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RPM, (const char *)packet, MAVLINK_MSG_ID_RPM_MIN_LEN, MAVLINK_MSG_ID_RPM_LEN, MAVLINK_MSG_ID_RPM_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE RPM UNPACKING
+
+
+/**
+ * @brief Get field rpm1 from rpm message
+ *
+ * @return RPM Sensor1.
+ */
+static inline float mavlink_msg_rpm_get_rpm1(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 0);
+}
+
+/**
+ * @brief Get field rpm2 from rpm message
+ *
+ * @return RPM Sensor2.
+ */
+static inline float mavlink_msg_rpm_get_rpm2(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 4);
+}
+
+/**
+ * @brief Decode a rpm message into a struct
+ *
+ * @param msg The message to decode
+ * @param rpm C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_rpm_decode(const mavlink_message_t* msg, mavlink_rpm_t* rpm)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ rpm->rpm1 = mavlink_msg_rpm_get_rpm1(msg);
+ rpm->rpm2 = mavlink_msg_rpm_get_rpm2(msg);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_RPM_LEN? msg->len : MAVLINK_MSG_ID_RPM_LEN;
+ memset(rpm, 0, MAVLINK_MSG_ID_RPM_LEN);
+ memcpy(rpm, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/ardupilotmega/mavlink_msg_secure_command.h b/lib/main/MAVLink/ardupilotmega/mavlink_msg_secure_command.h
new file mode 100644
index 00000000000..cc2a6c02ad5
--- /dev/null
+++ b/lib/main/MAVLink/ardupilotmega/mavlink_msg_secure_command.h
@@ -0,0 +1,418 @@
+#pragma once
+// MESSAGE SECURE_COMMAND PACKING
+
+#define MAVLINK_MSG_ID_SECURE_COMMAND 11004
+
+
+typedef struct __mavlink_secure_command_t {
+ uint32_t sequence; /*< Sequence ID for tagging reply.*/
+ uint32_t operation; /*< Operation being requested.*/
+ uint8_t target_system; /*< System ID.*/
+ uint8_t target_component; /*< Component ID.*/
+ uint8_t data_length; /*< Data length.*/
+ uint8_t sig_length; /*< Signature length.*/
+ uint8_t data[220]; /*< Signed data.*/
+} mavlink_secure_command_t;
+
+#define MAVLINK_MSG_ID_SECURE_COMMAND_LEN 232
+#define MAVLINK_MSG_ID_SECURE_COMMAND_MIN_LEN 232
+#define MAVLINK_MSG_ID_11004_LEN 232
+#define MAVLINK_MSG_ID_11004_MIN_LEN 232
+
+#define MAVLINK_MSG_ID_SECURE_COMMAND_CRC 11
+#define MAVLINK_MSG_ID_11004_CRC 11
+
+#define MAVLINK_MSG_SECURE_COMMAND_FIELD_DATA_LEN 220
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_SECURE_COMMAND { \
+ 11004, \
+ "SECURE_COMMAND", \
+ 7, \
+ { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_secure_command_t, target_system) }, \
+ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_secure_command_t, target_component) }, \
+ { "sequence", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_secure_command_t, sequence) }, \
+ { "operation", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_secure_command_t, operation) }, \
+ { "data_length", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_secure_command_t, data_length) }, \
+ { "sig_length", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_secure_command_t, sig_length) }, \
+ { "data", NULL, MAVLINK_TYPE_UINT8_T, 220, 12, offsetof(mavlink_secure_command_t, data) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_SECURE_COMMAND { \
+ "SECURE_COMMAND", \
+ 7, \
+ { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_secure_command_t, target_system) }, \
+ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_secure_command_t, target_component) }, \
+ { "sequence", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_secure_command_t, sequence) }, \
+ { "operation", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_secure_command_t, operation) }, \
+ { "data_length", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_secure_command_t, data_length) }, \
+ { "sig_length", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_secure_command_t, sig_length) }, \
+ { "data", NULL, MAVLINK_TYPE_UINT8_T, 220, 12, offsetof(mavlink_secure_command_t, data) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a secure_command 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 target_system System ID.
+ * @param target_component Component ID.
+ * @param sequence Sequence ID for tagging reply.
+ * @param operation Operation being requested.
+ * @param data_length Data length.
+ * @param sig_length Signature length.
+ * @param data Signed data.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_secure_command_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint8_t target_system, uint8_t target_component, uint32_t sequence, uint32_t operation, uint8_t data_length, uint8_t sig_length, const uint8_t *data)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_SECURE_COMMAND_LEN];
+ _mav_put_uint32_t(buf, 0, sequence);
+ _mav_put_uint32_t(buf, 4, operation);
+ _mav_put_uint8_t(buf, 8, target_system);
+ _mav_put_uint8_t(buf, 9, target_component);
+ _mav_put_uint8_t(buf, 10, data_length);
+ _mav_put_uint8_t(buf, 11, sig_length);
+ _mav_put_uint8_t_array(buf, 12, data, 220);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SECURE_COMMAND_LEN);
+#else
+ mavlink_secure_command_t packet;
+ packet.sequence = sequence;
+ packet.operation = operation;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.data_length = data_length;
+ packet.sig_length = sig_length;
+ mav_array_assign_uint8_t(packet.data, data, 220);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SECURE_COMMAND_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_SECURE_COMMAND;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SECURE_COMMAND_MIN_LEN, MAVLINK_MSG_ID_SECURE_COMMAND_LEN, MAVLINK_MSG_ID_SECURE_COMMAND_CRC);
+}
+
+/**
+ * @brief Pack a secure_command 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 target_system System ID.
+ * @param target_component Component ID.
+ * @param sequence Sequence ID for tagging reply.
+ * @param operation Operation being requested.
+ * @param data_length Data length.
+ * @param sig_length Signature length.
+ * @param data Signed data.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_secure_command_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ uint8_t target_system, uint8_t target_component, uint32_t sequence, uint32_t operation, uint8_t data_length, uint8_t sig_length, const uint8_t *data)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_SECURE_COMMAND_LEN];
+ _mav_put_uint32_t(buf, 0, sequence);
+ _mav_put_uint32_t(buf, 4, operation);
+ _mav_put_uint8_t(buf, 8, target_system);
+ _mav_put_uint8_t(buf, 9, target_component);
+ _mav_put_uint8_t(buf, 10, data_length);
+ _mav_put_uint8_t(buf, 11, sig_length);
+ _mav_put_uint8_t_array(buf, 12, data, 220);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SECURE_COMMAND_LEN);
+#else
+ mavlink_secure_command_t packet;
+ packet.sequence = sequence;
+ packet.operation = operation;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.data_length = data_length;
+ packet.sig_length = sig_length;
+ mav_array_memcpy(packet.data, data, sizeof(uint8_t)*220);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SECURE_COMMAND_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_SECURE_COMMAND;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_SECURE_COMMAND_MIN_LEN, MAVLINK_MSG_ID_SECURE_COMMAND_LEN, MAVLINK_MSG_ID_SECURE_COMMAND_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_SECURE_COMMAND_MIN_LEN, MAVLINK_MSG_ID_SECURE_COMMAND_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a secure_command 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 target_system System ID.
+ * @param target_component Component ID.
+ * @param sequence Sequence ID for tagging reply.
+ * @param operation Operation being requested.
+ * @param data_length Data length.
+ * @param sig_length Signature length.
+ * @param data Signed data.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_secure_command_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint8_t target_system,uint8_t target_component,uint32_t sequence,uint32_t operation,uint8_t data_length,uint8_t sig_length,const uint8_t *data)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_SECURE_COMMAND_LEN];
+ _mav_put_uint32_t(buf, 0, sequence);
+ _mav_put_uint32_t(buf, 4, operation);
+ _mav_put_uint8_t(buf, 8, target_system);
+ _mav_put_uint8_t(buf, 9, target_component);
+ _mav_put_uint8_t(buf, 10, data_length);
+ _mav_put_uint8_t(buf, 11, sig_length);
+ _mav_put_uint8_t_array(buf, 12, data, 220);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SECURE_COMMAND_LEN);
+#else
+ mavlink_secure_command_t packet;
+ packet.sequence = sequence;
+ packet.operation = operation;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.data_length = data_length;
+ packet.sig_length = sig_length;
+ mav_array_assign_uint8_t(packet.data, data, 220);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SECURE_COMMAND_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_SECURE_COMMAND;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SECURE_COMMAND_MIN_LEN, MAVLINK_MSG_ID_SECURE_COMMAND_LEN, MAVLINK_MSG_ID_SECURE_COMMAND_CRC);
+}
+
+/**
+ * @brief Encode a secure_command 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 secure_command C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_secure_command_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_secure_command_t* secure_command)
+{
+ return mavlink_msg_secure_command_pack(system_id, component_id, msg, secure_command->target_system, secure_command->target_component, secure_command->sequence, secure_command->operation, secure_command->data_length, secure_command->sig_length, secure_command->data);
+}
+
+/**
+ * @brief Encode a secure_command 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 secure_command C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_secure_command_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_secure_command_t* secure_command)
+{
+ return mavlink_msg_secure_command_pack_chan(system_id, component_id, chan, msg, secure_command->target_system, secure_command->target_component, secure_command->sequence, secure_command->operation, secure_command->data_length, secure_command->sig_length, secure_command->data);
+}
+
+/**
+ * @brief Encode a secure_command 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 secure_command C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_secure_command_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_secure_command_t* secure_command)
+{
+ return mavlink_msg_secure_command_pack_status(system_id, component_id, _status, msg, secure_command->target_system, secure_command->target_component, secure_command->sequence, secure_command->operation, secure_command->data_length, secure_command->sig_length, secure_command->data);
+}
+
+/**
+ * @brief Send a secure_command message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param target_system System ID.
+ * @param target_component Component ID.
+ * @param sequence Sequence ID for tagging reply.
+ * @param operation Operation being requested.
+ * @param data_length Data length.
+ * @param sig_length Signature length.
+ * @param data Signed data.
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_secure_command_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint32_t sequence, uint32_t operation, uint8_t data_length, uint8_t sig_length, const uint8_t *data)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_SECURE_COMMAND_LEN];
+ _mav_put_uint32_t(buf, 0, sequence);
+ _mav_put_uint32_t(buf, 4, operation);
+ _mav_put_uint8_t(buf, 8, target_system);
+ _mav_put_uint8_t(buf, 9, target_component);
+ _mav_put_uint8_t(buf, 10, data_length);
+ _mav_put_uint8_t(buf, 11, sig_length);
+ _mav_put_uint8_t_array(buf, 12, data, 220);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SECURE_COMMAND, buf, MAVLINK_MSG_ID_SECURE_COMMAND_MIN_LEN, MAVLINK_MSG_ID_SECURE_COMMAND_LEN, MAVLINK_MSG_ID_SECURE_COMMAND_CRC);
+#else
+ mavlink_secure_command_t packet;
+ packet.sequence = sequence;
+ packet.operation = operation;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.data_length = data_length;
+ packet.sig_length = sig_length;
+ mav_array_assign_uint8_t(packet.data, data, 220);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SECURE_COMMAND, (const char *)&packet, MAVLINK_MSG_ID_SECURE_COMMAND_MIN_LEN, MAVLINK_MSG_ID_SECURE_COMMAND_LEN, MAVLINK_MSG_ID_SECURE_COMMAND_CRC);
+#endif
+}
+
+/**
+ * @brief Send a secure_command message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_secure_command_send_struct(mavlink_channel_t chan, const mavlink_secure_command_t* secure_command)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_secure_command_send(chan, secure_command->target_system, secure_command->target_component, secure_command->sequence, secure_command->operation, secure_command->data_length, secure_command->sig_length, secure_command->data);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SECURE_COMMAND, (const char *)secure_command, MAVLINK_MSG_ID_SECURE_COMMAND_MIN_LEN, MAVLINK_MSG_ID_SECURE_COMMAND_LEN, MAVLINK_MSG_ID_SECURE_COMMAND_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_SECURE_COMMAND_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_secure_command_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint32_t sequence, uint32_t operation, uint8_t data_length, uint8_t sig_length, const uint8_t *data)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint32_t(buf, 0, sequence);
+ _mav_put_uint32_t(buf, 4, operation);
+ _mav_put_uint8_t(buf, 8, target_system);
+ _mav_put_uint8_t(buf, 9, target_component);
+ _mav_put_uint8_t(buf, 10, data_length);
+ _mav_put_uint8_t(buf, 11, sig_length);
+ _mav_put_uint8_t_array(buf, 12, data, 220);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SECURE_COMMAND, buf, MAVLINK_MSG_ID_SECURE_COMMAND_MIN_LEN, MAVLINK_MSG_ID_SECURE_COMMAND_LEN, MAVLINK_MSG_ID_SECURE_COMMAND_CRC);
+#else
+ mavlink_secure_command_t *packet = (mavlink_secure_command_t *)msgbuf;
+ packet->sequence = sequence;
+ packet->operation = operation;
+ packet->target_system = target_system;
+ packet->target_component = target_component;
+ packet->data_length = data_length;
+ packet->sig_length = sig_length;
+ mav_array_assign_uint8_t(packet->data, data, 220);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SECURE_COMMAND, (const char *)packet, MAVLINK_MSG_ID_SECURE_COMMAND_MIN_LEN, MAVLINK_MSG_ID_SECURE_COMMAND_LEN, MAVLINK_MSG_ID_SECURE_COMMAND_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE SECURE_COMMAND UNPACKING
+
+
+/**
+ * @brief Get field target_system from secure_command message
+ *
+ * @return System ID.
+ */
+static inline uint8_t mavlink_msg_secure_command_get_target_system(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 8);
+}
+
+/**
+ * @brief Get field target_component from secure_command message
+ *
+ * @return Component ID.
+ */
+static inline uint8_t mavlink_msg_secure_command_get_target_component(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 9);
+}
+
+/**
+ * @brief Get field sequence from secure_command message
+ *
+ * @return Sequence ID for tagging reply.
+ */
+static inline uint32_t mavlink_msg_secure_command_get_sequence(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint32_t(msg, 0);
+}
+
+/**
+ * @brief Get field operation from secure_command message
+ *
+ * @return Operation being requested.
+ */
+static inline uint32_t mavlink_msg_secure_command_get_operation(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint32_t(msg, 4);
+}
+
+/**
+ * @brief Get field data_length from secure_command message
+ *
+ * @return Data length.
+ */
+static inline uint8_t mavlink_msg_secure_command_get_data_length(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 10);
+}
+
+/**
+ * @brief Get field sig_length from secure_command message
+ *
+ * @return Signature length.
+ */
+static inline uint8_t mavlink_msg_secure_command_get_sig_length(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 11);
+}
+
+/**
+ * @brief Get field data from secure_command message
+ *
+ * @return Signed data.
+ */
+static inline uint16_t mavlink_msg_secure_command_get_data(const mavlink_message_t* msg, uint8_t *data)
+{
+ return _MAV_RETURN_uint8_t_array(msg, data, 220, 12);
+}
+
+/**
+ * @brief Decode a secure_command message into a struct
+ *
+ * @param msg The message to decode
+ * @param secure_command C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_secure_command_decode(const mavlink_message_t* msg, mavlink_secure_command_t* secure_command)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ secure_command->sequence = mavlink_msg_secure_command_get_sequence(msg);
+ secure_command->operation = mavlink_msg_secure_command_get_operation(msg);
+ secure_command->target_system = mavlink_msg_secure_command_get_target_system(msg);
+ secure_command->target_component = mavlink_msg_secure_command_get_target_component(msg);
+ secure_command->data_length = mavlink_msg_secure_command_get_data_length(msg);
+ secure_command->sig_length = mavlink_msg_secure_command_get_sig_length(msg);
+ mavlink_msg_secure_command_get_data(msg, secure_command->data);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_SECURE_COMMAND_LEN? msg->len : MAVLINK_MSG_ID_SECURE_COMMAND_LEN;
+ memset(secure_command, 0, MAVLINK_MSG_ID_SECURE_COMMAND_LEN);
+ memcpy(secure_command, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/ardupilotmega/mavlink_msg_secure_command_reply.h b/lib/main/MAVLink/ardupilotmega/mavlink_msg_secure_command_reply.h
new file mode 100644
index 00000000000..0f7d056f0ea
--- /dev/null
+++ b/lib/main/MAVLink/ardupilotmega/mavlink_msg_secure_command_reply.h
@@ -0,0 +1,362 @@
+#pragma once
+// MESSAGE SECURE_COMMAND_REPLY PACKING
+
+#define MAVLINK_MSG_ID_SECURE_COMMAND_REPLY 11005
+
+
+typedef struct __mavlink_secure_command_reply_t {
+ uint32_t sequence; /*< Sequence ID from request.*/
+ uint32_t operation; /*< Operation that was requested.*/
+ uint8_t result; /*< Result of command.*/
+ uint8_t data_length; /*< Data length.*/
+ uint8_t data[220]; /*< Reply data.*/
+} mavlink_secure_command_reply_t;
+
+#define MAVLINK_MSG_ID_SECURE_COMMAND_REPLY_LEN 230
+#define MAVLINK_MSG_ID_SECURE_COMMAND_REPLY_MIN_LEN 230
+#define MAVLINK_MSG_ID_11005_LEN 230
+#define MAVLINK_MSG_ID_11005_MIN_LEN 230
+
+#define MAVLINK_MSG_ID_SECURE_COMMAND_REPLY_CRC 93
+#define MAVLINK_MSG_ID_11005_CRC 93
+
+#define MAVLINK_MSG_SECURE_COMMAND_REPLY_FIELD_DATA_LEN 220
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_SECURE_COMMAND_REPLY { \
+ 11005, \
+ "SECURE_COMMAND_REPLY", \
+ 5, \
+ { { "sequence", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_secure_command_reply_t, sequence) }, \
+ { "operation", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_secure_command_reply_t, operation) }, \
+ { "result", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_secure_command_reply_t, result) }, \
+ { "data_length", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_secure_command_reply_t, data_length) }, \
+ { "data", NULL, MAVLINK_TYPE_UINT8_T, 220, 10, offsetof(mavlink_secure_command_reply_t, data) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_SECURE_COMMAND_REPLY { \
+ "SECURE_COMMAND_REPLY", \
+ 5, \
+ { { "sequence", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_secure_command_reply_t, sequence) }, \
+ { "operation", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_secure_command_reply_t, operation) }, \
+ { "result", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_secure_command_reply_t, result) }, \
+ { "data_length", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_secure_command_reply_t, data_length) }, \
+ { "data", NULL, MAVLINK_TYPE_UINT8_T, 220, 10, offsetof(mavlink_secure_command_reply_t, data) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a secure_command_reply 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 sequence Sequence ID from request.
+ * @param operation Operation that was requested.
+ * @param result Result of command.
+ * @param data_length Data length.
+ * @param data Reply data.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_secure_command_reply_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint32_t sequence, uint32_t operation, uint8_t result, uint8_t data_length, const uint8_t *data)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_SECURE_COMMAND_REPLY_LEN];
+ _mav_put_uint32_t(buf, 0, sequence);
+ _mav_put_uint32_t(buf, 4, operation);
+ _mav_put_uint8_t(buf, 8, result);
+ _mav_put_uint8_t(buf, 9, data_length);
+ _mav_put_uint8_t_array(buf, 10, data, 220);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SECURE_COMMAND_REPLY_LEN);
+#else
+ mavlink_secure_command_reply_t packet;
+ packet.sequence = sequence;
+ packet.operation = operation;
+ packet.result = result;
+ packet.data_length = data_length;
+ mav_array_assign_uint8_t(packet.data, data, 220);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SECURE_COMMAND_REPLY_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_SECURE_COMMAND_REPLY;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SECURE_COMMAND_REPLY_MIN_LEN, MAVLINK_MSG_ID_SECURE_COMMAND_REPLY_LEN, MAVLINK_MSG_ID_SECURE_COMMAND_REPLY_CRC);
+}
+
+/**
+ * @brief Pack a secure_command_reply 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 sequence Sequence ID from request.
+ * @param operation Operation that was requested.
+ * @param result Result of command.
+ * @param data_length Data length.
+ * @param data Reply data.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_secure_command_reply_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ uint32_t sequence, uint32_t operation, uint8_t result, uint8_t data_length, const uint8_t *data)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_SECURE_COMMAND_REPLY_LEN];
+ _mav_put_uint32_t(buf, 0, sequence);
+ _mav_put_uint32_t(buf, 4, operation);
+ _mav_put_uint8_t(buf, 8, result);
+ _mav_put_uint8_t(buf, 9, data_length);
+ _mav_put_uint8_t_array(buf, 10, data, 220);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SECURE_COMMAND_REPLY_LEN);
+#else
+ mavlink_secure_command_reply_t packet;
+ packet.sequence = sequence;
+ packet.operation = operation;
+ packet.result = result;
+ packet.data_length = data_length;
+ mav_array_memcpy(packet.data, data, sizeof(uint8_t)*220);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SECURE_COMMAND_REPLY_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_SECURE_COMMAND_REPLY;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_SECURE_COMMAND_REPLY_MIN_LEN, MAVLINK_MSG_ID_SECURE_COMMAND_REPLY_LEN, MAVLINK_MSG_ID_SECURE_COMMAND_REPLY_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_SECURE_COMMAND_REPLY_MIN_LEN, MAVLINK_MSG_ID_SECURE_COMMAND_REPLY_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a secure_command_reply 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 sequence Sequence ID from request.
+ * @param operation Operation that was requested.
+ * @param result Result of command.
+ * @param data_length Data length.
+ * @param data Reply data.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_secure_command_reply_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint32_t sequence,uint32_t operation,uint8_t result,uint8_t data_length,const uint8_t *data)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_SECURE_COMMAND_REPLY_LEN];
+ _mav_put_uint32_t(buf, 0, sequence);
+ _mav_put_uint32_t(buf, 4, operation);
+ _mav_put_uint8_t(buf, 8, result);
+ _mav_put_uint8_t(buf, 9, data_length);
+ _mav_put_uint8_t_array(buf, 10, data, 220);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SECURE_COMMAND_REPLY_LEN);
+#else
+ mavlink_secure_command_reply_t packet;
+ packet.sequence = sequence;
+ packet.operation = operation;
+ packet.result = result;
+ packet.data_length = data_length;
+ mav_array_assign_uint8_t(packet.data, data, 220);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SECURE_COMMAND_REPLY_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_SECURE_COMMAND_REPLY;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SECURE_COMMAND_REPLY_MIN_LEN, MAVLINK_MSG_ID_SECURE_COMMAND_REPLY_LEN, MAVLINK_MSG_ID_SECURE_COMMAND_REPLY_CRC);
+}
+
+/**
+ * @brief Encode a secure_command_reply 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 secure_command_reply C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_secure_command_reply_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_secure_command_reply_t* secure_command_reply)
+{
+ return mavlink_msg_secure_command_reply_pack(system_id, component_id, msg, secure_command_reply->sequence, secure_command_reply->operation, secure_command_reply->result, secure_command_reply->data_length, secure_command_reply->data);
+}
+
+/**
+ * @brief Encode a secure_command_reply 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 secure_command_reply C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_secure_command_reply_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_secure_command_reply_t* secure_command_reply)
+{
+ return mavlink_msg_secure_command_reply_pack_chan(system_id, component_id, chan, msg, secure_command_reply->sequence, secure_command_reply->operation, secure_command_reply->result, secure_command_reply->data_length, secure_command_reply->data);
+}
+
+/**
+ * @brief Encode a secure_command_reply 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 secure_command_reply C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_secure_command_reply_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_secure_command_reply_t* secure_command_reply)
+{
+ return mavlink_msg_secure_command_reply_pack_status(system_id, component_id, _status, msg, secure_command_reply->sequence, secure_command_reply->operation, secure_command_reply->result, secure_command_reply->data_length, secure_command_reply->data);
+}
+
+/**
+ * @brief Send a secure_command_reply message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param sequence Sequence ID from request.
+ * @param operation Operation that was requested.
+ * @param result Result of command.
+ * @param data_length Data length.
+ * @param data Reply data.
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_secure_command_reply_send(mavlink_channel_t chan, uint32_t sequence, uint32_t operation, uint8_t result, uint8_t data_length, const uint8_t *data)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_SECURE_COMMAND_REPLY_LEN];
+ _mav_put_uint32_t(buf, 0, sequence);
+ _mav_put_uint32_t(buf, 4, operation);
+ _mav_put_uint8_t(buf, 8, result);
+ _mav_put_uint8_t(buf, 9, data_length);
+ _mav_put_uint8_t_array(buf, 10, data, 220);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SECURE_COMMAND_REPLY, buf, MAVLINK_MSG_ID_SECURE_COMMAND_REPLY_MIN_LEN, MAVLINK_MSG_ID_SECURE_COMMAND_REPLY_LEN, MAVLINK_MSG_ID_SECURE_COMMAND_REPLY_CRC);
+#else
+ mavlink_secure_command_reply_t packet;
+ packet.sequence = sequence;
+ packet.operation = operation;
+ packet.result = result;
+ packet.data_length = data_length;
+ mav_array_assign_uint8_t(packet.data, data, 220);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SECURE_COMMAND_REPLY, (const char *)&packet, MAVLINK_MSG_ID_SECURE_COMMAND_REPLY_MIN_LEN, MAVLINK_MSG_ID_SECURE_COMMAND_REPLY_LEN, MAVLINK_MSG_ID_SECURE_COMMAND_REPLY_CRC);
+#endif
+}
+
+/**
+ * @brief Send a secure_command_reply message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_secure_command_reply_send_struct(mavlink_channel_t chan, const mavlink_secure_command_reply_t* secure_command_reply)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_secure_command_reply_send(chan, secure_command_reply->sequence, secure_command_reply->operation, secure_command_reply->result, secure_command_reply->data_length, secure_command_reply->data);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SECURE_COMMAND_REPLY, (const char *)secure_command_reply, MAVLINK_MSG_ID_SECURE_COMMAND_REPLY_MIN_LEN, MAVLINK_MSG_ID_SECURE_COMMAND_REPLY_LEN, MAVLINK_MSG_ID_SECURE_COMMAND_REPLY_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_SECURE_COMMAND_REPLY_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_secure_command_reply_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t sequence, uint32_t operation, uint8_t result, uint8_t data_length, const uint8_t *data)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint32_t(buf, 0, sequence);
+ _mav_put_uint32_t(buf, 4, operation);
+ _mav_put_uint8_t(buf, 8, result);
+ _mav_put_uint8_t(buf, 9, data_length);
+ _mav_put_uint8_t_array(buf, 10, data, 220);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SECURE_COMMAND_REPLY, buf, MAVLINK_MSG_ID_SECURE_COMMAND_REPLY_MIN_LEN, MAVLINK_MSG_ID_SECURE_COMMAND_REPLY_LEN, MAVLINK_MSG_ID_SECURE_COMMAND_REPLY_CRC);
+#else
+ mavlink_secure_command_reply_t *packet = (mavlink_secure_command_reply_t *)msgbuf;
+ packet->sequence = sequence;
+ packet->operation = operation;
+ packet->result = result;
+ packet->data_length = data_length;
+ mav_array_assign_uint8_t(packet->data, data, 220);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SECURE_COMMAND_REPLY, (const char *)packet, MAVLINK_MSG_ID_SECURE_COMMAND_REPLY_MIN_LEN, MAVLINK_MSG_ID_SECURE_COMMAND_REPLY_LEN, MAVLINK_MSG_ID_SECURE_COMMAND_REPLY_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE SECURE_COMMAND_REPLY UNPACKING
+
+
+/**
+ * @brief Get field sequence from secure_command_reply message
+ *
+ * @return Sequence ID from request.
+ */
+static inline uint32_t mavlink_msg_secure_command_reply_get_sequence(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint32_t(msg, 0);
+}
+
+/**
+ * @brief Get field operation from secure_command_reply message
+ *
+ * @return Operation that was requested.
+ */
+static inline uint32_t mavlink_msg_secure_command_reply_get_operation(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint32_t(msg, 4);
+}
+
+/**
+ * @brief Get field result from secure_command_reply message
+ *
+ * @return Result of command.
+ */
+static inline uint8_t mavlink_msg_secure_command_reply_get_result(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 8);
+}
+
+/**
+ * @brief Get field data_length from secure_command_reply message
+ *
+ * @return Data length.
+ */
+static inline uint8_t mavlink_msg_secure_command_reply_get_data_length(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 9);
+}
+
+/**
+ * @brief Get field data from secure_command_reply message
+ *
+ * @return Reply data.
+ */
+static inline uint16_t mavlink_msg_secure_command_reply_get_data(const mavlink_message_t* msg, uint8_t *data)
+{
+ return _MAV_RETURN_uint8_t_array(msg, data, 220, 10);
+}
+
+/**
+ * @brief Decode a secure_command_reply message into a struct
+ *
+ * @param msg The message to decode
+ * @param secure_command_reply C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_secure_command_reply_decode(const mavlink_message_t* msg, mavlink_secure_command_reply_t* secure_command_reply)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ secure_command_reply->sequence = mavlink_msg_secure_command_reply_get_sequence(msg);
+ secure_command_reply->operation = mavlink_msg_secure_command_reply_get_operation(msg);
+ secure_command_reply->result = mavlink_msg_secure_command_reply_get_result(msg);
+ secure_command_reply->data_length = mavlink_msg_secure_command_reply_get_data_length(msg);
+ mavlink_msg_secure_command_reply_get_data(msg, secure_command_reply->data);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_SECURE_COMMAND_REPLY_LEN? msg->len : MAVLINK_MSG_ID_SECURE_COMMAND_REPLY_LEN;
+ memset(secure_command_reply, 0, MAVLINK_MSG_ID_SECURE_COMMAND_REPLY_LEN);
+ memcpy(secure_command_reply, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/ardupilotmega/mavlink_msg_sensor_offsets.h b/lib/main/MAVLink/ardupilotmega/mavlink_msg_sensor_offsets.h
new file mode 100644
index 00000000000..9b03cacd9d4
--- /dev/null
+++ b/lib/main/MAVLink/ardupilotmega/mavlink_msg_sensor_offsets.h
@@ -0,0 +1,568 @@
+#pragma once
+// MESSAGE SENSOR_OFFSETS PACKING
+
+#define MAVLINK_MSG_ID_SENSOR_OFFSETS 150
+
+
+typedef struct __mavlink_sensor_offsets_t {
+ float mag_declination; /*< [rad] Magnetic declination.*/
+ int32_t raw_press; /*< Raw pressure from barometer.*/
+ int32_t raw_temp; /*< Raw temperature from barometer.*/
+ float gyro_cal_x; /*< Gyro X calibration.*/
+ float gyro_cal_y; /*< Gyro Y calibration.*/
+ float gyro_cal_z; /*< Gyro Z calibration.*/
+ float accel_cal_x; /*< Accel X calibration.*/
+ float accel_cal_y; /*< Accel Y calibration.*/
+ float accel_cal_z; /*< Accel Z calibration.*/
+ int16_t mag_ofs_x; /*< Magnetometer X offset.*/
+ int16_t mag_ofs_y; /*< Magnetometer Y offset.*/
+ int16_t mag_ofs_z; /*< Magnetometer Z offset.*/
+} mavlink_sensor_offsets_t;
+
+#define MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN 42
+#define MAVLINK_MSG_ID_SENSOR_OFFSETS_MIN_LEN 42
+#define MAVLINK_MSG_ID_150_LEN 42
+#define MAVLINK_MSG_ID_150_MIN_LEN 42
+
+#define MAVLINK_MSG_ID_SENSOR_OFFSETS_CRC 134
+#define MAVLINK_MSG_ID_150_CRC 134
+
+
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_SENSOR_OFFSETS { \
+ 150, \
+ "SENSOR_OFFSETS", \
+ 12, \
+ { { "mag_ofs_x", NULL, MAVLINK_TYPE_INT16_T, 0, 36, offsetof(mavlink_sensor_offsets_t, mag_ofs_x) }, \
+ { "mag_ofs_y", NULL, MAVLINK_TYPE_INT16_T, 0, 38, offsetof(mavlink_sensor_offsets_t, mag_ofs_y) }, \
+ { "mag_ofs_z", NULL, MAVLINK_TYPE_INT16_T, 0, 40, offsetof(mavlink_sensor_offsets_t, mag_ofs_z) }, \
+ { "mag_declination", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_sensor_offsets_t, mag_declination) }, \
+ { "raw_press", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_sensor_offsets_t, raw_press) }, \
+ { "raw_temp", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_sensor_offsets_t, raw_temp) }, \
+ { "gyro_cal_x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_sensor_offsets_t, gyro_cal_x) }, \
+ { "gyro_cal_y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_sensor_offsets_t, gyro_cal_y) }, \
+ { "gyro_cal_z", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_sensor_offsets_t, gyro_cal_z) }, \
+ { "accel_cal_x", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_sensor_offsets_t, accel_cal_x) }, \
+ { "accel_cal_y", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_sensor_offsets_t, accel_cal_y) }, \
+ { "accel_cal_z", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_sensor_offsets_t, accel_cal_z) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_SENSOR_OFFSETS { \
+ "SENSOR_OFFSETS", \
+ 12, \
+ { { "mag_ofs_x", NULL, MAVLINK_TYPE_INT16_T, 0, 36, offsetof(mavlink_sensor_offsets_t, mag_ofs_x) }, \
+ { "mag_ofs_y", NULL, MAVLINK_TYPE_INT16_T, 0, 38, offsetof(mavlink_sensor_offsets_t, mag_ofs_y) }, \
+ { "mag_ofs_z", NULL, MAVLINK_TYPE_INT16_T, 0, 40, offsetof(mavlink_sensor_offsets_t, mag_ofs_z) }, \
+ { "mag_declination", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_sensor_offsets_t, mag_declination) }, \
+ { "raw_press", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_sensor_offsets_t, raw_press) }, \
+ { "raw_temp", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_sensor_offsets_t, raw_temp) }, \
+ { "gyro_cal_x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_sensor_offsets_t, gyro_cal_x) }, \
+ { "gyro_cal_y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_sensor_offsets_t, gyro_cal_y) }, \
+ { "gyro_cal_z", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_sensor_offsets_t, gyro_cal_z) }, \
+ { "accel_cal_x", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_sensor_offsets_t, accel_cal_x) }, \
+ { "accel_cal_y", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_sensor_offsets_t, accel_cal_y) }, \
+ { "accel_cal_z", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_sensor_offsets_t, accel_cal_z) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a sensor_offsets 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 mag_ofs_x Magnetometer X offset.
+ * @param mag_ofs_y Magnetometer Y offset.
+ * @param mag_ofs_z Magnetometer Z offset.
+ * @param mag_declination [rad] Magnetic declination.
+ * @param raw_press Raw pressure from barometer.
+ * @param raw_temp Raw temperature from barometer.
+ * @param gyro_cal_x Gyro X calibration.
+ * @param gyro_cal_y Gyro Y calibration.
+ * @param gyro_cal_z Gyro Z calibration.
+ * @param accel_cal_x Accel X calibration.
+ * @param accel_cal_y Accel Y calibration.
+ * @param accel_cal_z Accel Z calibration.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_sensor_offsets_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ int16_t mag_ofs_x, int16_t mag_ofs_y, int16_t mag_ofs_z, float mag_declination, int32_t raw_press, int32_t raw_temp, float gyro_cal_x, float gyro_cal_y, float gyro_cal_z, float accel_cal_x, float accel_cal_y, float accel_cal_z)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN];
+ _mav_put_float(buf, 0, mag_declination);
+ _mav_put_int32_t(buf, 4, raw_press);
+ _mav_put_int32_t(buf, 8, raw_temp);
+ _mav_put_float(buf, 12, gyro_cal_x);
+ _mav_put_float(buf, 16, gyro_cal_y);
+ _mav_put_float(buf, 20, gyro_cal_z);
+ _mav_put_float(buf, 24, accel_cal_x);
+ _mav_put_float(buf, 28, accel_cal_y);
+ _mav_put_float(buf, 32, accel_cal_z);
+ _mav_put_int16_t(buf, 36, mag_ofs_x);
+ _mav_put_int16_t(buf, 38, mag_ofs_y);
+ _mav_put_int16_t(buf, 40, mag_ofs_z);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN);
+#else
+ mavlink_sensor_offsets_t packet;
+ packet.mag_declination = mag_declination;
+ packet.raw_press = raw_press;
+ packet.raw_temp = raw_temp;
+ packet.gyro_cal_x = gyro_cal_x;
+ packet.gyro_cal_y = gyro_cal_y;
+ packet.gyro_cal_z = gyro_cal_z;
+ packet.accel_cal_x = accel_cal_x;
+ packet.accel_cal_y = accel_cal_y;
+ packet.accel_cal_z = accel_cal_z;
+ packet.mag_ofs_x = mag_ofs_x;
+ packet.mag_ofs_y = mag_ofs_y;
+ packet.mag_ofs_z = mag_ofs_z;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_SENSOR_OFFSETS;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SENSOR_OFFSETS_MIN_LEN, MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN, MAVLINK_MSG_ID_SENSOR_OFFSETS_CRC);
+}
+
+/**
+ * @brief Pack a sensor_offsets 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 mag_ofs_x Magnetometer X offset.
+ * @param mag_ofs_y Magnetometer Y offset.
+ * @param mag_ofs_z Magnetometer Z offset.
+ * @param mag_declination [rad] Magnetic declination.
+ * @param raw_press Raw pressure from barometer.
+ * @param raw_temp Raw temperature from barometer.
+ * @param gyro_cal_x Gyro X calibration.
+ * @param gyro_cal_y Gyro Y calibration.
+ * @param gyro_cal_z Gyro Z calibration.
+ * @param accel_cal_x Accel X calibration.
+ * @param accel_cal_y Accel Y calibration.
+ * @param accel_cal_z Accel Z calibration.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_sensor_offsets_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ int16_t mag_ofs_x, int16_t mag_ofs_y, int16_t mag_ofs_z, float mag_declination, int32_t raw_press, int32_t raw_temp, float gyro_cal_x, float gyro_cal_y, float gyro_cal_z, float accel_cal_x, float accel_cal_y, float accel_cal_z)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN];
+ _mav_put_float(buf, 0, mag_declination);
+ _mav_put_int32_t(buf, 4, raw_press);
+ _mav_put_int32_t(buf, 8, raw_temp);
+ _mav_put_float(buf, 12, gyro_cal_x);
+ _mav_put_float(buf, 16, gyro_cal_y);
+ _mav_put_float(buf, 20, gyro_cal_z);
+ _mav_put_float(buf, 24, accel_cal_x);
+ _mav_put_float(buf, 28, accel_cal_y);
+ _mav_put_float(buf, 32, accel_cal_z);
+ _mav_put_int16_t(buf, 36, mag_ofs_x);
+ _mav_put_int16_t(buf, 38, mag_ofs_y);
+ _mav_put_int16_t(buf, 40, mag_ofs_z);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN);
+#else
+ mavlink_sensor_offsets_t packet;
+ packet.mag_declination = mag_declination;
+ packet.raw_press = raw_press;
+ packet.raw_temp = raw_temp;
+ packet.gyro_cal_x = gyro_cal_x;
+ packet.gyro_cal_y = gyro_cal_y;
+ packet.gyro_cal_z = gyro_cal_z;
+ packet.accel_cal_x = accel_cal_x;
+ packet.accel_cal_y = accel_cal_y;
+ packet.accel_cal_z = accel_cal_z;
+ packet.mag_ofs_x = mag_ofs_x;
+ packet.mag_ofs_y = mag_ofs_y;
+ packet.mag_ofs_z = mag_ofs_z;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_SENSOR_OFFSETS;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_SENSOR_OFFSETS_MIN_LEN, MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN, MAVLINK_MSG_ID_SENSOR_OFFSETS_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_SENSOR_OFFSETS_MIN_LEN, MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a sensor_offsets 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 mag_ofs_x Magnetometer X offset.
+ * @param mag_ofs_y Magnetometer Y offset.
+ * @param mag_ofs_z Magnetometer Z offset.
+ * @param mag_declination [rad] Magnetic declination.
+ * @param raw_press Raw pressure from barometer.
+ * @param raw_temp Raw temperature from barometer.
+ * @param gyro_cal_x Gyro X calibration.
+ * @param gyro_cal_y Gyro Y calibration.
+ * @param gyro_cal_z Gyro Z calibration.
+ * @param accel_cal_x Accel X calibration.
+ * @param accel_cal_y Accel Y calibration.
+ * @param accel_cal_z Accel Z calibration.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_sensor_offsets_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ int16_t mag_ofs_x,int16_t mag_ofs_y,int16_t mag_ofs_z,float mag_declination,int32_t raw_press,int32_t raw_temp,float gyro_cal_x,float gyro_cal_y,float gyro_cal_z,float accel_cal_x,float accel_cal_y,float accel_cal_z)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN];
+ _mav_put_float(buf, 0, mag_declination);
+ _mav_put_int32_t(buf, 4, raw_press);
+ _mav_put_int32_t(buf, 8, raw_temp);
+ _mav_put_float(buf, 12, gyro_cal_x);
+ _mav_put_float(buf, 16, gyro_cal_y);
+ _mav_put_float(buf, 20, gyro_cal_z);
+ _mav_put_float(buf, 24, accel_cal_x);
+ _mav_put_float(buf, 28, accel_cal_y);
+ _mav_put_float(buf, 32, accel_cal_z);
+ _mav_put_int16_t(buf, 36, mag_ofs_x);
+ _mav_put_int16_t(buf, 38, mag_ofs_y);
+ _mav_put_int16_t(buf, 40, mag_ofs_z);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN);
+#else
+ mavlink_sensor_offsets_t packet;
+ packet.mag_declination = mag_declination;
+ packet.raw_press = raw_press;
+ packet.raw_temp = raw_temp;
+ packet.gyro_cal_x = gyro_cal_x;
+ packet.gyro_cal_y = gyro_cal_y;
+ packet.gyro_cal_z = gyro_cal_z;
+ packet.accel_cal_x = accel_cal_x;
+ packet.accel_cal_y = accel_cal_y;
+ packet.accel_cal_z = accel_cal_z;
+ packet.mag_ofs_x = mag_ofs_x;
+ packet.mag_ofs_y = mag_ofs_y;
+ packet.mag_ofs_z = mag_ofs_z;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_SENSOR_OFFSETS;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SENSOR_OFFSETS_MIN_LEN, MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN, MAVLINK_MSG_ID_SENSOR_OFFSETS_CRC);
+}
+
+/**
+ * @brief Encode a sensor_offsets 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 sensor_offsets C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_sensor_offsets_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_sensor_offsets_t* sensor_offsets)
+{
+ return mavlink_msg_sensor_offsets_pack(system_id, component_id, msg, sensor_offsets->mag_ofs_x, sensor_offsets->mag_ofs_y, sensor_offsets->mag_ofs_z, sensor_offsets->mag_declination, sensor_offsets->raw_press, sensor_offsets->raw_temp, sensor_offsets->gyro_cal_x, sensor_offsets->gyro_cal_y, sensor_offsets->gyro_cal_z, sensor_offsets->accel_cal_x, sensor_offsets->accel_cal_y, sensor_offsets->accel_cal_z);
+}
+
+/**
+ * @brief Encode a sensor_offsets 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 sensor_offsets C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_sensor_offsets_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_sensor_offsets_t* sensor_offsets)
+{
+ return mavlink_msg_sensor_offsets_pack_chan(system_id, component_id, chan, msg, sensor_offsets->mag_ofs_x, sensor_offsets->mag_ofs_y, sensor_offsets->mag_ofs_z, sensor_offsets->mag_declination, sensor_offsets->raw_press, sensor_offsets->raw_temp, sensor_offsets->gyro_cal_x, sensor_offsets->gyro_cal_y, sensor_offsets->gyro_cal_z, sensor_offsets->accel_cal_x, sensor_offsets->accel_cal_y, sensor_offsets->accel_cal_z);
+}
+
+/**
+ * @brief Encode a sensor_offsets 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 sensor_offsets C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_sensor_offsets_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_sensor_offsets_t* sensor_offsets)
+{
+ return mavlink_msg_sensor_offsets_pack_status(system_id, component_id, _status, msg, sensor_offsets->mag_ofs_x, sensor_offsets->mag_ofs_y, sensor_offsets->mag_ofs_z, sensor_offsets->mag_declination, sensor_offsets->raw_press, sensor_offsets->raw_temp, sensor_offsets->gyro_cal_x, sensor_offsets->gyro_cal_y, sensor_offsets->gyro_cal_z, sensor_offsets->accel_cal_x, sensor_offsets->accel_cal_y, sensor_offsets->accel_cal_z);
+}
+
+/**
+ * @brief Send a sensor_offsets message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param mag_ofs_x Magnetometer X offset.
+ * @param mag_ofs_y Magnetometer Y offset.
+ * @param mag_ofs_z Magnetometer Z offset.
+ * @param mag_declination [rad] Magnetic declination.
+ * @param raw_press Raw pressure from barometer.
+ * @param raw_temp Raw temperature from barometer.
+ * @param gyro_cal_x Gyro X calibration.
+ * @param gyro_cal_y Gyro Y calibration.
+ * @param gyro_cal_z Gyro Z calibration.
+ * @param accel_cal_x Accel X calibration.
+ * @param accel_cal_y Accel Y calibration.
+ * @param accel_cal_z Accel Z calibration.
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_sensor_offsets_send(mavlink_channel_t chan, int16_t mag_ofs_x, int16_t mag_ofs_y, int16_t mag_ofs_z, float mag_declination, int32_t raw_press, int32_t raw_temp, float gyro_cal_x, float gyro_cal_y, float gyro_cal_z, float accel_cal_x, float accel_cal_y, float accel_cal_z)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN];
+ _mav_put_float(buf, 0, mag_declination);
+ _mav_put_int32_t(buf, 4, raw_press);
+ _mav_put_int32_t(buf, 8, raw_temp);
+ _mav_put_float(buf, 12, gyro_cal_x);
+ _mav_put_float(buf, 16, gyro_cal_y);
+ _mav_put_float(buf, 20, gyro_cal_z);
+ _mav_put_float(buf, 24, accel_cal_x);
+ _mav_put_float(buf, 28, accel_cal_y);
+ _mav_put_float(buf, 32, accel_cal_z);
+ _mav_put_int16_t(buf, 36, mag_ofs_x);
+ _mav_put_int16_t(buf, 38, mag_ofs_y);
+ _mav_put_int16_t(buf, 40, mag_ofs_z);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSOR_OFFSETS, buf, MAVLINK_MSG_ID_SENSOR_OFFSETS_MIN_LEN, MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN, MAVLINK_MSG_ID_SENSOR_OFFSETS_CRC);
+#else
+ mavlink_sensor_offsets_t packet;
+ packet.mag_declination = mag_declination;
+ packet.raw_press = raw_press;
+ packet.raw_temp = raw_temp;
+ packet.gyro_cal_x = gyro_cal_x;
+ packet.gyro_cal_y = gyro_cal_y;
+ packet.gyro_cal_z = gyro_cal_z;
+ packet.accel_cal_x = accel_cal_x;
+ packet.accel_cal_y = accel_cal_y;
+ packet.accel_cal_z = accel_cal_z;
+ packet.mag_ofs_x = mag_ofs_x;
+ packet.mag_ofs_y = mag_ofs_y;
+ packet.mag_ofs_z = mag_ofs_z;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSOR_OFFSETS, (const char *)&packet, MAVLINK_MSG_ID_SENSOR_OFFSETS_MIN_LEN, MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN, MAVLINK_MSG_ID_SENSOR_OFFSETS_CRC);
+#endif
+}
+
+/**
+ * @brief Send a sensor_offsets message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_sensor_offsets_send_struct(mavlink_channel_t chan, const mavlink_sensor_offsets_t* sensor_offsets)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_sensor_offsets_send(chan, sensor_offsets->mag_ofs_x, sensor_offsets->mag_ofs_y, sensor_offsets->mag_ofs_z, sensor_offsets->mag_declination, sensor_offsets->raw_press, sensor_offsets->raw_temp, sensor_offsets->gyro_cal_x, sensor_offsets->gyro_cal_y, sensor_offsets->gyro_cal_z, sensor_offsets->accel_cal_x, sensor_offsets->accel_cal_y, sensor_offsets->accel_cal_z);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSOR_OFFSETS, (const char *)sensor_offsets, MAVLINK_MSG_ID_SENSOR_OFFSETS_MIN_LEN, MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN, MAVLINK_MSG_ID_SENSOR_OFFSETS_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_sensor_offsets_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, int16_t mag_ofs_x, int16_t mag_ofs_y, int16_t mag_ofs_z, float mag_declination, int32_t raw_press, int32_t raw_temp, float gyro_cal_x, float gyro_cal_y, float gyro_cal_z, float accel_cal_x, float accel_cal_y, float accel_cal_z)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_float(buf, 0, mag_declination);
+ _mav_put_int32_t(buf, 4, raw_press);
+ _mav_put_int32_t(buf, 8, raw_temp);
+ _mav_put_float(buf, 12, gyro_cal_x);
+ _mav_put_float(buf, 16, gyro_cal_y);
+ _mav_put_float(buf, 20, gyro_cal_z);
+ _mav_put_float(buf, 24, accel_cal_x);
+ _mav_put_float(buf, 28, accel_cal_y);
+ _mav_put_float(buf, 32, accel_cal_z);
+ _mav_put_int16_t(buf, 36, mag_ofs_x);
+ _mav_put_int16_t(buf, 38, mag_ofs_y);
+ _mav_put_int16_t(buf, 40, mag_ofs_z);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSOR_OFFSETS, buf, MAVLINK_MSG_ID_SENSOR_OFFSETS_MIN_LEN, MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN, MAVLINK_MSG_ID_SENSOR_OFFSETS_CRC);
+#else
+ mavlink_sensor_offsets_t *packet = (mavlink_sensor_offsets_t *)msgbuf;
+ packet->mag_declination = mag_declination;
+ packet->raw_press = raw_press;
+ packet->raw_temp = raw_temp;
+ packet->gyro_cal_x = gyro_cal_x;
+ packet->gyro_cal_y = gyro_cal_y;
+ packet->gyro_cal_z = gyro_cal_z;
+ packet->accel_cal_x = accel_cal_x;
+ packet->accel_cal_y = accel_cal_y;
+ packet->accel_cal_z = accel_cal_z;
+ packet->mag_ofs_x = mag_ofs_x;
+ packet->mag_ofs_y = mag_ofs_y;
+ packet->mag_ofs_z = mag_ofs_z;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSOR_OFFSETS, (const char *)packet, MAVLINK_MSG_ID_SENSOR_OFFSETS_MIN_LEN, MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN, MAVLINK_MSG_ID_SENSOR_OFFSETS_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE SENSOR_OFFSETS UNPACKING
+
+
+/**
+ * @brief Get field mag_ofs_x from sensor_offsets message
+ *
+ * @return Magnetometer X offset.
+ */
+static inline int16_t mavlink_msg_sensor_offsets_get_mag_ofs_x(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_int16_t(msg, 36);
+}
+
+/**
+ * @brief Get field mag_ofs_y from sensor_offsets message
+ *
+ * @return Magnetometer Y offset.
+ */
+static inline int16_t mavlink_msg_sensor_offsets_get_mag_ofs_y(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_int16_t(msg, 38);
+}
+
+/**
+ * @brief Get field mag_ofs_z from sensor_offsets message
+ *
+ * @return Magnetometer Z offset.
+ */
+static inline int16_t mavlink_msg_sensor_offsets_get_mag_ofs_z(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_int16_t(msg, 40);
+}
+
+/**
+ * @brief Get field mag_declination from sensor_offsets message
+ *
+ * @return [rad] Magnetic declination.
+ */
+static inline float mavlink_msg_sensor_offsets_get_mag_declination(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 0);
+}
+
+/**
+ * @brief Get field raw_press from sensor_offsets message
+ *
+ * @return Raw pressure from barometer.
+ */
+static inline int32_t mavlink_msg_sensor_offsets_get_raw_press(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_int32_t(msg, 4);
+}
+
+/**
+ * @brief Get field raw_temp from sensor_offsets message
+ *
+ * @return Raw temperature from barometer.
+ */
+static inline int32_t mavlink_msg_sensor_offsets_get_raw_temp(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_int32_t(msg, 8);
+}
+
+/**
+ * @brief Get field gyro_cal_x from sensor_offsets message
+ *
+ * @return Gyro X calibration.
+ */
+static inline float mavlink_msg_sensor_offsets_get_gyro_cal_x(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 12);
+}
+
+/**
+ * @brief Get field gyro_cal_y from sensor_offsets message
+ *
+ * @return Gyro Y calibration.
+ */
+static inline float mavlink_msg_sensor_offsets_get_gyro_cal_y(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 16);
+}
+
+/**
+ * @brief Get field gyro_cal_z from sensor_offsets message
+ *
+ * @return Gyro Z calibration.
+ */
+static inline float mavlink_msg_sensor_offsets_get_gyro_cal_z(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 20);
+}
+
+/**
+ * @brief Get field accel_cal_x from sensor_offsets message
+ *
+ * @return Accel X calibration.
+ */
+static inline float mavlink_msg_sensor_offsets_get_accel_cal_x(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 24);
+}
+
+/**
+ * @brief Get field accel_cal_y from sensor_offsets message
+ *
+ * @return Accel Y calibration.
+ */
+static inline float mavlink_msg_sensor_offsets_get_accel_cal_y(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 28);
+}
+
+/**
+ * @brief Get field accel_cal_z from sensor_offsets message
+ *
+ * @return Accel Z calibration.
+ */
+static inline float mavlink_msg_sensor_offsets_get_accel_cal_z(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 32);
+}
+
+/**
+ * @brief Decode a sensor_offsets message into a struct
+ *
+ * @param msg The message to decode
+ * @param sensor_offsets C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_sensor_offsets_decode(const mavlink_message_t* msg, mavlink_sensor_offsets_t* sensor_offsets)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ sensor_offsets->mag_declination = mavlink_msg_sensor_offsets_get_mag_declination(msg);
+ sensor_offsets->raw_press = mavlink_msg_sensor_offsets_get_raw_press(msg);
+ sensor_offsets->raw_temp = mavlink_msg_sensor_offsets_get_raw_temp(msg);
+ sensor_offsets->gyro_cal_x = mavlink_msg_sensor_offsets_get_gyro_cal_x(msg);
+ sensor_offsets->gyro_cal_y = mavlink_msg_sensor_offsets_get_gyro_cal_y(msg);
+ sensor_offsets->gyro_cal_z = mavlink_msg_sensor_offsets_get_gyro_cal_z(msg);
+ sensor_offsets->accel_cal_x = mavlink_msg_sensor_offsets_get_accel_cal_x(msg);
+ sensor_offsets->accel_cal_y = mavlink_msg_sensor_offsets_get_accel_cal_y(msg);
+ sensor_offsets->accel_cal_z = mavlink_msg_sensor_offsets_get_accel_cal_z(msg);
+ sensor_offsets->mag_ofs_x = mavlink_msg_sensor_offsets_get_mag_ofs_x(msg);
+ sensor_offsets->mag_ofs_y = mavlink_msg_sensor_offsets_get_mag_ofs_y(msg);
+ sensor_offsets->mag_ofs_z = mavlink_msg_sensor_offsets_get_mag_ofs_z(msg);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN? msg->len : MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN;
+ memset(sensor_offsets, 0, MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN);
+ memcpy(sensor_offsets, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/ardupilotmega/mavlink_msg_set_mag_offsets.h b/lib/main/MAVLink/ardupilotmega/mavlink_msg_set_mag_offsets.h
new file mode 100644
index 00000000000..e03036ee6c2
--- /dev/null
+++ b/lib/main/MAVLink/ardupilotmega/mavlink_msg_set_mag_offsets.h
@@ -0,0 +1,372 @@
+#pragma once
+// MESSAGE SET_MAG_OFFSETS PACKING
+
+#define MAVLINK_MSG_ID_SET_MAG_OFFSETS 151
+
+
+typedef struct __mavlink_set_mag_offsets_t {
+ int16_t mag_ofs_x; /*< Magnetometer X offset.*/
+ int16_t mag_ofs_y; /*< Magnetometer Y offset.*/
+ int16_t mag_ofs_z; /*< Magnetometer Z offset.*/
+ uint8_t target_system; /*< System ID.*/
+ uint8_t target_component; /*< Component ID.*/
+} mavlink_set_mag_offsets_t;
+
+#define MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN 8
+#define MAVLINK_MSG_ID_SET_MAG_OFFSETS_MIN_LEN 8
+#define MAVLINK_MSG_ID_151_LEN 8
+#define MAVLINK_MSG_ID_151_MIN_LEN 8
+
+#define MAVLINK_MSG_ID_SET_MAG_OFFSETS_CRC 219
+#define MAVLINK_MSG_ID_151_CRC 219
+
+
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_SET_MAG_OFFSETS { \
+ 151, \
+ "SET_MAG_OFFSETS", \
+ 5, \
+ { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_set_mag_offsets_t, target_system) }, \
+ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_set_mag_offsets_t, target_component) }, \
+ { "mag_ofs_x", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_set_mag_offsets_t, mag_ofs_x) }, \
+ { "mag_ofs_y", NULL, MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_set_mag_offsets_t, mag_ofs_y) }, \
+ { "mag_ofs_z", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_set_mag_offsets_t, mag_ofs_z) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_SET_MAG_OFFSETS { \
+ "SET_MAG_OFFSETS", \
+ 5, \
+ { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_set_mag_offsets_t, target_system) }, \
+ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_set_mag_offsets_t, target_component) }, \
+ { "mag_ofs_x", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_set_mag_offsets_t, mag_ofs_x) }, \
+ { "mag_ofs_y", NULL, MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_set_mag_offsets_t, mag_ofs_y) }, \
+ { "mag_ofs_z", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_set_mag_offsets_t, mag_ofs_z) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a set_mag_offsets 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 target_system System ID.
+ * @param target_component Component ID.
+ * @param mag_ofs_x Magnetometer X offset.
+ * @param mag_ofs_y Magnetometer Y offset.
+ * @param mag_ofs_z Magnetometer Z offset.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_set_mag_offsets_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint8_t target_system, uint8_t target_component, int16_t mag_ofs_x, int16_t mag_ofs_y, int16_t mag_ofs_z)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN];
+ _mav_put_int16_t(buf, 0, mag_ofs_x);
+ _mav_put_int16_t(buf, 2, mag_ofs_y);
+ _mav_put_int16_t(buf, 4, mag_ofs_z);
+ _mav_put_uint8_t(buf, 6, target_system);
+ _mav_put_uint8_t(buf, 7, target_component);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN);
+#else
+ mavlink_set_mag_offsets_t packet;
+ packet.mag_ofs_x = mag_ofs_x;
+ packet.mag_ofs_y = mag_ofs_y;
+ packet.mag_ofs_z = mag_ofs_z;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_SET_MAG_OFFSETS;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SET_MAG_OFFSETS_MIN_LEN, MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN, MAVLINK_MSG_ID_SET_MAG_OFFSETS_CRC);
+}
+
+/**
+ * @brief Pack a set_mag_offsets 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 target_system System ID.
+ * @param target_component Component ID.
+ * @param mag_ofs_x Magnetometer X offset.
+ * @param mag_ofs_y Magnetometer Y offset.
+ * @param mag_ofs_z Magnetometer Z offset.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_set_mag_offsets_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ uint8_t target_system, uint8_t target_component, int16_t mag_ofs_x, int16_t mag_ofs_y, int16_t mag_ofs_z)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN];
+ _mav_put_int16_t(buf, 0, mag_ofs_x);
+ _mav_put_int16_t(buf, 2, mag_ofs_y);
+ _mav_put_int16_t(buf, 4, mag_ofs_z);
+ _mav_put_uint8_t(buf, 6, target_system);
+ _mav_put_uint8_t(buf, 7, target_component);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN);
+#else
+ mavlink_set_mag_offsets_t packet;
+ packet.mag_ofs_x = mag_ofs_x;
+ packet.mag_ofs_y = mag_ofs_y;
+ packet.mag_ofs_z = mag_ofs_z;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_SET_MAG_OFFSETS;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_SET_MAG_OFFSETS_MIN_LEN, MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN, MAVLINK_MSG_ID_SET_MAG_OFFSETS_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_SET_MAG_OFFSETS_MIN_LEN, MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a set_mag_offsets 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 target_system System ID.
+ * @param target_component Component ID.
+ * @param mag_ofs_x Magnetometer X offset.
+ * @param mag_ofs_y Magnetometer Y offset.
+ * @param mag_ofs_z Magnetometer Z offset.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_set_mag_offsets_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint8_t target_system,uint8_t target_component,int16_t mag_ofs_x,int16_t mag_ofs_y,int16_t mag_ofs_z)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN];
+ _mav_put_int16_t(buf, 0, mag_ofs_x);
+ _mav_put_int16_t(buf, 2, mag_ofs_y);
+ _mav_put_int16_t(buf, 4, mag_ofs_z);
+ _mav_put_uint8_t(buf, 6, target_system);
+ _mav_put_uint8_t(buf, 7, target_component);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN);
+#else
+ mavlink_set_mag_offsets_t packet;
+ packet.mag_ofs_x = mag_ofs_x;
+ packet.mag_ofs_y = mag_ofs_y;
+ packet.mag_ofs_z = mag_ofs_z;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_SET_MAG_OFFSETS;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SET_MAG_OFFSETS_MIN_LEN, MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN, MAVLINK_MSG_ID_SET_MAG_OFFSETS_CRC);
+}
+
+/**
+ * @brief Encode a set_mag_offsets 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 set_mag_offsets C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_set_mag_offsets_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_mag_offsets_t* set_mag_offsets)
+{
+ return mavlink_msg_set_mag_offsets_pack(system_id, component_id, msg, set_mag_offsets->target_system, set_mag_offsets->target_component, set_mag_offsets->mag_ofs_x, set_mag_offsets->mag_ofs_y, set_mag_offsets->mag_ofs_z);
+}
+
+/**
+ * @brief Encode a set_mag_offsets 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 set_mag_offsets C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_set_mag_offsets_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_set_mag_offsets_t* set_mag_offsets)
+{
+ return mavlink_msg_set_mag_offsets_pack_chan(system_id, component_id, chan, msg, set_mag_offsets->target_system, set_mag_offsets->target_component, set_mag_offsets->mag_ofs_x, set_mag_offsets->mag_ofs_y, set_mag_offsets->mag_ofs_z);
+}
+
+/**
+ * @brief Encode a set_mag_offsets 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 set_mag_offsets C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_set_mag_offsets_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_set_mag_offsets_t* set_mag_offsets)
+{
+ return mavlink_msg_set_mag_offsets_pack_status(system_id, component_id, _status, msg, set_mag_offsets->target_system, set_mag_offsets->target_component, set_mag_offsets->mag_ofs_x, set_mag_offsets->mag_ofs_y, set_mag_offsets->mag_ofs_z);
+}
+
+/**
+ * @brief Send a set_mag_offsets message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param target_system System ID.
+ * @param target_component Component ID.
+ * @param mag_ofs_x Magnetometer X offset.
+ * @param mag_ofs_y Magnetometer Y offset.
+ * @param mag_ofs_z Magnetometer Z offset.
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_set_mag_offsets_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, int16_t mag_ofs_x, int16_t mag_ofs_y, int16_t mag_ofs_z)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN];
+ _mav_put_int16_t(buf, 0, mag_ofs_x);
+ _mav_put_int16_t(buf, 2, mag_ofs_y);
+ _mav_put_int16_t(buf, 4, mag_ofs_z);
+ _mav_put_uint8_t(buf, 6, target_system);
+ _mav_put_uint8_t(buf, 7, target_component);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MAG_OFFSETS, buf, MAVLINK_MSG_ID_SET_MAG_OFFSETS_MIN_LEN, MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN, MAVLINK_MSG_ID_SET_MAG_OFFSETS_CRC);
+#else
+ mavlink_set_mag_offsets_t packet;
+ packet.mag_ofs_x = mag_ofs_x;
+ packet.mag_ofs_y = mag_ofs_y;
+ packet.mag_ofs_z = mag_ofs_z;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MAG_OFFSETS, (const char *)&packet, MAVLINK_MSG_ID_SET_MAG_OFFSETS_MIN_LEN, MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN, MAVLINK_MSG_ID_SET_MAG_OFFSETS_CRC);
+#endif
+}
+
+/**
+ * @brief Send a set_mag_offsets message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_set_mag_offsets_send_struct(mavlink_channel_t chan, const mavlink_set_mag_offsets_t* set_mag_offsets)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_set_mag_offsets_send(chan, set_mag_offsets->target_system, set_mag_offsets->target_component, set_mag_offsets->mag_ofs_x, set_mag_offsets->mag_ofs_y, set_mag_offsets->mag_ofs_z);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MAG_OFFSETS, (const char *)set_mag_offsets, MAVLINK_MSG_ID_SET_MAG_OFFSETS_MIN_LEN, MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN, MAVLINK_MSG_ID_SET_MAG_OFFSETS_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_set_mag_offsets_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, int16_t mag_ofs_x, int16_t mag_ofs_y, int16_t mag_ofs_z)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_int16_t(buf, 0, mag_ofs_x);
+ _mav_put_int16_t(buf, 2, mag_ofs_y);
+ _mav_put_int16_t(buf, 4, mag_ofs_z);
+ _mav_put_uint8_t(buf, 6, target_system);
+ _mav_put_uint8_t(buf, 7, target_component);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MAG_OFFSETS, buf, MAVLINK_MSG_ID_SET_MAG_OFFSETS_MIN_LEN, MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN, MAVLINK_MSG_ID_SET_MAG_OFFSETS_CRC);
+#else
+ mavlink_set_mag_offsets_t *packet = (mavlink_set_mag_offsets_t *)msgbuf;
+ packet->mag_ofs_x = mag_ofs_x;
+ packet->mag_ofs_y = mag_ofs_y;
+ packet->mag_ofs_z = mag_ofs_z;
+ packet->target_system = target_system;
+ packet->target_component = target_component;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MAG_OFFSETS, (const char *)packet, MAVLINK_MSG_ID_SET_MAG_OFFSETS_MIN_LEN, MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN, MAVLINK_MSG_ID_SET_MAG_OFFSETS_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE SET_MAG_OFFSETS UNPACKING
+
+
+/**
+ * @brief Get field target_system from set_mag_offsets message
+ *
+ * @return System ID.
+ */
+static inline uint8_t mavlink_msg_set_mag_offsets_get_target_system(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 6);
+}
+
+/**
+ * @brief Get field target_component from set_mag_offsets message
+ *
+ * @return Component ID.
+ */
+static inline uint8_t mavlink_msg_set_mag_offsets_get_target_component(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 7);
+}
+
+/**
+ * @brief Get field mag_ofs_x from set_mag_offsets message
+ *
+ * @return Magnetometer X offset.
+ */
+static inline int16_t mavlink_msg_set_mag_offsets_get_mag_ofs_x(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_int16_t(msg, 0);
+}
+
+/**
+ * @brief Get field mag_ofs_y from set_mag_offsets message
+ *
+ * @return Magnetometer Y offset.
+ */
+static inline int16_t mavlink_msg_set_mag_offsets_get_mag_ofs_y(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_int16_t(msg, 2);
+}
+
+/**
+ * @brief Get field mag_ofs_z from set_mag_offsets message
+ *
+ * @return Magnetometer Z offset.
+ */
+static inline int16_t mavlink_msg_set_mag_offsets_get_mag_ofs_z(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_int16_t(msg, 4);
+}
+
+/**
+ * @brief Decode a set_mag_offsets message into a struct
+ *
+ * @param msg The message to decode
+ * @param set_mag_offsets C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_set_mag_offsets_decode(const mavlink_message_t* msg, mavlink_set_mag_offsets_t* set_mag_offsets)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ set_mag_offsets->mag_ofs_x = mavlink_msg_set_mag_offsets_get_mag_ofs_x(msg);
+ set_mag_offsets->mag_ofs_y = mavlink_msg_set_mag_offsets_get_mag_ofs_y(msg);
+ set_mag_offsets->mag_ofs_z = mavlink_msg_set_mag_offsets_get_mag_ofs_z(msg);
+ set_mag_offsets->target_system = mavlink_msg_set_mag_offsets_get_target_system(msg);
+ set_mag_offsets->target_component = mavlink_msg_set_mag_offsets_get_target_component(msg);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN? msg->len : MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN;
+ memset(set_mag_offsets, 0, MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN);
+ memcpy(set_mag_offsets, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/ardupilotmega/mavlink_msg_simstate.h b/lib/main/MAVLink/ardupilotmega/mavlink_msg_simstate.h
new file mode 100644
index 00000000000..43993fc9cab
--- /dev/null
+++ b/lib/main/MAVLink/ardupilotmega/mavlink_msg_simstate.h
@@ -0,0 +1,540 @@
+#pragma once
+// MESSAGE SIMSTATE PACKING
+
+#define MAVLINK_MSG_ID_SIMSTATE 164
+
+
+typedef struct __mavlink_simstate_t {
+ float roll; /*< [rad] Roll angle.*/
+ float pitch; /*< [rad] Pitch angle.*/
+ float yaw; /*< [rad] Yaw angle.*/
+ float xacc; /*< [m/s/s] X acceleration.*/
+ float yacc; /*< [m/s/s] Y acceleration.*/
+ float zacc; /*< [m/s/s] Z acceleration.*/
+ float xgyro; /*< [rad/s] Angular speed around X axis.*/
+ float ygyro; /*< [rad/s] Angular speed around Y axis.*/
+ float zgyro; /*< [rad/s] Angular speed around Z axis.*/
+ int32_t lat; /*< [degE7] Latitude.*/
+ int32_t lng; /*< [degE7] Longitude.*/
+} mavlink_simstate_t;
+
+#define MAVLINK_MSG_ID_SIMSTATE_LEN 44
+#define MAVLINK_MSG_ID_SIMSTATE_MIN_LEN 44
+#define MAVLINK_MSG_ID_164_LEN 44
+#define MAVLINK_MSG_ID_164_MIN_LEN 44
+
+#define MAVLINK_MSG_ID_SIMSTATE_CRC 154
+#define MAVLINK_MSG_ID_164_CRC 154
+
+
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_SIMSTATE { \
+ 164, \
+ "SIMSTATE", \
+ 11, \
+ { { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_simstate_t, roll) }, \
+ { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_simstate_t, pitch) }, \
+ { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_simstate_t, yaw) }, \
+ { "xacc", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_simstate_t, xacc) }, \
+ { "yacc", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_simstate_t, yacc) }, \
+ { "zacc", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_simstate_t, zacc) }, \
+ { "xgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_simstate_t, xgyro) }, \
+ { "ygyro", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_simstate_t, ygyro) }, \
+ { "zgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_simstate_t, zgyro) }, \
+ { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 36, offsetof(mavlink_simstate_t, lat) }, \
+ { "lng", NULL, MAVLINK_TYPE_INT32_T, 0, 40, offsetof(mavlink_simstate_t, lng) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_SIMSTATE { \
+ "SIMSTATE", \
+ 11, \
+ { { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_simstate_t, roll) }, \
+ { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_simstate_t, pitch) }, \
+ { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_simstate_t, yaw) }, \
+ { "xacc", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_simstate_t, xacc) }, \
+ { "yacc", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_simstate_t, yacc) }, \
+ { "zacc", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_simstate_t, zacc) }, \
+ { "xgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_simstate_t, xgyro) }, \
+ { "ygyro", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_simstate_t, ygyro) }, \
+ { "zgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_simstate_t, zgyro) }, \
+ { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 36, offsetof(mavlink_simstate_t, lat) }, \
+ { "lng", NULL, MAVLINK_TYPE_INT32_T, 0, 40, offsetof(mavlink_simstate_t, lng) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a simstate 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 roll [rad] Roll angle.
+ * @param pitch [rad] Pitch angle.
+ * @param yaw [rad] Yaw angle.
+ * @param xacc [m/s/s] X acceleration.
+ * @param yacc [m/s/s] Y acceleration.
+ * @param zacc [m/s/s] Z acceleration.
+ * @param xgyro [rad/s] Angular speed around X axis.
+ * @param ygyro [rad/s] Angular speed around Y axis.
+ * @param zgyro [rad/s] Angular speed around Z axis.
+ * @param lat [degE7] Latitude.
+ * @param lng [degE7] Longitude.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_simstate_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ float roll, float pitch, float yaw, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, int32_t lat, int32_t lng)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_SIMSTATE_LEN];
+ _mav_put_float(buf, 0, roll);
+ _mav_put_float(buf, 4, pitch);
+ _mav_put_float(buf, 8, yaw);
+ _mav_put_float(buf, 12, xacc);
+ _mav_put_float(buf, 16, yacc);
+ _mav_put_float(buf, 20, zacc);
+ _mav_put_float(buf, 24, xgyro);
+ _mav_put_float(buf, 28, ygyro);
+ _mav_put_float(buf, 32, zgyro);
+ _mav_put_int32_t(buf, 36, lat);
+ _mav_put_int32_t(buf, 40, lng);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SIMSTATE_LEN);
+#else
+ mavlink_simstate_t packet;
+ packet.roll = roll;
+ packet.pitch = pitch;
+ packet.yaw = yaw;
+ packet.xacc = xacc;
+ packet.yacc = yacc;
+ packet.zacc = zacc;
+ packet.xgyro = xgyro;
+ packet.ygyro = ygyro;
+ packet.zgyro = zgyro;
+ packet.lat = lat;
+ packet.lng = lng;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SIMSTATE_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_SIMSTATE;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SIMSTATE_MIN_LEN, MAVLINK_MSG_ID_SIMSTATE_LEN, MAVLINK_MSG_ID_SIMSTATE_CRC);
+}
+
+/**
+ * @brief Pack a simstate 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 roll [rad] Roll angle.
+ * @param pitch [rad] Pitch angle.
+ * @param yaw [rad] Yaw angle.
+ * @param xacc [m/s/s] X acceleration.
+ * @param yacc [m/s/s] Y acceleration.
+ * @param zacc [m/s/s] Z acceleration.
+ * @param xgyro [rad/s] Angular speed around X axis.
+ * @param ygyro [rad/s] Angular speed around Y axis.
+ * @param zgyro [rad/s] Angular speed around Z axis.
+ * @param lat [degE7] Latitude.
+ * @param lng [degE7] Longitude.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_simstate_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ float roll, float pitch, float yaw, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, int32_t lat, int32_t lng)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_SIMSTATE_LEN];
+ _mav_put_float(buf, 0, roll);
+ _mav_put_float(buf, 4, pitch);
+ _mav_put_float(buf, 8, yaw);
+ _mav_put_float(buf, 12, xacc);
+ _mav_put_float(buf, 16, yacc);
+ _mav_put_float(buf, 20, zacc);
+ _mav_put_float(buf, 24, xgyro);
+ _mav_put_float(buf, 28, ygyro);
+ _mav_put_float(buf, 32, zgyro);
+ _mav_put_int32_t(buf, 36, lat);
+ _mav_put_int32_t(buf, 40, lng);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SIMSTATE_LEN);
+#else
+ mavlink_simstate_t packet;
+ packet.roll = roll;
+ packet.pitch = pitch;
+ packet.yaw = yaw;
+ packet.xacc = xacc;
+ packet.yacc = yacc;
+ packet.zacc = zacc;
+ packet.xgyro = xgyro;
+ packet.ygyro = ygyro;
+ packet.zgyro = zgyro;
+ packet.lat = lat;
+ packet.lng = lng;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SIMSTATE_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_SIMSTATE;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_SIMSTATE_MIN_LEN, MAVLINK_MSG_ID_SIMSTATE_LEN, MAVLINK_MSG_ID_SIMSTATE_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_SIMSTATE_MIN_LEN, MAVLINK_MSG_ID_SIMSTATE_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a simstate 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 roll [rad] Roll angle.
+ * @param pitch [rad] Pitch angle.
+ * @param yaw [rad] Yaw angle.
+ * @param xacc [m/s/s] X acceleration.
+ * @param yacc [m/s/s] Y acceleration.
+ * @param zacc [m/s/s] Z acceleration.
+ * @param xgyro [rad/s] Angular speed around X axis.
+ * @param ygyro [rad/s] Angular speed around Y axis.
+ * @param zgyro [rad/s] Angular speed around Z axis.
+ * @param lat [degE7] Latitude.
+ * @param lng [degE7] Longitude.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_simstate_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ float roll,float pitch,float yaw,float xacc,float yacc,float zacc,float xgyro,float ygyro,float zgyro,int32_t lat,int32_t lng)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_SIMSTATE_LEN];
+ _mav_put_float(buf, 0, roll);
+ _mav_put_float(buf, 4, pitch);
+ _mav_put_float(buf, 8, yaw);
+ _mav_put_float(buf, 12, xacc);
+ _mav_put_float(buf, 16, yacc);
+ _mav_put_float(buf, 20, zacc);
+ _mav_put_float(buf, 24, xgyro);
+ _mav_put_float(buf, 28, ygyro);
+ _mav_put_float(buf, 32, zgyro);
+ _mav_put_int32_t(buf, 36, lat);
+ _mav_put_int32_t(buf, 40, lng);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_SIMSTATE_LEN);
+#else
+ mavlink_simstate_t packet;
+ packet.roll = roll;
+ packet.pitch = pitch;
+ packet.yaw = yaw;
+ packet.xacc = xacc;
+ packet.yacc = yacc;
+ packet.zacc = zacc;
+ packet.xgyro = xgyro;
+ packet.ygyro = ygyro;
+ packet.zgyro = zgyro;
+ packet.lat = lat;
+ packet.lng = lng;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_SIMSTATE_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_SIMSTATE;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SIMSTATE_MIN_LEN, MAVLINK_MSG_ID_SIMSTATE_LEN, MAVLINK_MSG_ID_SIMSTATE_CRC);
+}
+
+/**
+ * @brief Encode a simstate 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 simstate C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_simstate_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_simstate_t* simstate)
+{
+ return mavlink_msg_simstate_pack(system_id, component_id, msg, simstate->roll, simstate->pitch, simstate->yaw, simstate->xacc, simstate->yacc, simstate->zacc, simstate->xgyro, simstate->ygyro, simstate->zgyro, simstate->lat, simstate->lng);
+}
+
+/**
+ * @brief Encode a simstate 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 simstate C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_simstate_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_simstate_t* simstate)
+{
+ return mavlink_msg_simstate_pack_chan(system_id, component_id, chan, msg, simstate->roll, simstate->pitch, simstate->yaw, simstate->xacc, simstate->yacc, simstate->zacc, simstate->xgyro, simstate->ygyro, simstate->zgyro, simstate->lat, simstate->lng);
+}
+
+/**
+ * @brief Encode a simstate 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 simstate C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_simstate_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_simstate_t* simstate)
+{
+ return mavlink_msg_simstate_pack_status(system_id, component_id, _status, msg, simstate->roll, simstate->pitch, simstate->yaw, simstate->xacc, simstate->yacc, simstate->zacc, simstate->xgyro, simstate->ygyro, simstate->zgyro, simstate->lat, simstate->lng);
+}
+
+/**
+ * @brief Send a simstate message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param roll [rad] Roll angle.
+ * @param pitch [rad] Pitch angle.
+ * @param yaw [rad] Yaw angle.
+ * @param xacc [m/s/s] X acceleration.
+ * @param yacc [m/s/s] Y acceleration.
+ * @param zacc [m/s/s] Z acceleration.
+ * @param xgyro [rad/s] Angular speed around X axis.
+ * @param ygyro [rad/s] Angular speed around Y axis.
+ * @param zgyro [rad/s] Angular speed around Z axis.
+ * @param lat [degE7] Latitude.
+ * @param lng [degE7] Longitude.
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_simstate_send(mavlink_channel_t chan, float roll, float pitch, float yaw, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, int32_t lat, int32_t lng)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_SIMSTATE_LEN];
+ _mav_put_float(buf, 0, roll);
+ _mav_put_float(buf, 4, pitch);
+ _mav_put_float(buf, 8, yaw);
+ _mav_put_float(buf, 12, xacc);
+ _mav_put_float(buf, 16, yacc);
+ _mav_put_float(buf, 20, zacc);
+ _mav_put_float(buf, 24, xgyro);
+ _mav_put_float(buf, 28, ygyro);
+ _mav_put_float(buf, 32, zgyro);
+ _mav_put_int32_t(buf, 36, lat);
+ _mav_put_int32_t(buf, 40, lng);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIMSTATE, buf, MAVLINK_MSG_ID_SIMSTATE_MIN_LEN, MAVLINK_MSG_ID_SIMSTATE_LEN, MAVLINK_MSG_ID_SIMSTATE_CRC);
+#else
+ mavlink_simstate_t packet;
+ packet.roll = roll;
+ packet.pitch = pitch;
+ packet.yaw = yaw;
+ packet.xacc = xacc;
+ packet.yacc = yacc;
+ packet.zacc = zacc;
+ packet.xgyro = xgyro;
+ packet.ygyro = ygyro;
+ packet.zgyro = zgyro;
+ packet.lat = lat;
+ packet.lng = lng;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIMSTATE, (const char *)&packet, MAVLINK_MSG_ID_SIMSTATE_MIN_LEN, MAVLINK_MSG_ID_SIMSTATE_LEN, MAVLINK_MSG_ID_SIMSTATE_CRC);
+#endif
+}
+
+/**
+ * @brief Send a simstate message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_simstate_send_struct(mavlink_channel_t chan, const mavlink_simstate_t* simstate)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_simstate_send(chan, simstate->roll, simstate->pitch, simstate->yaw, simstate->xacc, simstate->yacc, simstate->zacc, simstate->xgyro, simstate->ygyro, simstate->zgyro, simstate->lat, simstate->lng);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIMSTATE, (const char *)simstate, MAVLINK_MSG_ID_SIMSTATE_MIN_LEN, MAVLINK_MSG_ID_SIMSTATE_LEN, MAVLINK_MSG_ID_SIMSTATE_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_SIMSTATE_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_simstate_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float roll, float pitch, float yaw, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, int32_t lat, int32_t lng)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_float(buf, 0, roll);
+ _mav_put_float(buf, 4, pitch);
+ _mav_put_float(buf, 8, yaw);
+ _mav_put_float(buf, 12, xacc);
+ _mav_put_float(buf, 16, yacc);
+ _mav_put_float(buf, 20, zacc);
+ _mav_put_float(buf, 24, xgyro);
+ _mav_put_float(buf, 28, ygyro);
+ _mav_put_float(buf, 32, zgyro);
+ _mav_put_int32_t(buf, 36, lat);
+ _mav_put_int32_t(buf, 40, lng);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIMSTATE, buf, MAVLINK_MSG_ID_SIMSTATE_MIN_LEN, MAVLINK_MSG_ID_SIMSTATE_LEN, MAVLINK_MSG_ID_SIMSTATE_CRC);
+#else
+ mavlink_simstate_t *packet = (mavlink_simstate_t *)msgbuf;
+ packet->roll = roll;
+ packet->pitch = pitch;
+ packet->yaw = yaw;
+ packet->xacc = xacc;
+ packet->yacc = yacc;
+ packet->zacc = zacc;
+ packet->xgyro = xgyro;
+ packet->ygyro = ygyro;
+ packet->zgyro = zgyro;
+ packet->lat = lat;
+ packet->lng = lng;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIMSTATE, (const char *)packet, MAVLINK_MSG_ID_SIMSTATE_MIN_LEN, MAVLINK_MSG_ID_SIMSTATE_LEN, MAVLINK_MSG_ID_SIMSTATE_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE SIMSTATE UNPACKING
+
+
+/**
+ * @brief Get field roll from simstate message
+ *
+ * @return [rad] Roll angle.
+ */
+static inline float mavlink_msg_simstate_get_roll(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 0);
+}
+
+/**
+ * @brief Get field pitch from simstate message
+ *
+ * @return [rad] Pitch angle.
+ */
+static inline float mavlink_msg_simstate_get_pitch(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 4);
+}
+
+/**
+ * @brief Get field yaw from simstate message
+ *
+ * @return [rad] Yaw angle.
+ */
+static inline float mavlink_msg_simstate_get_yaw(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 8);
+}
+
+/**
+ * @brief Get field xacc from simstate message
+ *
+ * @return [m/s/s] X acceleration.
+ */
+static inline float mavlink_msg_simstate_get_xacc(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 12);
+}
+
+/**
+ * @brief Get field yacc from simstate message
+ *
+ * @return [m/s/s] Y acceleration.
+ */
+static inline float mavlink_msg_simstate_get_yacc(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 16);
+}
+
+/**
+ * @brief Get field zacc from simstate message
+ *
+ * @return [m/s/s] Z acceleration.
+ */
+static inline float mavlink_msg_simstate_get_zacc(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 20);
+}
+
+/**
+ * @brief Get field xgyro from simstate message
+ *
+ * @return [rad/s] Angular speed around X axis.
+ */
+static inline float mavlink_msg_simstate_get_xgyro(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 24);
+}
+
+/**
+ * @brief Get field ygyro from simstate message
+ *
+ * @return [rad/s] Angular speed around Y axis.
+ */
+static inline float mavlink_msg_simstate_get_ygyro(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 28);
+}
+
+/**
+ * @brief Get field zgyro from simstate message
+ *
+ * @return [rad/s] Angular speed around Z axis.
+ */
+static inline float mavlink_msg_simstate_get_zgyro(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 32);
+}
+
+/**
+ * @brief Get field lat from simstate message
+ *
+ * @return [degE7] Latitude.
+ */
+static inline int32_t mavlink_msg_simstate_get_lat(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_int32_t(msg, 36);
+}
+
+/**
+ * @brief Get field lng from simstate message
+ *
+ * @return [degE7] Longitude.
+ */
+static inline int32_t mavlink_msg_simstate_get_lng(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_int32_t(msg, 40);
+}
+
+/**
+ * @brief Decode a simstate message into a struct
+ *
+ * @param msg The message to decode
+ * @param simstate C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_simstate_decode(const mavlink_message_t* msg, mavlink_simstate_t* simstate)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ simstate->roll = mavlink_msg_simstate_get_roll(msg);
+ simstate->pitch = mavlink_msg_simstate_get_pitch(msg);
+ simstate->yaw = mavlink_msg_simstate_get_yaw(msg);
+ simstate->xacc = mavlink_msg_simstate_get_xacc(msg);
+ simstate->yacc = mavlink_msg_simstate_get_yacc(msg);
+ simstate->zacc = mavlink_msg_simstate_get_zacc(msg);
+ simstate->xgyro = mavlink_msg_simstate_get_xgyro(msg);
+ simstate->ygyro = mavlink_msg_simstate_get_ygyro(msg);
+ simstate->zgyro = mavlink_msg_simstate_get_zgyro(msg);
+ simstate->lat = mavlink_msg_simstate_get_lat(msg);
+ simstate->lng = mavlink_msg_simstate_get_lng(msg);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_SIMSTATE_LEN? msg->len : MAVLINK_MSG_ID_SIMSTATE_LEN;
+ memset(simstate, 0, MAVLINK_MSG_ID_SIMSTATE_LEN);
+ memcpy(simstate, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/ardupilotmega/mavlink_msg_vision_position_delta.h b/lib/main/MAVLink/ardupilotmega/mavlink_msg_vision_position_delta.h
new file mode 100644
index 00000000000..ee8db6cf182
--- /dev/null
+++ b/lib/main/MAVLink/ardupilotmega/mavlink_msg_vision_position_delta.h
@@ -0,0 +1,363 @@
+#pragma once
+// MESSAGE VISION_POSITION_DELTA PACKING
+
+#define MAVLINK_MSG_ID_VISION_POSITION_DELTA 11011
+
+
+typedef struct __mavlink_vision_position_delta_t {
+ uint64_t time_usec; /*< [us] Timestamp (synced to UNIX time or since system boot).*/
+ uint64_t time_delta_usec; /*< [us] Time since the last reported camera frame.*/
+ float angle_delta[3]; /*< [rad] Defines a rotation vector [roll, pitch, yaw] to the current MAV_FRAME_BODY_FRD from the previous MAV_FRAME_BODY_FRD.*/
+ float position_delta[3]; /*< [m] Change in position to the current MAV_FRAME_BODY_FRD from the previous FRAME_BODY_FRD rotated to the current MAV_FRAME_BODY_FRD.*/
+ float confidence; /*< [%] Normalised confidence value from 0 to 100.*/
+} mavlink_vision_position_delta_t;
+
+#define MAVLINK_MSG_ID_VISION_POSITION_DELTA_LEN 44
+#define MAVLINK_MSG_ID_VISION_POSITION_DELTA_MIN_LEN 44
+#define MAVLINK_MSG_ID_11011_LEN 44
+#define MAVLINK_MSG_ID_11011_MIN_LEN 44
+
+#define MAVLINK_MSG_ID_VISION_POSITION_DELTA_CRC 106
+#define MAVLINK_MSG_ID_11011_CRC 106
+
+#define MAVLINK_MSG_VISION_POSITION_DELTA_FIELD_ANGLE_DELTA_LEN 3
+#define MAVLINK_MSG_VISION_POSITION_DELTA_FIELD_POSITION_DELTA_LEN 3
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_VISION_POSITION_DELTA { \
+ 11011, \
+ "VISION_POSITION_DELTA", \
+ 5, \
+ { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_vision_position_delta_t, time_usec) }, \
+ { "time_delta_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_vision_position_delta_t, time_delta_usec) }, \
+ { "angle_delta", NULL, MAVLINK_TYPE_FLOAT, 3, 16, offsetof(mavlink_vision_position_delta_t, angle_delta) }, \
+ { "position_delta", NULL, MAVLINK_TYPE_FLOAT, 3, 28, offsetof(mavlink_vision_position_delta_t, position_delta) }, \
+ { "confidence", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_vision_position_delta_t, confidence) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_VISION_POSITION_DELTA { \
+ "VISION_POSITION_DELTA", \
+ 5, \
+ { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_vision_position_delta_t, time_usec) }, \
+ { "time_delta_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_vision_position_delta_t, time_delta_usec) }, \
+ { "angle_delta", NULL, MAVLINK_TYPE_FLOAT, 3, 16, offsetof(mavlink_vision_position_delta_t, angle_delta) }, \
+ { "position_delta", NULL, MAVLINK_TYPE_FLOAT, 3, 28, offsetof(mavlink_vision_position_delta_t, position_delta) }, \
+ { "confidence", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_vision_position_delta_t, confidence) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a vision_position_delta 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 time_usec [us] Timestamp (synced to UNIX time or since system boot).
+ * @param time_delta_usec [us] Time since the last reported camera frame.
+ * @param angle_delta [rad] Defines a rotation vector [roll, pitch, yaw] to the current MAV_FRAME_BODY_FRD from the previous MAV_FRAME_BODY_FRD.
+ * @param position_delta [m] Change in position to the current MAV_FRAME_BODY_FRD from the previous FRAME_BODY_FRD rotated to the current MAV_FRAME_BODY_FRD.
+ * @param confidence [%] Normalised confidence value from 0 to 100.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_vision_position_delta_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint64_t time_usec, uint64_t time_delta_usec, const float *angle_delta, const float *position_delta, float confidence)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_VISION_POSITION_DELTA_LEN];
+ _mav_put_uint64_t(buf, 0, time_usec);
+ _mav_put_uint64_t(buf, 8, time_delta_usec);
+ _mav_put_float(buf, 40, confidence);
+ _mav_put_float_array(buf, 16, angle_delta, 3);
+ _mav_put_float_array(buf, 28, position_delta, 3);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VISION_POSITION_DELTA_LEN);
+#else
+ mavlink_vision_position_delta_t packet;
+ packet.time_usec = time_usec;
+ packet.time_delta_usec = time_delta_usec;
+ packet.confidence = confidence;
+ mav_array_assign_float(packet.angle_delta, angle_delta, 3);
+ mav_array_assign_float(packet.position_delta, position_delta, 3);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VISION_POSITION_DELTA_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_VISION_POSITION_DELTA;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_VISION_POSITION_DELTA_MIN_LEN, MAVLINK_MSG_ID_VISION_POSITION_DELTA_LEN, MAVLINK_MSG_ID_VISION_POSITION_DELTA_CRC);
+}
+
+/**
+ * @brief Pack a vision_position_delta 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 time_usec [us] Timestamp (synced to UNIX time or since system boot).
+ * @param time_delta_usec [us] Time since the last reported camera frame.
+ * @param angle_delta [rad] Defines a rotation vector [roll, pitch, yaw] to the current MAV_FRAME_BODY_FRD from the previous MAV_FRAME_BODY_FRD.
+ * @param position_delta [m] Change in position to the current MAV_FRAME_BODY_FRD from the previous FRAME_BODY_FRD rotated to the current MAV_FRAME_BODY_FRD.
+ * @param confidence [%] Normalised confidence value from 0 to 100.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_vision_position_delta_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ uint64_t time_usec, uint64_t time_delta_usec, const float *angle_delta, const float *position_delta, float confidence)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_VISION_POSITION_DELTA_LEN];
+ _mav_put_uint64_t(buf, 0, time_usec);
+ _mav_put_uint64_t(buf, 8, time_delta_usec);
+ _mav_put_float(buf, 40, confidence);
+ _mav_put_float_array(buf, 16, angle_delta, 3);
+ _mav_put_float_array(buf, 28, position_delta, 3);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VISION_POSITION_DELTA_LEN);
+#else
+ mavlink_vision_position_delta_t packet;
+ packet.time_usec = time_usec;
+ packet.time_delta_usec = time_delta_usec;
+ packet.confidence = confidence;
+ mav_array_memcpy(packet.angle_delta, angle_delta, sizeof(float)*3);
+ mav_array_memcpy(packet.position_delta, position_delta, sizeof(float)*3);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VISION_POSITION_DELTA_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_VISION_POSITION_DELTA;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_VISION_POSITION_DELTA_MIN_LEN, MAVLINK_MSG_ID_VISION_POSITION_DELTA_LEN, MAVLINK_MSG_ID_VISION_POSITION_DELTA_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_VISION_POSITION_DELTA_MIN_LEN, MAVLINK_MSG_ID_VISION_POSITION_DELTA_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a vision_position_delta 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 time_usec [us] Timestamp (synced to UNIX time or since system boot).
+ * @param time_delta_usec [us] Time since the last reported camera frame.
+ * @param angle_delta [rad] Defines a rotation vector [roll, pitch, yaw] to the current MAV_FRAME_BODY_FRD from the previous MAV_FRAME_BODY_FRD.
+ * @param position_delta [m] Change in position to the current MAV_FRAME_BODY_FRD from the previous FRAME_BODY_FRD rotated to the current MAV_FRAME_BODY_FRD.
+ * @param confidence [%] Normalised confidence value from 0 to 100.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_vision_position_delta_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint64_t time_usec,uint64_t time_delta_usec,const float *angle_delta,const float *position_delta,float confidence)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_VISION_POSITION_DELTA_LEN];
+ _mav_put_uint64_t(buf, 0, time_usec);
+ _mav_put_uint64_t(buf, 8, time_delta_usec);
+ _mav_put_float(buf, 40, confidence);
+ _mav_put_float_array(buf, 16, angle_delta, 3);
+ _mav_put_float_array(buf, 28, position_delta, 3);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VISION_POSITION_DELTA_LEN);
+#else
+ mavlink_vision_position_delta_t packet;
+ packet.time_usec = time_usec;
+ packet.time_delta_usec = time_delta_usec;
+ packet.confidence = confidence;
+ mav_array_assign_float(packet.angle_delta, angle_delta, 3);
+ mav_array_assign_float(packet.position_delta, position_delta, 3);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VISION_POSITION_DELTA_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_VISION_POSITION_DELTA;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_VISION_POSITION_DELTA_MIN_LEN, MAVLINK_MSG_ID_VISION_POSITION_DELTA_LEN, MAVLINK_MSG_ID_VISION_POSITION_DELTA_CRC);
+}
+
+/**
+ * @brief Encode a vision_position_delta 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 vision_position_delta C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_vision_position_delta_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_vision_position_delta_t* vision_position_delta)
+{
+ return mavlink_msg_vision_position_delta_pack(system_id, component_id, msg, vision_position_delta->time_usec, vision_position_delta->time_delta_usec, vision_position_delta->angle_delta, vision_position_delta->position_delta, vision_position_delta->confidence);
+}
+
+/**
+ * @brief Encode a vision_position_delta 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 vision_position_delta C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_vision_position_delta_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_vision_position_delta_t* vision_position_delta)
+{
+ return mavlink_msg_vision_position_delta_pack_chan(system_id, component_id, chan, msg, vision_position_delta->time_usec, vision_position_delta->time_delta_usec, vision_position_delta->angle_delta, vision_position_delta->position_delta, vision_position_delta->confidence);
+}
+
+/**
+ * @brief Encode a vision_position_delta 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 vision_position_delta C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_vision_position_delta_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_vision_position_delta_t* vision_position_delta)
+{
+ return mavlink_msg_vision_position_delta_pack_status(system_id, component_id, _status, msg, vision_position_delta->time_usec, vision_position_delta->time_delta_usec, vision_position_delta->angle_delta, vision_position_delta->position_delta, vision_position_delta->confidence);
+}
+
+/**
+ * @brief Send a vision_position_delta message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param time_usec [us] Timestamp (synced to UNIX time or since system boot).
+ * @param time_delta_usec [us] Time since the last reported camera frame.
+ * @param angle_delta [rad] Defines a rotation vector [roll, pitch, yaw] to the current MAV_FRAME_BODY_FRD from the previous MAV_FRAME_BODY_FRD.
+ * @param position_delta [m] Change in position to the current MAV_FRAME_BODY_FRD from the previous FRAME_BODY_FRD rotated to the current MAV_FRAME_BODY_FRD.
+ * @param confidence [%] Normalised confidence value from 0 to 100.
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_vision_position_delta_send(mavlink_channel_t chan, uint64_t time_usec, uint64_t time_delta_usec, const float *angle_delta, const float *position_delta, float confidence)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_VISION_POSITION_DELTA_LEN];
+ _mav_put_uint64_t(buf, 0, time_usec);
+ _mav_put_uint64_t(buf, 8, time_delta_usec);
+ _mav_put_float(buf, 40, confidence);
+ _mav_put_float_array(buf, 16, angle_delta, 3);
+ _mav_put_float_array(buf, 28, position_delta, 3);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_POSITION_DELTA, buf, MAVLINK_MSG_ID_VISION_POSITION_DELTA_MIN_LEN, MAVLINK_MSG_ID_VISION_POSITION_DELTA_LEN, MAVLINK_MSG_ID_VISION_POSITION_DELTA_CRC);
+#else
+ mavlink_vision_position_delta_t packet;
+ packet.time_usec = time_usec;
+ packet.time_delta_usec = time_delta_usec;
+ packet.confidence = confidence;
+ mav_array_assign_float(packet.angle_delta, angle_delta, 3);
+ mav_array_assign_float(packet.position_delta, position_delta, 3);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_POSITION_DELTA, (const char *)&packet, MAVLINK_MSG_ID_VISION_POSITION_DELTA_MIN_LEN, MAVLINK_MSG_ID_VISION_POSITION_DELTA_LEN, MAVLINK_MSG_ID_VISION_POSITION_DELTA_CRC);
+#endif
+}
+
+/**
+ * @brief Send a vision_position_delta message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_vision_position_delta_send_struct(mavlink_channel_t chan, const mavlink_vision_position_delta_t* vision_position_delta)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_vision_position_delta_send(chan, vision_position_delta->time_usec, vision_position_delta->time_delta_usec, vision_position_delta->angle_delta, vision_position_delta->position_delta, vision_position_delta->confidence);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_POSITION_DELTA, (const char *)vision_position_delta, MAVLINK_MSG_ID_VISION_POSITION_DELTA_MIN_LEN, MAVLINK_MSG_ID_VISION_POSITION_DELTA_LEN, MAVLINK_MSG_ID_VISION_POSITION_DELTA_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_VISION_POSITION_DELTA_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_vision_position_delta_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint64_t time_delta_usec, const float *angle_delta, const float *position_delta, float confidence)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint64_t(buf, 0, time_usec);
+ _mav_put_uint64_t(buf, 8, time_delta_usec);
+ _mav_put_float(buf, 40, confidence);
+ _mav_put_float_array(buf, 16, angle_delta, 3);
+ _mav_put_float_array(buf, 28, position_delta, 3);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_POSITION_DELTA, buf, MAVLINK_MSG_ID_VISION_POSITION_DELTA_MIN_LEN, MAVLINK_MSG_ID_VISION_POSITION_DELTA_LEN, MAVLINK_MSG_ID_VISION_POSITION_DELTA_CRC);
+#else
+ mavlink_vision_position_delta_t *packet = (mavlink_vision_position_delta_t *)msgbuf;
+ packet->time_usec = time_usec;
+ packet->time_delta_usec = time_delta_usec;
+ packet->confidence = confidence;
+ mav_array_assign_float(packet->angle_delta, angle_delta, 3);
+ mav_array_assign_float(packet->position_delta, position_delta, 3);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_POSITION_DELTA, (const char *)packet, MAVLINK_MSG_ID_VISION_POSITION_DELTA_MIN_LEN, MAVLINK_MSG_ID_VISION_POSITION_DELTA_LEN, MAVLINK_MSG_ID_VISION_POSITION_DELTA_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE VISION_POSITION_DELTA UNPACKING
+
+
+/**
+ * @brief Get field time_usec from vision_position_delta message
+ *
+ * @return [us] Timestamp (synced to UNIX time or since system boot).
+ */
+static inline uint64_t mavlink_msg_vision_position_delta_get_time_usec(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint64_t(msg, 0);
+}
+
+/**
+ * @brief Get field time_delta_usec from vision_position_delta message
+ *
+ * @return [us] Time since the last reported camera frame.
+ */
+static inline uint64_t mavlink_msg_vision_position_delta_get_time_delta_usec(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint64_t(msg, 8);
+}
+
+/**
+ * @brief Get field angle_delta from vision_position_delta message
+ *
+ * @return [rad] Defines a rotation vector [roll, pitch, yaw] to the current MAV_FRAME_BODY_FRD from the previous MAV_FRAME_BODY_FRD.
+ */
+static inline uint16_t mavlink_msg_vision_position_delta_get_angle_delta(const mavlink_message_t* msg, float *angle_delta)
+{
+ return _MAV_RETURN_float_array(msg, angle_delta, 3, 16);
+}
+
+/**
+ * @brief Get field position_delta from vision_position_delta message
+ *
+ * @return [m] Change in position to the current MAV_FRAME_BODY_FRD from the previous FRAME_BODY_FRD rotated to the current MAV_FRAME_BODY_FRD.
+ */
+static inline uint16_t mavlink_msg_vision_position_delta_get_position_delta(const mavlink_message_t* msg, float *position_delta)
+{
+ return _MAV_RETURN_float_array(msg, position_delta, 3, 28);
+}
+
+/**
+ * @brief Get field confidence from vision_position_delta message
+ *
+ * @return [%] Normalised confidence value from 0 to 100.
+ */
+static inline float mavlink_msg_vision_position_delta_get_confidence(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 40);
+}
+
+/**
+ * @brief Decode a vision_position_delta message into a struct
+ *
+ * @param msg The message to decode
+ * @param vision_position_delta C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_vision_position_delta_decode(const mavlink_message_t* msg, mavlink_vision_position_delta_t* vision_position_delta)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ vision_position_delta->time_usec = mavlink_msg_vision_position_delta_get_time_usec(msg);
+ vision_position_delta->time_delta_usec = mavlink_msg_vision_position_delta_get_time_delta_usec(msg);
+ mavlink_msg_vision_position_delta_get_angle_delta(msg, vision_position_delta->angle_delta);
+ mavlink_msg_vision_position_delta_get_position_delta(msg, vision_position_delta->position_delta);
+ vision_position_delta->confidence = mavlink_msg_vision_position_delta_get_confidence(msg);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_VISION_POSITION_DELTA_LEN? msg->len : MAVLINK_MSG_ID_VISION_POSITION_DELTA_LEN;
+ memset(vision_position_delta, 0, MAVLINK_MSG_ID_VISION_POSITION_DELTA_LEN);
+ memcpy(vision_position_delta, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/ardupilotmega/mavlink_msg_water_depth.h b/lib/main/MAVLink/ardupilotmega/mavlink_msg_water_depth.h
new file mode 100644
index 00000000000..fd5a6e6c8ee
--- /dev/null
+++ b/lib/main/MAVLink/ardupilotmega/mavlink_msg_water_depth.h
@@ -0,0 +1,540 @@
+#pragma once
+// MESSAGE WATER_DEPTH PACKING
+
+#define MAVLINK_MSG_ID_WATER_DEPTH 11038
+
+
+typedef struct __mavlink_water_depth_t {
+ uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot)*/
+ int32_t lat; /*< [degE7] Latitude*/
+ int32_t lng; /*< [degE7] Longitude*/
+ float alt; /*< [m] Altitude (MSL) of vehicle*/
+ float roll; /*< [rad] Roll angle*/
+ float pitch; /*< [rad] Pitch angle*/
+ float yaw; /*< [rad] Yaw angle*/
+ float distance; /*< [m] Distance (uncorrected)*/
+ float temperature; /*< [degC] Water temperature*/
+ uint8_t id; /*< Onboard ID of the sensor*/
+ uint8_t healthy; /*< Sensor data healthy (0=unhealthy, 1=healthy)*/
+} mavlink_water_depth_t;
+
+#define MAVLINK_MSG_ID_WATER_DEPTH_LEN 38
+#define MAVLINK_MSG_ID_WATER_DEPTH_MIN_LEN 38
+#define MAVLINK_MSG_ID_11038_LEN 38
+#define MAVLINK_MSG_ID_11038_MIN_LEN 38
+
+#define MAVLINK_MSG_ID_WATER_DEPTH_CRC 47
+#define MAVLINK_MSG_ID_11038_CRC 47
+
+
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_WATER_DEPTH { \
+ 11038, \
+ "WATER_DEPTH", \
+ 11, \
+ { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_water_depth_t, time_boot_ms) }, \
+ { "id", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_water_depth_t, id) }, \
+ { "healthy", NULL, MAVLINK_TYPE_UINT8_T, 0, 37, offsetof(mavlink_water_depth_t, healthy) }, \
+ { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_water_depth_t, lat) }, \
+ { "lng", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_water_depth_t, lng) }, \
+ { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_water_depth_t, alt) }, \
+ { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_water_depth_t, roll) }, \
+ { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_water_depth_t, pitch) }, \
+ { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_water_depth_t, yaw) }, \
+ { "distance", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_water_depth_t, distance) }, \
+ { "temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_water_depth_t, temperature) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_WATER_DEPTH { \
+ "WATER_DEPTH", \
+ 11, \
+ { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_water_depth_t, time_boot_ms) }, \
+ { "id", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_water_depth_t, id) }, \
+ { "healthy", NULL, MAVLINK_TYPE_UINT8_T, 0, 37, offsetof(mavlink_water_depth_t, healthy) }, \
+ { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_water_depth_t, lat) }, \
+ { "lng", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_water_depth_t, lng) }, \
+ { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_water_depth_t, alt) }, \
+ { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_water_depth_t, roll) }, \
+ { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_water_depth_t, pitch) }, \
+ { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_water_depth_t, yaw) }, \
+ { "distance", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_water_depth_t, distance) }, \
+ { "temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_water_depth_t, temperature) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a water_depth 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 time_boot_ms [ms] Timestamp (time since system boot)
+ * @param id Onboard ID of the sensor
+ * @param healthy Sensor data healthy (0=unhealthy, 1=healthy)
+ * @param lat [degE7] Latitude
+ * @param lng [degE7] Longitude
+ * @param alt [m] Altitude (MSL) of vehicle
+ * @param roll [rad] Roll angle
+ * @param pitch [rad] Pitch angle
+ * @param yaw [rad] Yaw angle
+ * @param distance [m] Distance (uncorrected)
+ * @param temperature [degC] Water temperature
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_water_depth_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint32_t time_boot_ms, uint8_t id, uint8_t healthy, int32_t lat, int32_t lng, float alt, float roll, float pitch, float yaw, float distance, float temperature)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_WATER_DEPTH_LEN];
+ _mav_put_uint32_t(buf, 0, time_boot_ms);
+ _mav_put_int32_t(buf, 4, lat);
+ _mav_put_int32_t(buf, 8, lng);
+ _mav_put_float(buf, 12, alt);
+ _mav_put_float(buf, 16, roll);
+ _mav_put_float(buf, 20, pitch);
+ _mav_put_float(buf, 24, yaw);
+ _mav_put_float(buf, 28, distance);
+ _mav_put_float(buf, 32, temperature);
+ _mav_put_uint8_t(buf, 36, id);
+ _mav_put_uint8_t(buf, 37, healthy);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_WATER_DEPTH_LEN);
+#else
+ mavlink_water_depth_t packet;
+ packet.time_boot_ms = time_boot_ms;
+ packet.lat = lat;
+ packet.lng = lng;
+ packet.alt = alt;
+ packet.roll = roll;
+ packet.pitch = pitch;
+ packet.yaw = yaw;
+ packet.distance = distance;
+ packet.temperature = temperature;
+ packet.id = id;
+ packet.healthy = healthy;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_WATER_DEPTH_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_WATER_DEPTH;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_WATER_DEPTH_MIN_LEN, MAVLINK_MSG_ID_WATER_DEPTH_LEN, MAVLINK_MSG_ID_WATER_DEPTH_CRC);
+}
+
+/**
+ * @brief Pack a water_depth 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 time_boot_ms [ms] Timestamp (time since system boot)
+ * @param id Onboard ID of the sensor
+ * @param healthy Sensor data healthy (0=unhealthy, 1=healthy)
+ * @param lat [degE7] Latitude
+ * @param lng [degE7] Longitude
+ * @param alt [m] Altitude (MSL) of vehicle
+ * @param roll [rad] Roll angle
+ * @param pitch [rad] Pitch angle
+ * @param yaw [rad] Yaw angle
+ * @param distance [m] Distance (uncorrected)
+ * @param temperature [degC] Water temperature
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_water_depth_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ uint32_t time_boot_ms, uint8_t id, uint8_t healthy, int32_t lat, int32_t lng, float alt, float roll, float pitch, float yaw, float distance, float temperature)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_WATER_DEPTH_LEN];
+ _mav_put_uint32_t(buf, 0, time_boot_ms);
+ _mav_put_int32_t(buf, 4, lat);
+ _mav_put_int32_t(buf, 8, lng);
+ _mav_put_float(buf, 12, alt);
+ _mav_put_float(buf, 16, roll);
+ _mav_put_float(buf, 20, pitch);
+ _mav_put_float(buf, 24, yaw);
+ _mav_put_float(buf, 28, distance);
+ _mav_put_float(buf, 32, temperature);
+ _mav_put_uint8_t(buf, 36, id);
+ _mav_put_uint8_t(buf, 37, healthy);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_WATER_DEPTH_LEN);
+#else
+ mavlink_water_depth_t packet;
+ packet.time_boot_ms = time_boot_ms;
+ packet.lat = lat;
+ packet.lng = lng;
+ packet.alt = alt;
+ packet.roll = roll;
+ packet.pitch = pitch;
+ packet.yaw = yaw;
+ packet.distance = distance;
+ packet.temperature = temperature;
+ packet.id = id;
+ packet.healthy = healthy;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_WATER_DEPTH_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_WATER_DEPTH;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_WATER_DEPTH_MIN_LEN, MAVLINK_MSG_ID_WATER_DEPTH_LEN, MAVLINK_MSG_ID_WATER_DEPTH_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_WATER_DEPTH_MIN_LEN, MAVLINK_MSG_ID_WATER_DEPTH_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a water_depth 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 time_boot_ms [ms] Timestamp (time since system boot)
+ * @param id Onboard ID of the sensor
+ * @param healthy Sensor data healthy (0=unhealthy, 1=healthy)
+ * @param lat [degE7] Latitude
+ * @param lng [degE7] Longitude
+ * @param alt [m] Altitude (MSL) of vehicle
+ * @param roll [rad] Roll angle
+ * @param pitch [rad] Pitch angle
+ * @param yaw [rad] Yaw angle
+ * @param distance [m] Distance (uncorrected)
+ * @param temperature [degC] Water temperature
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_water_depth_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint32_t time_boot_ms,uint8_t id,uint8_t healthy,int32_t lat,int32_t lng,float alt,float roll,float pitch,float yaw,float distance,float temperature)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_WATER_DEPTH_LEN];
+ _mav_put_uint32_t(buf, 0, time_boot_ms);
+ _mav_put_int32_t(buf, 4, lat);
+ _mav_put_int32_t(buf, 8, lng);
+ _mav_put_float(buf, 12, alt);
+ _mav_put_float(buf, 16, roll);
+ _mav_put_float(buf, 20, pitch);
+ _mav_put_float(buf, 24, yaw);
+ _mav_put_float(buf, 28, distance);
+ _mav_put_float(buf, 32, temperature);
+ _mav_put_uint8_t(buf, 36, id);
+ _mav_put_uint8_t(buf, 37, healthy);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_WATER_DEPTH_LEN);
+#else
+ mavlink_water_depth_t packet;
+ packet.time_boot_ms = time_boot_ms;
+ packet.lat = lat;
+ packet.lng = lng;
+ packet.alt = alt;
+ packet.roll = roll;
+ packet.pitch = pitch;
+ packet.yaw = yaw;
+ packet.distance = distance;
+ packet.temperature = temperature;
+ packet.id = id;
+ packet.healthy = healthy;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_WATER_DEPTH_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_WATER_DEPTH;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_WATER_DEPTH_MIN_LEN, MAVLINK_MSG_ID_WATER_DEPTH_LEN, MAVLINK_MSG_ID_WATER_DEPTH_CRC);
+}
+
+/**
+ * @brief Encode a water_depth 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 water_depth C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_water_depth_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_water_depth_t* water_depth)
+{
+ return mavlink_msg_water_depth_pack(system_id, component_id, msg, water_depth->time_boot_ms, water_depth->id, water_depth->healthy, water_depth->lat, water_depth->lng, water_depth->alt, water_depth->roll, water_depth->pitch, water_depth->yaw, water_depth->distance, water_depth->temperature);
+}
+
+/**
+ * @brief Encode a water_depth 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 water_depth C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_water_depth_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_water_depth_t* water_depth)
+{
+ return mavlink_msg_water_depth_pack_chan(system_id, component_id, chan, msg, water_depth->time_boot_ms, water_depth->id, water_depth->healthy, water_depth->lat, water_depth->lng, water_depth->alt, water_depth->roll, water_depth->pitch, water_depth->yaw, water_depth->distance, water_depth->temperature);
+}
+
+/**
+ * @brief Encode a water_depth 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 water_depth C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_water_depth_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_water_depth_t* water_depth)
+{
+ return mavlink_msg_water_depth_pack_status(system_id, component_id, _status, msg, water_depth->time_boot_ms, water_depth->id, water_depth->healthy, water_depth->lat, water_depth->lng, water_depth->alt, water_depth->roll, water_depth->pitch, water_depth->yaw, water_depth->distance, water_depth->temperature);
+}
+
+/**
+ * @brief Send a water_depth message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param time_boot_ms [ms] Timestamp (time since system boot)
+ * @param id Onboard ID of the sensor
+ * @param healthy Sensor data healthy (0=unhealthy, 1=healthy)
+ * @param lat [degE7] Latitude
+ * @param lng [degE7] Longitude
+ * @param alt [m] Altitude (MSL) of vehicle
+ * @param roll [rad] Roll angle
+ * @param pitch [rad] Pitch angle
+ * @param yaw [rad] Yaw angle
+ * @param distance [m] Distance (uncorrected)
+ * @param temperature [degC] Water temperature
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_water_depth_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t id, uint8_t healthy, int32_t lat, int32_t lng, float alt, float roll, float pitch, float yaw, float distance, float temperature)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_WATER_DEPTH_LEN];
+ _mav_put_uint32_t(buf, 0, time_boot_ms);
+ _mav_put_int32_t(buf, 4, lat);
+ _mav_put_int32_t(buf, 8, lng);
+ _mav_put_float(buf, 12, alt);
+ _mav_put_float(buf, 16, roll);
+ _mav_put_float(buf, 20, pitch);
+ _mav_put_float(buf, 24, yaw);
+ _mav_put_float(buf, 28, distance);
+ _mav_put_float(buf, 32, temperature);
+ _mav_put_uint8_t(buf, 36, id);
+ _mav_put_uint8_t(buf, 37, healthy);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATER_DEPTH, buf, MAVLINK_MSG_ID_WATER_DEPTH_MIN_LEN, MAVLINK_MSG_ID_WATER_DEPTH_LEN, MAVLINK_MSG_ID_WATER_DEPTH_CRC);
+#else
+ mavlink_water_depth_t packet;
+ packet.time_boot_ms = time_boot_ms;
+ packet.lat = lat;
+ packet.lng = lng;
+ packet.alt = alt;
+ packet.roll = roll;
+ packet.pitch = pitch;
+ packet.yaw = yaw;
+ packet.distance = distance;
+ packet.temperature = temperature;
+ packet.id = id;
+ packet.healthy = healthy;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATER_DEPTH, (const char *)&packet, MAVLINK_MSG_ID_WATER_DEPTH_MIN_LEN, MAVLINK_MSG_ID_WATER_DEPTH_LEN, MAVLINK_MSG_ID_WATER_DEPTH_CRC);
+#endif
+}
+
+/**
+ * @brief Send a water_depth message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_water_depth_send_struct(mavlink_channel_t chan, const mavlink_water_depth_t* water_depth)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_water_depth_send(chan, water_depth->time_boot_ms, water_depth->id, water_depth->healthy, water_depth->lat, water_depth->lng, water_depth->alt, water_depth->roll, water_depth->pitch, water_depth->yaw, water_depth->distance, water_depth->temperature);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATER_DEPTH, (const char *)water_depth, MAVLINK_MSG_ID_WATER_DEPTH_MIN_LEN, MAVLINK_MSG_ID_WATER_DEPTH_LEN, MAVLINK_MSG_ID_WATER_DEPTH_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_WATER_DEPTH_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_water_depth_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t id, uint8_t healthy, int32_t lat, int32_t lng, float alt, float roll, float pitch, float yaw, float distance, float temperature)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint32_t(buf, 0, time_boot_ms);
+ _mav_put_int32_t(buf, 4, lat);
+ _mav_put_int32_t(buf, 8, lng);
+ _mav_put_float(buf, 12, alt);
+ _mav_put_float(buf, 16, roll);
+ _mav_put_float(buf, 20, pitch);
+ _mav_put_float(buf, 24, yaw);
+ _mav_put_float(buf, 28, distance);
+ _mav_put_float(buf, 32, temperature);
+ _mav_put_uint8_t(buf, 36, id);
+ _mav_put_uint8_t(buf, 37, healthy);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATER_DEPTH, buf, MAVLINK_MSG_ID_WATER_DEPTH_MIN_LEN, MAVLINK_MSG_ID_WATER_DEPTH_LEN, MAVLINK_MSG_ID_WATER_DEPTH_CRC);
+#else
+ mavlink_water_depth_t *packet = (mavlink_water_depth_t *)msgbuf;
+ packet->time_boot_ms = time_boot_ms;
+ packet->lat = lat;
+ packet->lng = lng;
+ packet->alt = alt;
+ packet->roll = roll;
+ packet->pitch = pitch;
+ packet->yaw = yaw;
+ packet->distance = distance;
+ packet->temperature = temperature;
+ packet->id = id;
+ packet->healthy = healthy;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WATER_DEPTH, (const char *)packet, MAVLINK_MSG_ID_WATER_DEPTH_MIN_LEN, MAVLINK_MSG_ID_WATER_DEPTH_LEN, MAVLINK_MSG_ID_WATER_DEPTH_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE WATER_DEPTH UNPACKING
+
+
+/**
+ * @brief Get field time_boot_ms from water_depth message
+ *
+ * @return [ms] Timestamp (time since system boot)
+ */
+static inline uint32_t mavlink_msg_water_depth_get_time_boot_ms(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint32_t(msg, 0);
+}
+
+/**
+ * @brief Get field id from water_depth message
+ *
+ * @return Onboard ID of the sensor
+ */
+static inline uint8_t mavlink_msg_water_depth_get_id(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 36);
+}
+
+/**
+ * @brief Get field healthy from water_depth message
+ *
+ * @return Sensor data healthy (0=unhealthy, 1=healthy)
+ */
+static inline uint8_t mavlink_msg_water_depth_get_healthy(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 37);
+}
+
+/**
+ * @brief Get field lat from water_depth message
+ *
+ * @return [degE7] Latitude
+ */
+static inline int32_t mavlink_msg_water_depth_get_lat(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_int32_t(msg, 4);
+}
+
+/**
+ * @brief Get field lng from water_depth message
+ *
+ * @return [degE7] Longitude
+ */
+static inline int32_t mavlink_msg_water_depth_get_lng(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_int32_t(msg, 8);
+}
+
+/**
+ * @brief Get field alt from water_depth message
+ *
+ * @return [m] Altitude (MSL) of vehicle
+ */
+static inline float mavlink_msg_water_depth_get_alt(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 12);
+}
+
+/**
+ * @brief Get field roll from water_depth message
+ *
+ * @return [rad] Roll angle
+ */
+static inline float mavlink_msg_water_depth_get_roll(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 16);
+}
+
+/**
+ * @brief Get field pitch from water_depth message
+ *
+ * @return [rad] Pitch angle
+ */
+static inline float mavlink_msg_water_depth_get_pitch(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 20);
+}
+
+/**
+ * @brief Get field yaw from water_depth message
+ *
+ * @return [rad] Yaw angle
+ */
+static inline float mavlink_msg_water_depth_get_yaw(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 24);
+}
+
+/**
+ * @brief Get field distance from water_depth message
+ *
+ * @return [m] Distance (uncorrected)
+ */
+static inline float mavlink_msg_water_depth_get_distance(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 28);
+}
+
+/**
+ * @brief Get field temperature from water_depth message
+ *
+ * @return [degC] Water temperature
+ */
+static inline float mavlink_msg_water_depth_get_temperature(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 32);
+}
+
+/**
+ * @brief Decode a water_depth message into a struct
+ *
+ * @param msg The message to decode
+ * @param water_depth C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_water_depth_decode(const mavlink_message_t* msg, mavlink_water_depth_t* water_depth)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ water_depth->time_boot_ms = mavlink_msg_water_depth_get_time_boot_ms(msg);
+ water_depth->lat = mavlink_msg_water_depth_get_lat(msg);
+ water_depth->lng = mavlink_msg_water_depth_get_lng(msg);
+ water_depth->alt = mavlink_msg_water_depth_get_alt(msg);
+ water_depth->roll = mavlink_msg_water_depth_get_roll(msg);
+ water_depth->pitch = mavlink_msg_water_depth_get_pitch(msg);
+ water_depth->yaw = mavlink_msg_water_depth_get_yaw(msg);
+ water_depth->distance = mavlink_msg_water_depth_get_distance(msg);
+ water_depth->temperature = mavlink_msg_water_depth_get_temperature(msg);
+ water_depth->id = mavlink_msg_water_depth_get_id(msg);
+ water_depth->healthy = mavlink_msg_water_depth_get_healthy(msg);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_WATER_DEPTH_LEN? msg->len : MAVLINK_MSG_ID_WATER_DEPTH_LEN;
+ memset(water_depth, 0, MAVLINK_MSG_ID_WATER_DEPTH_LEN);
+ memcpy(water_depth, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/ardupilotmega/mavlink_msg_wind.h b/lib/main/MAVLink/ardupilotmega/mavlink_msg_wind.h
new file mode 100644
index 00000000000..92d51f12af3
--- /dev/null
+++ b/lib/main/MAVLink/ardupilotmega/mavlink_msg_wind.h
@@ -0,0 +1,316 @@
+#pragma once
+// MESSAGE WIND PACKING
+
+#define MAVLINK_MSG_ID_WIND 168
+
+
+typedef struct __mavlink_wind_t {
+ float direction; /*< [deg] Wind direction (that wind is coming from).*/
+ float speed; /*< [m/s] Wind speed in ground plane.*/
+ float speed_z; /*< [m/s] Vertical wind speed.*/
+} mavlink_wind_t;
+
+#define MAVLINK_MSG_ID_WIND_LEN 12
+#define MAVLINK_MSG_ID_WIND_MIN_LEN 12
+#define MAVLINK_MSG_ID_168_LEN 12
+#define MAVLINK_MSG_ID_168_MIN_LEN 12
+
+#define MAVLINK_MSG_ID_WIND_CRC 1
+#define MAVLINK_MSG_ID_168_CRC 1
+
+
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_WIND { \
+ 168, \
+ "WIND", \
+ 3, \
+ { { "direction", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_wind_t, direction) }, \
+ { "speed", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_wind_t, speed) }, \
+ { "speed_z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_wind_t, speed_z) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_WIND { \
+ "WIND", \
+ 3, \
+ { { "direction", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_wind_t, direction) }, \
+ { "speed", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_wind_t, speed) }, \
+ { "speed_z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_wind_t, speed_z) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a wind 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 direction [deg] Wind direction (that wind is coming from).
+ * @param speed [m/s] Wind speed in ground plane.
+ * @param speed_z [m/s] Vertical wind speed.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_wind_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ float direction, float speed, float speed_z)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_WIND_LEN];
+ _mav_put_float(buf, 0, direction);
+ _mav_put_float(buf, 4, speed);
+ _mav_put_float(buf, 8, speed_z);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_WIND_LEN);
+#else
+ mavlink_wind_t packet;
+ packet.direction = direction;
+ packet.speed = speed;
+ packet.speed_z = speed_z;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_WIND_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_WIND;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_WIND_MIN_LEN, MAVLINK_MSG_ID_WIND_LEN, MAVLINK_MSG_ID_WIND_CRC);
+}
+
+/**
+ * @brief Pack a wind 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 direction [deg] Wind direction (that wind is coming from).
+ * @param speed [m/s] Wind speed in ground plane.
+ * @param speed_z [m/s] Vertical wind speed.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_wind_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ float direction, float speed, float speed_z)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_WIND_LEN];
+ _mav_put_float(buf, 0, direction);
+ _mav_put_float(buf, 4, speed);
+ _mav_put_float(buf, 8, speed_z);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_WIND_LEN);
+#else
+ mavlink_wind_t packet;
+ packet.direction = direction;
+ packet.speed = speed;
+ packet.speed_z = speed_z;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_WIND_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_WIND;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_WIND_MIN_LEN, MAVLINK_MSG_ID_WIND_LEN, MAVLINK_MSG_ID_WIND_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_WIND_MIN_LEN, MAVLINK_MSG_ID_WIND_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a wind 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 direction [deg] Wind direction (that wind is coming from).
+ * @param speed [m/s] Wind speed in ground plane.
+ * @param speed_z [m/s] Vertical wind speed.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_wind_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ float direction,float speed,float speed_z)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_WIND_LEN];
+ _mav_put_float(buf, 0, direction);
+ _mav_put_float(buf, 4, speed);
+ _mav_put_float(buf, 8, speed_z);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_WIND_LEN);
+#else
+ mavlink_wind_t packet;
+ packet.direction = direction;
+ packet.speed = speed;
+ packet.speed_z = speed_z;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_WIND_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_WIND;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_WIND_MIN_LEN, MAVLINK_MSG_ID_WIND_LEN, MAVLINK_MSG_ID_WIND_CRC);
+}
+
+/**
+ * @brief Encode a wind 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 wind C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_wind_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_wind_t* wind)
+{
+ return mavlink_msg_wind_pack(system_id, component_id, msg, wind->direction, wind->speed, wind->speed_z);
+}
+
+/**
+ * @brief Encode a wind 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 wind C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_wind_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_wind_t* wind)
+{
+ return mavlink_msg_wind_pack_chan(system_id, component_id, chan, msg, wind->direction, wind->speed, wind->speed_z);
+}
+
+/**
+ * @brief Encode a wind 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 wind C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_wind_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_wind_t* wind)
+{
+ return mavlink_msg_wind_pack_status(system_id, component_id, _status, msg, wind->direction, wind->speed, wind->speed_z);
+}
+
+/**
+ * @brief Send a wind message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param direction [deg] Wind direction (that wind is coming from).
+ * @param speed [m/s] Wind speed in ground plane.
+ * @param speed_z [m/s] Vertical wind speed.
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_wind_send(mavlink_channel_t chan, float direction, float speed, float speed_z)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_WIND_LEN];
+ _mav_put_float(buf, 0, direction);
+ _mav_put_float(buf, 4, speed);
+ _mav_put_float(buf, 8, speed_z);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WIND, buf, MAVLINK_MSG_ID_WIND_MIN_LEN, MAVLINK_MSG_ID_WIND_LEN, MAVLINK_MSG_ID_WIND_CRC);
+#else
+ mavlink_wind_t packet;
+ packet.direction = direction;
+ packet.speed = speed;
+ packet.speed_z = speed_z;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WIND, (const char *)&packet, MAVLINK_MSG_ID_WIND_MIN_LEN, MAVLINK_MSG_ID_WIND_LEN, MAVLINK_MSG_ID_WIND_CRC);
+#endif
+}
+
+/**
+ * @brief Send a wind message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_wind_send_struct(mavlink_channel_t chan, const mavlink_wind_t* wind)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_wind_send(chan, wind->direction, wind->speed, wind->speed_z);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WIND, (const char *)wind, MAVLINK_MSG_ID_WIND_MIN_LEN, MAVLINK_MSG_ID_WIND_LEN, MAVLINK_MSG_ID_WIND_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_WIND_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_wind_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float direction, float speed, float speed_z)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_float(buf, 0, direction);
+ _mav_put_float(buf, 4, speed);
+ _mav_put_float(buf, 8, speed_z);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WIND, buf, MAVLINK_MSG_ID_WIND_MIN_LEN, MAVLINK_MSG_ID_WIND_LEN, MAVLINK_MSG_ID_WIND_CRC);
+#else
+ mavlink_wind_t *packet = (mavlink_wind_t *)msgbuf;
+ packet->direction = direction;
+ packet->speed = speed;
+ packet->speed_z = speed_z;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WIND, (const char *)packet, MAVLINK_MSG_ID_WIND_MIN_LEN, MAVLINK_MSG_ID_WIND_LEN, MAVLINK_MSG_ID_WIND_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE WIND UNPACKING
+
+
+/**
+ * @brief Get field direction from wind message
+ *
+ * @return [deg] Wind direction (that wind is coming from).
+ */
+static inline float mavlink_msg_wind_get_direction(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 0);
+}
+
+/**
+ * @brief Get field speed from wind message
+ *
+ * @return [m/s] Wind speed in ground plane.
+ */
+static inline float mavlink_msg_wind_get_speed(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 4);
+}
+
+/**
+ * @brief Get field speed_z from wind message
+ *
+ * @return [m/s] Vertical wind speed.
+ */
+static inline float mavlink_msg_wind_get_speed_z(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 8);
+}
+
+/**
+ * @brief Decode a wind message into a struct
+ *
+ * @param msg The message to decode
+ * @param wind C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_wind_decode(const mavlink_message_t* msg, mavlink_wind_t* wind)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ wind->direction = mavlink_msg_wind_get_direction(msg);
+ wind->speed = mavlink_msg_wind_get_speed(msg);
+ wind->speed_z = mavlink_msg_wind_get_speed_z(msg);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_WIND_LEN? msg->len : MAVLINK_MSG_ID_WIND_LEN;
+ memset(wind, 0, MAVLINK_MSG_ID_WIND_LEN);
+ memcpy(wind, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/ardupilotmega/testsuite.h b/lib/main/MAVLink/ardupilotmega/testsuite.h
new file mode 100644
index 00000000000..72b02bea810
--- /dev/null
+++ b/lib/main/MAVLink/ardupilotmega/testsuite.h
@@ -0,0 +1,4808 @@
+/** @file
+ * @brief MAVLink comm protocol testsuite generated from ardupilotmega.xml
+ * @see https://mavlink.io/en/
+ */
+#pragma once
+#ifndef ARDUPILOTMEGA_TESTSUITE_H
+#define ARDUPILOTMEGA_TESTSUITE_H
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+#ifndef MAVLINK_TEST_ALL
+#define MAVLINK_TEST_ALL
+static void mavlink_test_common(uint8_t, uint8_t, mavlink_message_t *last_msg);
+static void mavlink_test_uAvionix(uint8_t, uint8_t, mavlink_message_t *last_msg);
+static void mavlink_test_icarous(uint8_t, uint8_t, mavlink_message_t *last_msg);
+static void mavlink_test_loweheiser(uint8_t, uint8_t, mavlink_message_t *last_msg);
+static void mavlink_test_cubepilot(uint8_t, uint8_t, mavlink_message_t *last_msg);
+static void mavlink_test_csAirLink(uint8_t, uint8_t, mavlink_message_t *last_msg);
+static void mavlink_test_ardupilotmega(uint8_t, uint8_t, mavlink_message_t *last_msg);
+
+static void mavlink_test_all(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
+{
+ mavlink_test_common(system_id, component_id, last_msg);
+ mavlink_test_uAvionix(system_id, component_id, last_msg);
+ mavlink_test_icarous(system_id, component_id, last_msg);
+ mavlink_test_loweheiser(system_id, component_id, last_msg);
+ mavlink_test_cubepilot(system_id, component_id, last_msg);
+ mavlink_test_csAirLink(system_id, component_id, last_msg);
+ mavlink_test_ardupilotmega(system_id, component_id, last_msg);
+}
+#endif
+
+#include "../common/testsuite.h"
+#include "../uAvionix/testsuite.h"
+#include "../icarous/testsuite.h"
+#include "../loweheiser/testsuite.h"
+#include "../cubepilot/testsuite.h"
+#include "../csAirLink/testsuite.h"
+
+
+static void mavlink_test_sensor_offsets(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_SENSOR_OFFSETS >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_sensor_offsets_t packet_in = {
+ 17.0,963497672,963497880,101.0,129.0,157.0,185.0,213.0,241.0,19107,19211,19315
+ };
+ mavlink_sensor_offsets_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.mag_declination = packet_in.mag_declination;
+ packet1.raw_press = packet_in.raw_press;
+ packet1.raw_temp = packet_in.raw_temp;
+ packet1.gyro_cal_x = packet_in.gyro_cal_x;
+ packet1.gyro_cal_y = packet_in.gyro_cal_y;
+ packet1.gyro_cal_z = packet_in.gyro_cal_z;
+ packet1.accel_cal_x = packet_in.accel_cal_x;
+ packet1.accel_cal_y = packet_in.accel_cal_y;
+ packet1.accel_cal_z = packet_in.accel_cal_z;
+ packet1.mag_ofs_x = packet_in.mag_ofs_x;
+ packet1.mag_ofs_y = packet_in.mag_ofs_y;
+ packet1.mag_ofs_z = packet_in.mag_ofs_z;
+
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_SENSOR_OFFSETS_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SENSOR_OFFSETS_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_sensor_offsets_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_sensor_offsets_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_sensor_offsets_pack(system_id, component_id, &msg , packet1.mag_ofs_x , packet1.mag_ofs_y , packet1.mag_ofs_z , packet1.mag_declination , packet1.raw_press , packet1.raw_temp , packet1.gyro_cal_x , packet1.gyro_cal_y , packet1.gyro_cal_z , packet1.accel_cal_x , packet1.accel_cal_y , packet1.accel_cal_z );
+ mavlink_msg_sensor_offsets_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_sensor_offsets_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.mag_ofs_x , packet1.mag_ofs_y , packet1.mag_ofs_z , packet1.mag_declination , packet1.raw_press , packet1.raw_temp , packet1.gyro_cal_x , packet1.gyro_cal_y , packet1.gyro_cal_z , packet1.accel_cal_x , packet1.accel_cal_y , packet1.accel_cal_z );
+ mavlink_msg_sensor_offsets_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_SET_MAG_OFFSETS >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_set_mag_offsets_t packet_in = {
+ 17235,17339,17443,151,218
+ };
+ mavlink_set_mag_offsets_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.mag_ofs_x = packet_in.mag_ofs_x;
+ packet1.mag_ofs_y = packet_in.mag_ofs_y;
+ packet1.mag_ofs_z = packet_in.mag_ofs_z;
+ packet1.target_system = packet_in.target_system;
+ packet1.target_component = packet_in.target_component;
+
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_SET_MAG_OFFSETS_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SET_MAG_OFFSETS_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_set_mag_offsets_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_set_mag_offsets_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_set_mag_offsets_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.mag_ofs_x , packet1.mag_ofs_y , packet1.mag_ofs_z );
+ mavlink_msg_set_mag_offsets_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_set_mag_offsets_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.mag_ofs_x , packet1.mag_ofs_y , packet1.mag_ofs_z );
+ mavlink_msg_set_mag_offsets_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_MEMINFO >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_meminfo_t packet_in = {
+ 17235,17339,963497672
+ };
+ mavlink_meminfo_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.brkval = packet_in.brkval;
+ packet1.freemem = packet_in.freemem;
+ packet1.freemem32 = packet_in.freemem32;
+
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_MEMINFO_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_MEMINFO_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_meminfo_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_meminfo_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_meminfo_pack(system_id, component_id, &msg , packet1.brkval , packet1.freemem , packet1.freemem32 );
+ mavlink_msg_meminfo_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_meminfo_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.brkval , packet1.freemem , packet1.freemem32 );
+ mavlink_msg_meminfo_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_AP_ADC >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_ap_adc_t packet_in = {
+ 17235,17339,17443,17547,17651,17755
+ };
+ mavlink_ap_adc_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.adc1 = packet_in.adc1;
+ packet1.adc2 = packet_in.adc2;
+ packet1.adc3 = packet_in.adc3;
+ packet1.adc4 = packet_in.adc4;
+ packet1.adc5 = packet_in.adc5;
+ packet1.adc6 = packet_in.adc6;
+
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_AP_ADC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_AP_ADC_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_ap_adc_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_ap_adc_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_ap_adc_pack(system_id, component_id, &msg , packet1.adc1 , packet1.adc2 , packet1.adc3 , packet1.adc4 , packet1.adc5 , packet1.adc6 );
+ mavlink_msg_ap_adc_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_ap_adc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.adc1 , packet1.adc2 , packet1.adc3 , packet1.adc4 , packet1.adc5 , packet1.adc6 );
+ mavlink_msg_ap_adc_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_DIGICAM_CONFIGURE >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_digicam_configure_t packet_in = {
+ 17.0,17443,151,218,29,96,163,230,41,108,175
+ };
+ mavlink_digicam_configure_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.extra_value = packet_in.extra_value;
+ packet1.shutter_speed = packet_in.shutter_speed;
+ packet1.target_system = packet_in.target_system;
+ packet1.target_component = packet_in.target_component;
+ packet1.mode = packet_in.mode;
+ packet1.aperture = packet_in.aperture;
+ packet1.iso = packet_in.iso;
+ packet1.exposure_type = packet_in.exposure_type;
+ packet1.command_id = packet_in.command_id;
+ packet1.engine_cut_off = packet_in.engine_cut_off;
+ packet1.extra_param = packet_in.extra_param;
+
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_DIGICAM_CONFIGURE_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_DIGICAM_CONFIGURE_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_digicam_configure_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_digicam_configure_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_digicam_configure_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.mode , packet1.shutter_speed , packet1.aperture , packet1.iso , packet1.exposure_type , packet1.command_id , packet1.engine_cut_off , packet1.extra_param , packet1.extra_value );
+ mavlink_msg_digicam_configure_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_digicam_configure_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.mode , packet1.shutter_speed , packet1.aperture , packet1.iso , packet1.exposure_type , packet1.command_id , packet1.engine_cut_off , packet1.extra_param , packet1.extra_value );
+ mavlink_msg_digicam_configure_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_DIGICAM_CONTROL >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_digicam_control_t packet_in = {
+ 17.0,17,84,151,218,29,96,163,230,41
+ };
+ mavlink_digicam_control_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.extra_value = packet_in.extra_value;
+ packet1.target_system = packet_in.target_system;
+ packet1.target_component = packet_in.target_component;
+ packet1.session = packet_in.session;
+ packet1.zoom_pos = packet_in.zoom_pos;
+ packet1.zoom_step = packet_in.zoom_step;
+ packet1.focus_lock = packet_in.focus_lock;
+ packet1.shot = packet_in.shot;
+ packet1.command_id = packet_in.command_id;
+ packet1.extra_param = packet_in.extra_param;
+
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_DIGICAM_CONTROL_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_DIGICAM_CONTROL_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_digicam_control_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_digicam_control_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_digicam_control_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.session , packet1.zoom_pos , packet1.zoom_step , packet1.focus_lock , packet1.shot , packet1.command_id , packet1.extra_param , packet1.extra_value );
+ mavlink_msg_digicam_control_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_digicam_control_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.session , packet1.zoom_pos , packet1.zoom_step , packet1.focus_lock , packet1.shot , packet1.command_id , packet1.extra_param , packet1.extra_value );
+ mavlink_msg_digicam_control_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_MOUNT_CONFIGURE >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_mount_configure_t packet_in = {
+ 5,72,139,206,17,84
+ };
+ mavlink_mount_configure_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.target_system = packet_in.target_system;
+ packet1.target_component = packet_in.target_component;
+ packet1.mount_mode = packet_in.mount_mode;
+ packet1.stab_roll = packet_in.stab_roll;
+ packet1.stab_pitch = packet_in.stab_pitch;
+ packet1.stab_yaw = packet_in.stab_yaw;
+
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_MOUNT_CONFIGURE_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_MOUNT_CONFIGURE_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_mount_configure_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_mount_configure_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_mount_configure_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.mount_mode , packet1.stab_roll , packet1.stab_pitch , packet1.stab_yaw );
+ mavlink_msg_mount_configure_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_mount_configure_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.mount_mode , packet1.stab_roll , packet1.stab_pitch , packet1.stab_yaw );
+ mavlink_msg_mount_configure_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_MOUNT_CONTROL >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_mount_control_t packet_in = {
+ 963497464,963497672,963497880,41,108,175
+ };
+ mavlink_mount_control_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.input_a = packet_in.input_a;
+ packet1.input_b = packet_in.input_b;
+ packet1.input_c = packet_in.input_c;
+ packet1.target_system = packet_in.target_system;
+ packet1.target_component = packet_in.target_component;
+ packet1.save_position = packet_in.save_position;
+
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_MOUNT_CONTROL_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_MOUNT_CONTROL_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_mount_control_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_mount_control_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_mount_control_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.input_a , packet1.input_b , packet1.input_c , packet1.save_position );
+ mavlink_msg_mount_control_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_mount_control_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.input_a , packet1.input_b , packet1.input_c , packet1.save_position );
+ mavlink_msg_mount_control_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_MOUNT_STATUS >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_mount_status_t packet_in = {
+ 963497464,963497672,963497880,41,108,175
+ };
+ mavlink_mount_status_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.pointing_a = packet_in.pointing_a;
+ packet1.pointing_b = packet_in.pointing_b;
+ packet1.pointing_c = packet_in.pointing_c;
+ packet1.target_system = packet_in.target_system;
+ packet1.target_component = packet_in.target_component;
+ packet1.mount_mode = packet_in.mount_mode;
+
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_MOUNT_STATUS_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_MOUNT_STATUS_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_mount_status_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_mount_status_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_mount_status_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.pointing_a , packet1.pointing_b , packet1.pointing_c , packet1.mount_mode );
+ mavlink_msg_mount_status_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_mount_status_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.pointing_a , packet1.pointing_b , packet1.pointing_c , packet1.mount_mode );
+ mavlink_msg_mount_status_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_FENCE_POINT >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_fence_point_t packet_in = {
+ 17.0,45.0,29,96,163,230
+ };
+ mavlink_fence_point_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.lat = packet_in.lat;
+ packet1.lng = packet_in.lng;
+ packet1.target_system = packet_in.target_system;
+ packet1.target_component = packet_in.target_component;
+ packet1.idx = packet_in.idx;
+ packet1.count = packet_in.count;
+
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_FENCE_POINT_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_FENCE_POINT_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_fence_point_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_fence_point_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_fence_point_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.idx , packet1.count , packet1.lat , packet1.lng );
+ mavlink_msg_fence_point_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_fence_point_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.idx , packet1.count , packet1.lat , packet1.lng );
+ mavlink_msg_fence_point_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_FENCE_FETCH_POINT >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_fence_fetch_point_t packet_in = {
+ 5,72,139
+ };
+ mavlink_fence_fetch_point_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.target_system = packet_in.target_system;
+ packet1.target_component = packet_in.target_component;
+ packet1.idx = packet_in.idx;
+
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_FENCE_FETCH_POINT_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_FENCE_FETCH_POINT_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_fence_fetch_point_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_fence_fetch_point_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_fence_fetch_point_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.idx );
+ mavlink_msg_fence_fetch_point_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_fence_fetch_point_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.idx );
+ mavlink_msg_fence_fetch_point_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_AHRS >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_ahrs_t packet_in = {
+ 17.0,45.0,73.0,101.0,129.0,157.0,185.0
+ };
+ mavlink_ahrs_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.omegaIx = packet_in.omegaIx;
+ packet1.omegaIy = packet_in.omegaIy;
+ packet1.omegaIz = packet_in.omegaIz;
+ packet1.accel_weight = packet_in.accel_weight;
+ packet1.renorm_val = packet_in.renorm_val;
+ packet1.error_rp = packet_in.error_rp;
+ packet1.error_yaw = packet_in.error_yaw;
+
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_AHRS_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_AHRS_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_ahrs_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_ahrs_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_ahrs_pack(system_id, component_id, &msg , packet1.omegaIx , packet1.omegaIy , packet1.omegaIz , packet1.accel_weight , packet1.renorm_val , packet1.error_rp , packet1.error_yaw );
+ mavlink_msg_ahrs_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_ahrs_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.omegaIx , packet1.omegaIy , packet1.omegaIz , packet1.accel_weight , packet1.renorm_val , packet1.error_rp , packet1.error_yaw );
+ mavlink_msg_ahrs_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_SIMSTATE >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_simstate_t packet_in = {
+ 17.0,45.0,73.0,101.0,129.0,157.0,185.0,213.0,241.0,963499336,963499544
+ };
+ mavlink_simstate_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.roll = packet_in.roll;
+ packet1.pitch = packet_in.pitch;
+ packet1.yaw = packet_in.yaw;
+ packet1.xacc = packet_in.xacc;
+ packet1.yacc = packet_in.yacc;
+ packet1.zacc = packet_in.zacc;
+ packet1.xgyro = packet_in.xgyro;
+ packet1.ygyro = packet_in.ygyro;
+ packet1.zgyro = packet_in.zgyro;
+ packet1.lat = packet_in.lat;
+ packet1.lng = packet_in.lng;
+
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_SIMSTATE_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SIMSTATE_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_simstate_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_simstate_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_simstate_pack(system_id, component_id, &msg , packet1.roll , packet1.pitch , packet1.yaw , packet1.xacc , packet1.yacc , packet1.zacc , packet1.xgyro , packet1.ygyro , packet1.zgyro , packet1.lat , packet1.lng );
+ mavlink_msg_simstate_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_simstate_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.roll , packet1.pitch , packet1.yaw , packet1.xacc , packet1.yacc , packet1.zacc , packet1.xgyro , packet1.ygyro , packet1.zgyro , packet1.lat , packet1.lng );
+ mavlink_msg_simstate_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_HWSTATUS >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_hwstatus_t packet_in = {
+ 17235,139
+ };
+ mavlink_hwstatus_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.Vcc = packet_in.Vcc;
+ packet1.I2Cerr = packet_in.I2Cerr;
+
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_HWSTATUS_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_HWSTATUS_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_hwstatus_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_hwstatus_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_hwstatus_pack(system_id, component_id, &msg , packet1.Vcc , packet1.I2Cerr );
+ mavlink_msg_hwstatus_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_hwstatus_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.Vcc , packet1.I2Cerr );
+ mavlink_msg_hwstatus_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_RADIO >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_radio_t packet_in = {
+ 17235,17339,17,84,151,218,29
+ };
+ mavlink_radio_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.rxerrors = packet_in.rxerrors;
+ packet1.fixed = packet_in.fixed;
+ packet1.rssi = packet_in.rssi;
+ packet1.remrssi = packet_in.remrssi;
+ packet1.txbuf = packet_in.txbuf;
+ packet1.noise = packet_in.noise;
+ packet1.remnoise = packet_in.remnoise;
+
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_RADIO_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_RADIO_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_radio_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_radio_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_radio_pack(system_id, component_id, &msg , packet1.rssi , packet1.remrssi , packet1.txbuf , packet1.noise , packet1.remnoise , packet1.rxerrors , packet1.fixed );
+ mavlink_msg_radio_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_radio_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.rssi , packet1.remrssi , packet1.txbuf , packet1.noise , packet1.remnoise , packet1.rxerrors , packet1.fixed );
+ mavlink_msg_radio_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_LIMITS_STATUS >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_limits_status_t packet_in = {
+ 963497464,963497672,963497880,963498088,18067,187,254,65,132
+ };
+ mavlink_limits_status_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.last_trigger = packet_in.last_trigger;
+ packet1.last_action = packet_in.last_action;
+ packet1.last_recovery = packet_in.last_recovery;
+ packet1.last_clear = packet_in.last_clear;
+ packet1.breach_count = packet_in.breach_count;
+ packet1.limits_state = packet_in.limits_state;
+ packet1.mods_enabled = packet_in.mods_enabled;
+ packet1.mods_required = packet_in.mods_required;
+ packet1.mods_triggered = packet_in.mods_triggered;
+
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_LIMITS_STATUS_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_LIMITS_STATUS_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_limits_status_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_limits_status_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_limits_status_pack(system_id, component_id, &msg , packet1.limits_state , packet1.last_trigger , packet1.last_action , packet1.last_recovery , packet1.last_clear , packet1.breach_count , packet1.mods_enabled , packet1.mods_required , packet1.mods_triggered );
+ mavlink_msg_limits_status_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_limits_status_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.limits_state , packet1.last_trigger , packet1.last_action , packet1.last_recovery , packet1.last_clear , packet1.breach_count , packet1.mods_enabled , packet1.mods_required , packet1.mods_triggered );
+ mavlink_msg_limits_status_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_WIND >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_wind_t packet_in = {
+ 17.0,45.0,73.0
+ };
+ mavlink_wind_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.direction = packet_in.direction;
+ packet1.speed = packet_in.speed;
+ packet1.speed_z = packet_in.speed_z;
+
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_WIND_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_WIND_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_wind_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_wind_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_wind_pack(system_id, component_id, &msg , packet1.direction , packet1.speed , packet1.speed_z );
+ mavlink_msg_wind_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_wind_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.direction , packet1.speed , packet1.speed_z );
+ mavlink_msg_wind_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_DATA16 >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_data16_t packet_in = {
+ 5,72,{ 139, 140, 141, 142, 143, 144, 145, 146, 147, 148, 149, 150, 151, 152, 153, 154 }
+ };
+ mavlink_data16_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.type = packet_in.type;
+ packet1.len = packet_in.len;
+
+ mav_array_memcpy(packet1.data, packet_in.data, sizeof(uint8_t)*16);
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_DATA16_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_DATA16_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_data16_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_data16_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_data16_pack(system_id, component_id, &msg , packet1.type , packet1.len , packet1.data );
+ mavlink_msg_data16_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_data16_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.type , packet1.len , packet1.data );
+ mavlink_msg_data16_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_DATA32 >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_data32_t packet_in = {
+ 5,72,{ 139, 140, 141, 142, 143, 144, 145, 146, 147, 148, 149, 150, 151, 152, 153, 154, 155, 156, 157, 158, 159, 160, 161, 162, 163, 164, 165, 166, 167, 168, 169, 170 }
+ };
+ mavlink_data32_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.type = packet_in.type;
+ packet1.len = packet_in.len;
+
+ mav_array_memcpy(packet1.data, packet_in.data, sizeof(uint8_t)*32);
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_DATA32_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_DATA32_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_data32_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_data32_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_data32_pack(system_id, component_id, &msg , packet1.type , packet1.len , packet1.data );
+ mavlink_msg_data32_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_data32_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.type , packet1.len , packet1.data );
+ mavlink_msg_data32_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_DATA64 >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_data64_t packet_in = {
+ 5,72,{ 139, 140, 141, 142, 143, 144, 145, 146, 147, 148, 149, 150, 151, 152, 153, 154, 155, 156, 157, 158, 159, 160, 161, 162, 163, 164, 165, 166, 167, 168, 169, 170, 171, 172, 173, 174, 175, 176, 177, 178, 179, 180, 181, 182, 183, 184, 185, 186, 187, 188, 189, 190, 191, 192, 193, 194, 195, 196, 197, 198, 199, 200, 201, 202 }
+ };
+ mavlink_data64_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.type = packet_in.type;
+ packet1.len = packet_in.len;
+
+ mav_array_memcpy(packet1.data, packet_in.data, sizeof(uint8_t)*64);
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_DATA64_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_DATA64_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_data64_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_data64_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_data64_pack(system_id, component_id, &msg , packet1.type , packet1.len , packet1.data );
+ mavlink_msg_data64_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_data64_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.type , packet1.len , packet1.data );
+ mavlink_msg_data64_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_DATA96 >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_data96_t packet_in = {
+ 5,72,{ 139, 140, 141, 142, 143, 144, 145, 146, 147, 148, 149, 150, 151, 152, 153, 154, 155, 156, 157, 158, 159, 160, 161, 162, 163, 164, 165, 166, 167, 168, 169, 170, 171, 172, 173, 174, 175, 176, 177, 178, 179, 180, 181, 182, 183, 184, 185, 186, 187, 188, 189, 190, 191, 192, 193, 194, 195, 196, 197, 198, 199, 200, 201, 202, 203, 204, 205, 206, 207, 208, 209, 210, 211, 212, 213, 214, 215, 216, 217, 218, 219, 220, 221, 222, 223, 224, 225, 226, 227, 228, 229, 230, 231, 232, 233, 234 }
+ };
+ mavlink_data96_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.type = packet_in.type;
+ packet1.len = packet_in.len;
+
+ mav_array_memcpy(packet1.data, packet_in.data, sizeof(uint8_t)*96);
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_DATA96_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_DATA96_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_data96_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_data96_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_data96_pack(system_id, component_id, &msg , packet1.type , packet1.len , packet1.data );
+ mavlink_msg_data96_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_data96_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.type , packet1.len , packet1.data );
+ mavlink_msg_data96_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_RANGEFINDER >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_rangefinder_t packet_in = {
+ 17.0,45.0
+ };
+ mavlink_rangefinder_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.distance = packet_in.distance;
+ packet1.voltage = packet_in.voltage;
+
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_RANGEFINDER_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_RANGEFINDER_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_rangefinder_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_rangefinder_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_rangefinder_pack(system_id, component_id, &msg , packet1.distance , packet1.voltage );
+ mavlink_msg_rangefinder_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_rangefinder_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.distance , packet1.voltage );
+ mavlink_msg_rangefinder_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_AIRSPEED_AUTOCAL >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_airspeed_autocal_t packet_in = {
+ 17.0,45.0,73.0,101.0,129.0,157.0,185.0,213.0,241.0,269.0,297.0,325.0
+ };
+ mavlink_airspeed_autocal_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.vx = packet_in.vx;
+ packet1.vy = packet_in.vy;
+ packet1.vz = packet_in.vz;
+ packet1.diff_pressure = packet_in.diff_pressure;
+ packet1.EAS2TAS = packet_in.EAS2TAS;
+ packet1.ratio = packet_in.ratio;
+ packet1.state_x = packet_in.state_x;
+ packet1.state_y = packet_in.state_y;
+ packet1.state_z = packet_in.state_z;
+ packet1.Pax = packet_in.Pax;
+ packet1.Pby = packet_in.Pby;
+ packet1.Pcz = packet_in.Pcz;
+
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_AIRSPEED_AUTOCAL_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_airspeed_autocal_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_airspeed_autocal_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_airspeed_autocal_pack(system_id, component_id, &msg , packet1.vx , packet1.vy , packet1.vz , packet1.diff_pressure , packet1.EAS2TAS , packet1.ratio , packet1.state_x , packet1.state_y , packet1.state_z , packet1.Pax , packet1.Pby , packet1.Pcz );
+ mavlink_msg_airspeed_autocal_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_airspeed_autocal_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.vx , packet1.vy , packet1.vz , packet1.diff_pressure , packet1.EAS2TAS , packet1.ratio , packet1.state_x , packet1.state_y , packet1.state_z , packet1.Pax , packet1.Pby , packet1.Pcz );
+ mavlink_msg_airspeed_autocal_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_RALLY_POINT >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_rally_point_t packet_in = {
+ 963497464,963497672,17651,17755,17859,175,242,53,120,187
+ };
+ mavlink_rally_point_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.lat = packet_in.lat;
+ packet1.lng = packet_in.lng;
+ packet1.alt = packet_in.alt;
+ packet1.break_alt = packet_in.break_alt;
+ packet1.land_dir = packet_in.land_dir;
+ packet1.target_system = packet_in.target_system;
+ packet1.target_component = packet_in.target_component;
+ packet1.idx = packet_in.idx;
+ packet1.count = packet_in.count;
+ packet1.flags = packet_in.flags;
+
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_RALLY_POINT_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_RALLY_POINT_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_rally_point_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_rally_point_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_rally_point_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.idx , packet1.count , packet1.lat , packet1.lng , packet1.alt , packet1.break_alt , packet1.land_dir , packet1.flags );
+ mavlink_msg_rally_point_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_rally_point_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.idx , packet1.count , packet1.lat , packet1.lng , packet1.alt , packet1.break_alt , packet1.land_dir , packet1.flags );
+ mavlink_msg_rally_point_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_RALLY_FETCH_POINT >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_rally_fetch_point_t packet_in = {
+ 5,72,139
+ };
+ mavlink_rally_fetch_point_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.target_system = packet_in.target_system;
+ packet1.target_component = packet_in.target_component;
+ packet1.idx = packet_in.idx;
+
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_RALLY_FETCH_POINT_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_RALLY_FETCH_POINT_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_rally_fetch_point_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_rally_fetch_point_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_rally_fetch_point_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.idx );
+ mavlink_msg_rally_fetch_point_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_rally_fetch_point_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.idx );
+ mavlink_msg_rally_fetch_point_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_COMPASSMOT_STATUS >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_compassmot_status_t packet_in = {
+ 17.0,45.0,73.0,101.0,18067,18171
+ };
+ mavlink_compassmot_status_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.current = packet_in.current;
+ packet1.CompensationX = packet_in.CompensationX;
+ packet1.CompensationY = packet_in.CompensationY;
+ packet1.CompensationZ = packet_in.CompensationZ;
+ packet1.throttle = packet_in.throttle;
+ packet1.interference = packet_in.interference;
+
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_COMPASSMOT_STATUS_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_COMPASSMOT_STATUS_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_compassmot_status_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_compassmot_status_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_compassmot_status_pack(system_id, component_id, &msg , packet1.throttle , packet1.current , packet1.interference , packet1.CompensationX , packet1.CompensationY , packet1.CompensationZ );
+ mavlink_msg_compassmot_status_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_compassmot_status_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.throttle , packet1.current , packet1.interference , packet1.CompensationX , packet1.CompensationY , packet1.CompensationZ );
+ mavlink_msg_compassmot_status_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_AHRS2 >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_ahrs2_t packet_in = {
+ 17.0,45.0,73.0,101.0,963498296,963498504
+ };
+ mavlink_ahrs2_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.roll = packet_in.roll;
+ packet1.pitch = packet_in.pitch;
+ packet1.yaw = packet_in.yaw;
+ packet1.altitude = packet_in.altitude;
+ packet1.lat = packet_in.lat;
+ packet1.lng = packet_in.lng;
+
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_AHRS2_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_AHRS2_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_ahrs2_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_ahrs2_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_ahrs2_pack(system_id, component_id, &msg , packet1.roll , packet1.pitch , packet1.yaw , packet1.altitude , packet1.lat , packet1.lng );
+ mavlink_msg_ahrs2_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_ahrs2_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.roll , packet1.pitch , packet1.yaw , packet1.altitude , packet1.lat , packet1.lng );
+ mavlink_msg_ahrs2_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_CAMERA_STATUS >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_camera_status_t packet_in = {
+ 93372036854775807ULL,73.0,101.0,129.0,157.0,18483,211,22,89
+ };
+ mavlink_camera_status_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.time_usec = packet_in.time_usec;
+ packet1.p1 = packet_in.p1;
+ packet1.p2 = packet_in.p2;
+ packet1.p3 = packet_in.p3;
+ packet1.p4 = packet_in.p4;
+ packet1.img_idx = packet_in.img_idx;
+ packet1.target_system = packet_in.target_system;
+ packet1.cam_idx = packet_in.cam_idx;
+ packet1.event_id = packet_in.event_id;
+
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_CAMERA_STATUS_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_CAMERA_STATUS_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_camera_status_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_camera_status_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_camera_status_pack(system_id, component_id, &msg , packet1.time_usec , packet1.target_system , packet1.cam_idx , packet1.img_idx , packet1.event_id , packet1.p1 , packet1.p2 , packet1.p3 , packet1.p4 );
+ mavlink_msg_camera_status_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_camera_status_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.target_system , packet1.cam_idx , packet1.img_idx , packet1.event_id , packet1.p1 , packet1.p2 , packet1.p3 , packet1.p4 );
+ mavlink_msg_camera_status_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_CAMERA_FEEDBACK >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_camera_feedback_t packet_in = {
+ 93372036854775807ULL,963497880,963498088,129.0,157.0,185.0,213.0,241.0,269.0,19315,3,70,137,19575
+ };
+ mavlink_camera_feedback_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.time_usec = packet_in.time_usec;
+ packet1.lat = packet_in.lat;
+ packet1.lng = packet_in.lng;
+ packet1.alt_msl = packet_in.alt_msl;
+ packet1.alt_rel = packet_in.alt_rel;
+ packet1.roll = packet_in.roll;
+ packet1.pitch = packet_in.pitch;
+ packet1.yaw = packet_in.yaw;
+ packet1.foc_len = packet_in.foc_len;
+ packet1.img_idx = packet_in.img_idx;
+ packet1.target_system = packet_in.target_system;
+ packet1.cam_idx = packet_in.cam_idx;
+ packet1.flags = packet_in.flags;
+ packet1.completed_captures = packet_in.completed_captures;
+
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_CAMERA_FEEDBACK_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_CAMERA_FEEDBACK_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_camera_feedback_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_camera_feedback_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_camera_feedback_pack(system_id, component_id, &msg , packet1.time_usec , packet1.target_system , packet1.cam_idx , packet1.img_idx , packet1.lat , packet1.lng , packet1.alt_msl , packet1.alt_rel , packet1.roll , packet1.pitch , packet1.yaw , packet1.foc_len , packet1.flags , packet1.completed_captures );
+ mavlink_msg_camera_feedback_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_camera_feedback_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.target_system , packet1.cam_idx , packet1.img_idx , packet1.lat , packet1.lng , packet1.alt_msl , packet1.alt_rel , packet1.roll , packet1.pitch , packet1.yaw , packet1.foc_len , packet1.flags , packet1.completed_captures );
+ mavlink_msg_camera_feedback_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_BATTERY2 >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_battery2_t packet_in = {
+ 17235,17339
+ };
+ mavlink_battery2_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.voltage = packet_in.voltage;
+ packet1.current_battery = packet_in.current_battery;
+
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_BATTERY2_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_BATTERY2_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_battery2_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_battery2_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_battery2_pack(system_id, component_id, &msg , packet1.voltage , packet1.current_battery );
+ mavlink_msg_battery2_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_battery2_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.voltage , packet1.current_battery );
+ mavlink_msg_battery2_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_AHRS3 >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_ahrs3_t packet_in = {
+ 17.0,45.0,73.0,101.0,963498296,963498504,185.0,213.0,241.0,269.0
+ };
+ mavlink_ahrs3_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.roll = packet_in.roll;
+ packet1.pitch = packet_in.pitch;
+ packet1.yaw = packet_in.yaw;
+ packet1.altitude = packet_in.altitude;
+ packet1.lat = packet_in.lat;
+ packet1.lng = packet_in.lng;
+ packet1.v1 = packet_in.v1;
+ packet1.v2 = packet_in.v2;
+ packet1.v3 = packet_in.v3;
+ packet1.v4 = packet_in.v4;
+
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_AHRS3_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_AHRS3_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_ahrs3_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_ahrs3_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_ahrs3_pack(system_id, component_id, &msg , packet1.roll , packet1.pitch , packet1.yaw , packet1.altitude , packet1.lat , packet1.lng , packet1.v1 , packet1.v2 , packet1.v3 , packet1.v4 );
+ mavlink_msg_ahrs3_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_ahrs3_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.roll , packet1.pitch , packet1.yaw , packet1.altitude , packet1.lat , packet1.lng , packet1.v1 , packet1.v2 , packet1.v3 , packet1.v4 );
+ mavlink_msg_ahrs3_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_autopilot_version_request_t packet_in = {
+ 5,72
+ };
+ mavlink_autopilot_version_request_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.target_system = packet_in.target_system;
+ packet1.target_component = packet_in.target_component;
+
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_AUTOPILOT_VERSION_REQUEST_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_autopilot_version_request_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_autopilot_version_request_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_autopilot_version_request_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component );
+ mavlink_msg_autopilot_version_request_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_autopilot_version_request_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component );
+ mavlink_msg_autopilot_version_request_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_remote_log_data_block_t packet_in = {
+ 963497464,17,84,{ 151, 152, 153, 154, 155, 156, 157, 158, 159, 160, 161, 162, 163, 164, 165, 166, 167, 168, 169, 170, 171, 172, 173, 174, 175, 176, 177, 178, 179, 180, 181, 182, 183, 184, 185, 186, 187, 188, 189, 190, 191, 192, 193, 194, 195, 196, 197, 198, 199, 200, 201, 202, 203, 204, 205, 206, 207, 208, 209, 210, 211, 212, 213, 214, 215, 216, 217, 218, 219, 220, 221, 222, 223, 224, 225, 226, 227, 228, 229, 230, 231, 232, 233, 234, 235, 236, 237, 238, 239, 240, 241, 242, 243, 244, 245, 246, 247, 248, 249, 250, 251, 252, 253, 254, 255, 0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 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 }
+ };
+ mavlink_remote_log_data_block_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.seqno = packet_in.seqno;
+ packet1.target_system = packet_in.target_system;
+ packet1.target_component = packet_in.target_component;
+
+ mav_array_memcpy(packet1.data, packet_in.data, sizeof(uint8_t)*200);
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_REMOTE_LOG_DATA_BLOCK_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_remote_log_data_block_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_remote_log_data_block_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_remote_log_data_block_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.seqno , packet1.data );
+ mavlink_msg_remote_log_data_block_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_remote_log_data_block_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.seqno , packet1.data );
+ mavlink_msg_remote_log_data_block_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_remote_log_block_status_t packet_in = {
+ 963497464,17,84,151
+ };
+ mavlink_remote_log_block_status_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.seqno = packet_in.seqno;
+ packet1.target_system = packet_in.target_system;
+ packet1.target_component = packet_in.target_component;
+ packet1.status = packet_in.status;
+
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_REMOTE_LOG_BLOCK_STATUS_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_remote_log_block_status_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_remote_log_block_status_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_remote_log_block_status_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.seqno , packet1.status );
+ mavlink_msg_remote_log_block_status_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_remote_log_block_status_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.seqno , packet1.status );
+ mavlink_msg_remote_log_block_status_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_LED_CONTROL >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_led_control_t packet_in = {
+ 5,72,139,206,17,{ 84, 85, 86, 87, 88, 89, 90, 91, 92, 93, 94, 95, 96, 97, 98, 99, 100, 101, 102, 103, 104, 105, 106, 107 }
+ };
+ mavlink_led_control_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.target_system = packet_in.target_system;
+ packet1.target_component = packet_in.target_component;
+ packet1.instance = packet_in.instance;
+ packet1.pattern = packet_in.pattern;
+ packet1.custom_len = packet_in.custom_len;
+
+ mav_array_memcpy(packet1.custom_bytes, packet_in.custom_bytes, sizeof(uint8_t)*24);
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_LED_CONTROL_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_LED_CONTROL_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_led_control_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_led_control_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_led_control_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.instance , packet1.pattern , packet1.custom_len , packet1.custom_bytes );
+ mavlink_msg_led_control_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_led_control_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.instance , packet1.pattern , packet1.custom_len , packet1.custom_bytes );
+ mavlink_msg_led_control_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_MAG_CAL_PROGRESS >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_mag_cal_progress_t packet_in = {
+ 17.0,45.0,73.0,41,108,175,242,53,{ 120, 121, 122, 123, 124, 125, 126, 127, 128, 129 }
+ };
+ mavlink_mag_cal_progress_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.direction_x = packet_in.direction_x;
+ packet1.direction_y = packet_in.direction_y;
+ packet1.direction_z = packet_in.direction_z;
+ packet1.compass_id = packet_in.compass_id;
+ packet1.cal_mask = packet_in.cal_mask;
+ packet1.cal_status = packet_in.cal_status;
+ packet1.attempt = packet_in.attempt;
+ packet1.completion_pct = packet_in.completion_pct;
+
+ mav_array_memcpy(packet1.completion_mask, packet_in.completion_mask, sizeof(uint8_t)*10);
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_MAG_CAL_PROGRESS_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_MAG_CAL_PROGRESS_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_mag_cal_progress_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_mag_cal_progress_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_mag_cal_progress_pack(system_id, component_id, &msg , packet1.compass_id , packet1.cal_mask , packet1.cal_status , packet1.attempt , packet1.completion_pct , packet1.completion_mask , packet1.direction_x , packet1.direction_y , packet1.direction_z );
+ mavlink_msg_mag_cal_progress_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_mag_cal_progress_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.compass_id , packet1.cal_mask , packet1.cal_status , packet1.attempt , packet1.completion_pct , packet1.completion_mask , packet1.direction_x , packet1.direction_y , packet1.direction_z );
+ mavlink_msg_mag_cal_progress_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_EKF_STATUS_REPORT >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_ekf_status_report_t packet_in = {
+ 17.0,45.0,73.0,101.0,129.0,18275,171.0
+ };
+ mavlink_ekf_status_report_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.velocity_variance = packet_in.velocity_variance;
+ packet1.pos_horiz_variance = packet_in.pos_horiz_variance;
+ packet1.pos_vert_variance = packet_in.pos_vert_variance;
+ packet1.compass_variance = packet_in.compass_variance;
+ packet1.terrain_alt_variance = packet_in.terrain_alt_variance;
+ packet1.flags = packet_in.flags;
+ packet1.airspeed_variance = packet_in.airspeed_variance;
+
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_EKF_STATUS_REPORT_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_EKF_STATUS_REPORT_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_ekf_status_report_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_ekf_status_report_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_ekf_status_report_pack(system_id, component_id, &msg , packet1.flags , packet1.velocity_variance , packet1.pos_horiz_variance , packet1.pos_vert_variance , packet1.compass_variance , packet1.terrain_alt_variance , packet1.airspeed_variance );
+ mavlink_msg_ekf_status_report_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_ekf_status_report_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.flags , packet1.velocity_variance , packet1.pos_horiz_variance , packet1.pos_vert_variance , packet1.compass_variance , packet1.terrain_alt_variance , packet1.airspeed_variance );
+ mavlink_msg_ekf_status_report_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_PID_TUNING >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_pid_tuning_t packet_in = {
+ 17.0,45.0,73.0,101.0,129.0,157.0,77,192.0,220.0
+ };
+ mavlink_pid_tuning_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.desired = packet_in.desired;
+ packet1.achieved = packet_in.achieved;
+ packet1.FF = packet_in.FF;
+ packet1.P = packet_in.P;
+ packet1.I = packet_in.I;
+ packet1.D = packet_in.D;
+ packet1.axis = packet_in.axis;
+ packet1.SRate = packet_in.SRate;
+ packet1.PDmod = packet_in.PDmod;
+
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_PID_TUNING_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_PID_TUNING_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_pid_tuning_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_pid_tuning_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_pid_tuning_pack(system_id, component_id, &msg , packet1.axis , packet1.desired , packet1.achieved , packet1.FF , packet1.P , packet1.I , packet1.D , packet1.SRate , packet1.PDmod );
+ mavlink_msg_pid_tuning_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_pid_tuning_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.axis , packet1.desired , packet1.achieved , packet1.FF , packet1.P , packet1.I , packet1.D , packet1.SRate , packet1.PDmod );
+ mavlink_msg_pid_tuning_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_DEEPSTALL >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_deepstall_t packet_in = {
+ 963497464,963497672,963497880,963498088,963498296,963498504,185.0,213.0,241.0,113
+ };
+ mavlink_deepstall_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.landing_lat = packet_in.landing_lat;
+ packet1.landing_lon = packet_in.landing_lon;
+ packet1.path_lat = packet_in.path_lat;
+ packet1.path_lon = packet_in.path_lon;
+ packet1.arc_entry_lat = packet_in.arc_entry_lat;
+ packet1.arc_entry_lon = packet_in.arc_entry_lon;
+ packet1.altitude = packet_in.altitude;
+ packet1.expected_travel_distance = packet_in.expected_travel_distance;
+ packet1.cross_track_error = packet_in.cross_track_error;
+ packet1.stage = packet_in.stage;
+
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_DEEPSTALL_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_DEEPSTALL_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_deepstall_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_deepstall_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_deepstall_pack(system_id, component_id, &msg , packet1.landing_lat , packet1.landing_lon , packet1.path_lat , packet1.path_lon , packet1.arc_entry_lat , packet1.arc_entry_lon , packet1.altitude , packet1.expected_travel_distance , packet1.cross_track_error , packet1.stage );
+ mavlink_msg_deepstall_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_deepstall_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.landing_lat , packet1.landing_lon , packet1.path_lat , packet1.path_lon , packet1.arc_entry_lat , packet1.arc_entry_lon , packet1.altitude , packet1.expected_travel_distance , packet1.cross_track_error , packet1.stage );
+ mavlink_msg_deepstall_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_GIMBAL_REPORT >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_gimbal_report_t packet_in = {
+ 17.0,45.0,73.0,101.0,129.0,157.0,185.0,213.0,241.0,269.0,125,192
+ };
+ mavlink_gimbal_report_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.delta_time = packet_in.delta_time;
+ packet1.delta_angle_x = packet_in.delta_angle_x;
+ packet1.delta_angle_y = packet_in.delta_angle_y;
+ packet1.delta_angle_z = packet_in.delta_angle_z;
+ packet1.delta_velocity_x = packet_in.delta_velocity_x;
+ packet1.delta_velocity_y = packet_in.delta_velocity_y;
+ packet1.delta_velocity_z = packet_in.delta_velocity_z;
+ packet1.joint_roll = packet_in.joint_roll;
+ packet1.joint_el = packet_in.joint_el;
+ packet1.joint_az = packet_in.joint_az;
+ packet1.target_system = packet_in.target_system;
+ packet1.target_component = packet_in.target_component;
+
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_GIMBAL_REPORT_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_GIMBAL_REPORT_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_gimbal_report_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_gimbal_report_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_gimbal_report_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.delta_time , packet1.delta_angle_x , packet1.delta_angle_y , packet1.delta_angle_z , packet1.delta_velocity_x , packet1.delta_velocity_y , packet1.delta_velocity_z , packet1.joint_roll , packet1.joint_el , packet1.joint_az );
+ mavlink_msg_gimbal_report_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_gimbal_report_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.delta_time , packet1.delta_angle_x , packet1.delta_angle_y , packet1.delta_angle_z , packet1.delta_velocity_x , packet1.delta_velocity_y , packet1.delta_velocity_z , packet1.joint_roll , packet1.joint_el , packet1.joint_az );
+ mavlink_msg_gimbal_report_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_GIMBAL_CONTROL >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_gimbal_control_t packet_in = {
+ 17.0,45.0,73.0,41,108
+ };
+ mavlink_gimbal_control_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.demanded_rate_x = packet_in.demanded_rate_x;
+ packet1.demanded_rate_y = packet_in.demanded_rate_y;
+ packet1.demanded_rate_z = packet_in.demanded_rate_z;
+ packet1.target_system = packet_in.target_system;
+ packet1.target_component = packet_in.target_component;
+
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_GIMBAL_CONTROL_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_GIMBAL_CONTROL_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_gimbal_control_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_gimbal_control_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_gimbal_control_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.demanded_rate_x , packet1.demanded_rate_y , packet1.demanded_rate_z );
+ mavlink_msg_gimbal_control_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_gimbal_control_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.demanded_rate_x , packet1.demanded_rate_y , packet1.demanded_rate_z );
+ mavlink_msg_gimbal_control_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_gimbal_torque_cmd_report_t packet_in = {
+ 17235,17339,17443,151,218
+ };
+ mavlink_gimbal_torque_cmd_report_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.rl_torque_cmd = packet_in.rl_torque_cmd;
+ packet1.el_torque_cmd = packet_in.el_torque_cmd;
+ packet1.az_torque_cmd = packet_in.az_torque_cmd;
+ packet1.target_system = packet_in.target_system;
+ packet1.target_component = packet_in.target_component;
+
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_GIMBAL_TORQUE_CMD_REPORT_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_gimbal_torque_cmd_report_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_gimbal_torque_cmd_report_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_gimbal_torque_cmd_report_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.rl_torque_cmd , packet1.el_torque_cmd , packet1.az_torque_cmd );
+ mavlink_msg_gimbal_torque_cmd_report_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_gimbal_torque_cmd_report_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.rl_torque_cmd , packet1.el_torque_cmd , packet1.az_torque_cmd );
+ mavlink_msg_gimbal_torque_cmd_report_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_GOPRO_HEARTBEAT >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_gopro_heartbeat_t packet_in = {
+ 5,72,139
+ };
+ mavlink_gopro_heartbeat_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.status = packet_in.status;
+ packet1.capture_mode = packet_in.capture_mode;
+ packet1.flags = packet_in.flags;
+
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_GOPRO_HEARTBEAT_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_GOPRO_HEARTBEAT_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_gopro_heartbeat_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_gopro_heartbeat_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_gopro_heartbeat_pack(system_id, component_id, &msg , packet1.status , packet1.capture_mode , packet1.flags );
+ mavlink_msg_gopro_heartbeat_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_gopro_heartbeat_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.status , packet1.capture_mode , packet1.flags );
+ mavlink_msg_gopro_heartbeat_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_GOPRO_GET_REQUEST >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_gopro_get_request_t packet_in = {
+ 5,72,139
+ };
+ mavlink_gopro_get_request_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.target_system = packet_in.target_system;
+ packet1.target_component = packet_in.target_component;
+ packet1.cmd_id = packet_in.cmd_id;
+
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_GOPRO_GET_REQUEST_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_GOPRO_GET_REQUEST_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_gopro_get_request_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_gopro_get_request_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_gopro_get_request_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.cmd_id );
+ mavlink_msg_gopro_get_request_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_gopro_get_request_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.cmd_id );
+ mavlink_msg_gopro_get_request_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_GOPRO_GET_RESPONSE >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_gopro_get_response_t packet_in = {
+ 5,72,{ 139, 140, 141, 142 }
+ };
+ mavlink_gopro_get_response_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.cmd_id = packet_in.cmd_id;
+ packet1.status = packet_in.status;
+
+ mav_array_memcpy(packet1.value, packet_in.value, sizeof(uint8_t)*4);
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_GOPRO_GET_RESPONSE_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_gopro_get_response_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_gopro_get_response_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_gopro_get_response_pack(system_id, component_id, &msg , packet1.cmd_id , packet1.status , packet1.value );
+ mavlink_msg_gopro_get_response_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_gopro_get_response_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.cmd_id , packet1.status , packet1.value );
+ mavlink_msg_gopro_get_response_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_GOPRO_SET_REQUEST >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_gopro_set_request_t packet_in = {
+ 5,72,139,{ 206, 207, 208, 209 }
+ };
+ mavlink_gopro_set_request_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.target_system = packet_in.target_system;
+ packet1.target_component = packet_in.target_component;
+ packet1.cmd_id = packet_in.cmd_id;
+
+ mav_array_memcpy(packet1.value, packet_in.value, sizeof(uint8_t)*4);
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_GOPRO_SET_REQUEST_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_GOPRO_SET_REQUEST_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_gopro_set_request_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_gopro_set_request_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_gopro_set_request_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.cmd_id , packet1.value );
+ mavlink_msg_gopro_set_request_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_gopro_set_request_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.cmd_id , packet1.value );
+ mavlink_msg_gopro_set_request_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_GOPRO_SET_RESPONSE >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_gopro_set_response_t packet_in = {
+ 5,72
+ };
+ mavlink_gopro_set_response_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.cmd_id = packet_in.cmd_id;
+ packet1.status = packet_in.status;
+
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_GOPRO_SET_RESPONSE_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_gopro_set_response_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_gopro_set_response_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_gopro_set_response_pack(system_id, component_id, &msg , packet1.cmd_id , packet1.status );
+ mavlink_msg_gopro_set_response_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_gopro_set_response_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.cmd_id , packet1.status );
+ mavlink_msg_gopro_set_response_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_RPM >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_rpm_t packet_in = {
+ 17.0,45.0
+ };
+ mavlink_rpm_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.rpm1 = packet_in.rpm1;
+ packet1.rpm2 = packet_in.rpm2;
+
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_RPM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_RPM_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_rpm_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_rpm_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_rpm_pack(system_id, component_id, &msg , packet1.rpm1 , packet1.rpm2 );
+ mavlink_msg_rpm_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_rpm_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.rpm1 , packet1.rpm2 );
+ mavlink_msg_rpm_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_DEVICE_OP_READ >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_device_op_read_t packet_in = {
+ 963497464,17,84,151,218,29,"JKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUV",216,27,94
+ };
+ mavlink_device_op_read_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.request_id = packet_in.request_id;
+ packet1.target_system = packet_in.target_system;
+ packet1.target_component = packet_in.target_component;
+ packet1.bustype = packet_in.bustype;
+ packet1.bus = packet_in.bus;
+ packet1.address = packet_in.address;
+ packet1.regstart = packet_in.regstart;
+ packet1.count = packet_in.count;
+ packet1.bank = packet_in.bank;
+
+ mav_array_memcpy(packet1.busname, packet_in.busname, sizeof(char)*40);
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_DEVICE_OP_READ_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_DEVICE_OP_READ_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_device_op_read_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_device_op_read_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_device_op_read_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.request_id , packet1.bustype , packet1.bus , packet1.address , packet1.busname , packet1.regstart , packet1.count , packet1.bank );
+ mavlink_msg_device_op_read_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_device_op_read_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.request_id , packet1.bustype , packet1.bus , packet1.address , packet1.busname , packet1.regstart , packet1.count , packet1.bank );
+ mavlink_msg_device_op_read_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_device_op_read_reply_t packet_in = {
+ 963497464,17,84,151,{ 218, 219, 220, 221, 222, 223, 224, 225, 226, 227, 228, 229, 230, 231, 232, 233, 234, 235, 236, 237, 238, 239, 240, 241, 242, 243, 244, 245, 246, 247, 248, 249, 250, 251, 252, 253, 254, 255, 0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 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
+ };
+ mavlink_device_op_read_reply_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.request_id = packet_in.request_id;
+ packet1.result = packet_in.result;
+ packet1.regstart = packet_in.regstart;
+ packet1.count = packet_in.count;
+ packet1.bank = packet_in.bank;
+
+ 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_DEVICE_OP_READ_REPLY_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_DEVICE_OP_READ_REPLY_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_device_op_read_reply_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_device_op_read_reply_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_device_op_read_reply_pack(system_id, component_id, &msg , packet1.request_id , packet1.result , packet1.regstart , packet1.count , packet1.data , packet1.bank );
+ mavlink_msg_device_op_read_reply_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_device_op_read_reply_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.request_id , packet1.result , packet1.regstart , packet1.count , packet1.data , packet1.bank );
+ mavlink_msg_device_op_read_reply_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_DEVICE_OP_WRITE >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_device_op_write_t packet_in = {
+ 963497464,17,84,151,218,29,"JKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUV",216,27,{ 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, 145, 146, 147, 148, 149, 150, 151, 152, 153, 154, 155, 156, 157, 158, 159, 160, 161, 162, 163, 164, 165, 166, 167, 168, 169, 170, 171, 172, 173, 174, 175, 176, 177, 178, 179, 180, 181, 182, 183, 184, 185, 186, 187, 188, 189, 190, 191, 192, 193, 194, 195, 196, 197, 198, 199, 200, 201, 202, 203, 204, 205, 206, 207, 208, 209, 210, 211, 212, 213, 214, 215, 216, 217, 218, 219, 220, 221 },222
+ };
+ mavlink_device_op_write_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.request_id = packet_in.request_id;
+ packet1.target_system = packet_in.target_system;
+ packet1.target_component = packet_in.target_component;
+ packet1.bustype = packet_in.bustype;
+ packet1.bus = packet_in.bus;
+ packet1.address = packet_in.address;
+ packet1.regstart = packet_in.regstart;
+ packet1.count = packet_in.count;
+ packet1.bank = packet_in.bank;
+
+ mav_array_memcpy(packet1.busname, packet_in.busname, sizeof(char)*40);
+ 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_DEVICE_OP_WRITE_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_DEVICE_OP_WRITE_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_device_op_write_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_device_op_write_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_device_op_write_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.request_id , packet1.bustype , packet1.bus , packet1.address , packet1.busname , packet1.regstart , packet1.count , packet1.data , packet1.bank );
+ mavlink_msg_device_op_write_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_device_op_write_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.request_id , packet1.bustype , packet1.bus , packet1.address , packet1.busname , packet1.regstart , packet1.count , packet1.data , packet1.bank );
+ mavlink_msg_device_op_write_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_device_op_write_reply_t packet_in = {
+ 963497464,17
+ };
+ mavlink_device_op_write_reply_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.request_id = packet_in.request_id;
+ packet1.result = packet_in.result;
+
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_DEVICE_OP_WRITE_REPLY_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_device_op_write_reply_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_device_op_write_reply_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_device_op_write_reply_pack(system_id, component_id, &msg , packet1.request_id , packet1.result );
+ mavlink_msg_device_op_write_reply_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_device_op_write_reply_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.request_id , packet1.result );
+ mavlink_msg_device_op_write_reply_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_SECURE_COMMAND >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_secure_command_t packet_in = {
+ 963497464,963497672,29,96,163,230,{ 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, 145, 146, 147, 148, 149, 150, 151, 152, 153, 154, 155, 156, 157, 158, 159, 160, 161, 162, 163, 164, 165, 166, 167, 168, 169, 170, 171, 172, 173, 174, 175, 176, 177, 178, 179, 180, 181, 182, 183, 184, 185, 186, 187, 188, 189, 190, 191, 192, 193, 194, 195, 196, 197, 198, 199, 200, 201, 202, 203, 204, 205, 206, 207, 208, 209, 210, 211, 212, 213, 214, 215, 216, 217, 218, 219, 220, 221, 222, 223, 224, 225, 226, 227, 228, 229, 230, 231, 232, 233, 234, 235, 236, 237, 238, 239, 240, 241, 242, 243, 244, 245, 246, 247, 248, 249, 250, 251, 252, 253, 254, 255, 0, 1, 2, 3, 4 }
+ };
+ mavlink_secure_command_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.sequence = packet_in.sequence;
+ packet1.operation = packet_in.operation;
+ packet1.target_system = packet_in.target_system;
+ packet1.target_component = packet_in.target_component;
+ packet1.data_length = packet_in.data_length;
+ packet1.sig_length = packet_in.sig_length;
+
+ mav_array_memcpy(packet1.data, packet_in.data, sizeof(uint8_t)*220);
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_SECURE_COMMAND_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SECURE_COMMAND_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_secure_command_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_secure_command_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_secure_command_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.sequence , packet1.operation , packet1.data_length , packet1.sig_length , packet1.data );
+ mavlink_msg_secure_command_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_secure_command_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.sequence , packet1.operation , packet1.data_length , packet1.sig_length , packet1.data );
+ mavlink_msg_secure_command_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_SECURE_COMMAND_REPLY >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_secure_command_reply_t packet_in = {
+ 963497464,963497672,29,96,{ 163, 164, 165, 166, 167, 168, 169, 170, 171, 172, 173, 174, 175, 176, 177, 178, 179, 180, 181, 182, 183, 184, 185, 186, 187, 188, 189, 190, 191, 192, 193, 194, 195, 196, 197, 198, 199, 200, 201, 202, 203, 204, 205, 206, 207, 208, 209, 210, 211, 212, 213, 214, 215, 216, 217, 218, 219, 220, 221, 222, 223, 224, 225, 226, 227, 228, 229, 230, 231, 232, 233, 234, 235, 236, 237, 238, 239, 240, 241, 242, 243, 244, 245, 246, 247, 248, 249, 250, 251, 252, 253, 254, 255, 0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 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 }
+ };
+ mavlink_secure_command_reply_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.sequence = packet_in.sequence;
+ packet1.operation = packet_in.operation;
+ packet1.result = packet_in.result;
+ packet1.data_length = packet_in.data_length;
+
+ mav_array_memcpy(packet1.data, packet_in.data, sizeof(uint8_t)*220);
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_SECURE_COMMAND_REPLY_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_SECURE_COMMAND_REPLY_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_secure_command_reply_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_secure_command_reply_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_secure_command_reply_pack(system_id, component_id, &msg , packet1.sequence , packet1.operation , packet1.result , packet1.data_length , packet1.data );
+ mavlink_msg_secure_command_reply_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_secure_command_reply_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.sequence , packet1.operation , packet1.result , packet1.data_length , packet1.data );
+ mavlink_msg_secure_command_reply_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_ADAP_TUNING >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_adap_tuning_t packet_in = {
+ 17.0,45.0,73.0,101.0,129.0,157.0,185.0,213.0,241.0,269.0,297.0,325.0,149
+ };
+ mavlink_adap_tuning_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.desired = packet_in.desired;
+ packet1.achieved = packet_in.achieved;
+ packet1.error = packet_in.error;
+ packet1.theta = packet_in.theta;
+ packet1.omega = packet_in.omega;
+ packet1.sigma = packet_in.sigma;
+ packet1.theta_dot = packet_in.theta_dot;
+ packet1.omega_dot = packet_in.omega_dot;
+ packet1.sigma_dot = packet_in.sigma_dot;
+ packet1.f = packet_in.f;
+ packet1.f_dot = packet_in.f_dot;
+ packet1.u = packet_in.u;
+ packet1.axis = packet_in.axis;
+
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_ADAP_TUNING_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_ADAP_TUNING_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_adap_tuning_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_adap_tuning_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_adap_tuning_pack(system_id, component_id, &msg , packet1.axis , packet1.desired , packet1.achieved , packet1.error , packet1.theta , packet1.omega , packet1.sigma , packet1.theta_dot , packet1.omega_dot , packet1.sigma_dot , packet1.f , packet1.f_dot , packet1.u );
+ mavlink_msg_adap_tuning_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_adap_tuning_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.axis , packet1.desired , packet1.achieved , packet1.error , packet1.theta , packet1.omega , packet1.sigma , packet1.theta_dot , packet1.omega_dot , packet1.sigma_dot , packet1.f , packet1.f_dot , packet1.u );
+ mavlink_msg_adap_tuning_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_VISION_POSITION_DELTA >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_vision_position_delta_t packet_in = {
+ 93372036854775807ULL,93372036854776311ULL,{ 129.0, 130.0, 131.0 },{ 213.0, 214.0, 215.0 },297.0
+ };
+ mavlink_vision_position_delta_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.time_usec = packet_in.time_usec;
+ packet1.time_delta_usec = packet_in.time_delta_usec;
+ packet1.confidence = packet_in.confidence;
+
+ mav_array_memcpy(packet1.angle_delta, packet_in.angle_delta, sizeof(float)*3);
+ mav_array_memcpy(packet1.position_delta, packet_in.position_delta, sizeof(float)*3);
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_VISION_POSITION_DELTA_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_VISION_POSITION_DELTA_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_vision_position_delta_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_vision_position_delta_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_vision_position_delta_pack(system_id, component_id, &msg , packet1.time_usec , packet1.time_delta_usec , packet1.angle_delta , packet1.position_delta , packet1.confidence );
+ mavlink_msg_vision_position_delta_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_vision_position_delta_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.time_delta_usec , packet1.angle_delta , packet1.position_delta , packet1.confidence );
+ mavlink_msg_vision_position_delta_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_AOA_SSA >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_aoa_ssa_t packet_in = {
+ 93372036854775807ULL,73.0,101.0
+ };
+ mavlink_aoa_ssa_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.time_usec = packet_in.time_usec;
+ packet1.AOA = packet_in.AOA;
+ packet1.SSA = packet_in.SSA;
+
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_AOA_SSA_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_AOA_SSA_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_aoa_ssa_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_aoa_ssa_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_aoa_ssa_pack(system_id, component_id, &msg , packet1.time_usec , packet1.AOA , packet1.SSA );
+ mavlink_msg_aoa_ssa_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_aoa_ssa_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.AOA , packet1.SSA );
+ mavlink_msg_aoa_ssa_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4 >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_esc_telemetry_1_to_4_t packet_in = {
+ { 17235, 17236, 17237, 17238 },{ 17651, 17652, 17653, 17654 },{ 18067, 18068, 18069, 18070 },{ 18483, 18484, 18485, 18486 },{ 18899, 18900, 18901, 18902 },{ 125, 126, 127, 128 }
+ };
+ mavlink_esc_telemetry_1_to_4_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+
+ mav_array_memcpy(packet1.voltage, packet_in.voltage, sizeof(uint16_t)*4);
+ mav_array_memcpy(packet1.current, packet_in.current, sizeof(uint16_t)*4);
+ mav_array_memcpy(packet1.totalcurrent, packet_in.totalcurrent, sizeof(uint16_t)*4);
+ mav_array_memcpy(packet1.rpm, packet_in.rpm, sizeof(uint16_t)*4);
+ mav_array_memcpy(packet1.count, packet_in.count, sizeof(uint16_t)*4);
+ mav_array_memcpy(packet1.temperature, packet_in.temperature, sizeof(uint8_t)*4);
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_esc_telemetry_1_to_4_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_esc_telemetry_1_to_4_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_esc_telemetry_1_to_4_pack(system_id, component_id, &msg , packet1.temperature , packet1.voltage , packet1.current , packet1.totalcurrent , packet1.rpm , packet1.count );
+ mavlink_msg_esc_telemetry_1_to_4_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_esc_telemetry_1_to_4_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.temperature , packet1.voltage , packet1.current , packet1.totalcurrent , packet1.rpm , packet1.count );
+ mavlink_msg_esc_telemetry_1_to_4_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8 >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_esc_telemetry_5_to_8_t packet_in = {
+ { 17235, 17236, 17237, 17238 },{ 17651, 17652, 17653, 17654 },{ 18067, 18068, 18069, 18070 },{ 18483, 18484, 18485, 18486 },{ 18899, 18900, 18901, 18902 },{ 125, 126, 127, 128 }
+ };
+ mavlink_esc_telemetry_5_to_8_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+
+ mav_array_memcpy(packet1.voltage, packet_in.voltage, sizeof(uint16_t)*4);
+ mav_array_memcpy(packet1.current, packet_in.current, sizeof(uint16_t)*4);
+ mav_array_memcpy(packet1.totalcurrent, packet_in.totalcurrent, sizeof(uint16_t)*4);
+ mav_array_memcpy(packet1.rpm, packet_in.rpm, sizeof(uint16_t)*4);
+ mav_array_memcpy(packet1.count, packet_in.count, sizeof(uint16_t)*4);
+ mav_array_memcpy(packet1.temperature, packet_in.temperature, sizeof(uint8_t)*4);
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_esc_telemetry_5_to_8_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_esc_telemetry_5_to_8_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_esc_telemetry_5_to_8_pack(system_id, component_id, &msg , packet1.temperature , packet1.voltage , packet1.current , packet1.totalcurrent , packet1.rpm , packet1.count );
+ mavlink_msg_esc_telemetry_5_to_8_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_esc_telemetry_5_to_8_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.temperature , packet1.voltage , packet1.current , packet1.totalcurrent , packet1.rpm , packet1.count );
+ mavlink_msg_esc_telemetry_5_to_8_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12 >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_esc_telemetry_9_to_12_t packet_in = {
+ { 17235, 17236, 17237, 17238 },{ 17651, 17652, 17653, 17654 },{ 18067, 18068, 18069, 18070 },{ 18483, 18484, 18485, 18486 },{ 18899, 18900, 18901, 18902 },{ 125, 126, 127, 128 }
+ };
+ mavlink_esc_telemetry_9_to_12_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+
+ mav_array_memcpy(packet1.voltage, packet_in.voltage, sizeof(uint16_t)*4);
+ mav_array_memcpy(packet1.current, packet_in.current, sizeof(uint16_t)*4);
+ mav_array_memcpy(packet1.totalcurrent, packet_in.totalcurrent, sizeof(uint16_t)*4);
+ mav_array_memcpy(packet1.rpm, packet_in.rpm, sizeof(uint16_t)*4);
+ mav_array_memcpy(packet1.count, packet_in.count, sizeof(uint16_t)*4);
+ mav_array_memcpy(packet1.temperature, packet_in.temperature, sizeof(uint8_t)*4);
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_esc_telemetry_9_to_12_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_esc_telemetry_9_to_12_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_esc_telemetry_9_to_12_pack(system_id, component_id, &msg , packet1.temperature , packet1.voltage , packet1.current , packet1.totalcurrent , packet1.rpm , packet1.count );
+ mavlink_msg_esc_telemetry_9_to_12_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_esc_telemetry_9_to_12_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.temperature , packet1.voltage , packet1.current , packet1.totalcurrent , packet1.rpm , packet1.count );
+ mavlink_msg_esc_telemetry_9_to_12_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_OSD_PARAM_CONFIG >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_osd_param_config_t packet_in = {
+ 963497464,45.0,73.0,101.0,53,120,187,254,"UVWXYZABCDEFGHI",113
+ };
+ mavlink_osd_param_config_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.request_id = packet_in.request_id;
+ packet1.min_value = packet_in.min_value;
+ packet1.max_value = packet_in.max_value;
+ packet1.increment = packet_in.increment;
+ packet1.target_system = packet_in.target_system;
+ packet1.target_component = packet_in.target_component;
+ packet1.osd_screen = packet_in.osd_screen;
+ packet1.osd_index = packet_in.osd_index;
+ packet1.config_type = packet_in.config_type;
+
+ mav_array_memcpy(packet1.param_id, packet_in.param_id, sizeof(char)*16);
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_OSD_PARAM_CONFIG_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_OSD_PARAM_CONFIG_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_osd_param_config_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_osd_param_config_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_osd_param_config_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.request_id , packet1.osd_screen , packet1.osd_index , packet1.param_id , packet1.config_type , packet1.min_value , packet1.max_value , packet1.increment );
+ mavlink_msg_osd_param_config_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_osd_param_config_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.request_id , packet1.osd_screen , packet1.osd_index , packet1.param_id , packet1.config_type , packet1.min_value , packet1.max_value , packet1.increment );
+ mavlink_msg_osd_param_config_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_OSD_PARAM_CONFIG_REPLY >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_osd_param_config_reply_t packet_in = {
+ 963497464,17
+ };
+ mavlink_osd_param_config_reply_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.request_id = packet_in.request_id;
+ packet1.result = packet_in.result;
+
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_OSD_PARAM_CONFIG_REPLY_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_OSD_PARAM_CONFIG_REPLY_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_osd_param_config_reply_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_osd_param_config_reply_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_osd_param_config_reply_pack(system_id, component_id, &msg , packet1.request_id , packet1.result );
+ mavlink_msg_osd_param_config_reply_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_osd_param_config_reply_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.request_id , packet1.result );
+ mavlink_msg_osd_param_config_reply_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_osd_param_show_config_t packet_in = {
+ 963497464,17,84,151,218
+ };
+ mavlink_osd_param_show_config_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.request_id = packet_in.request_id;
+ packet1.target_system = packet_in.target_system;
+ packet1.target_component = packet_in.target_component;
+ packet1.osd_screen = packet_in.osd_screen;
+ packet1.osd_index = packet_in.osd_index;
+
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_osd_param_show_config_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_osd_param_show_config_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_osd_param_show_config_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.request_id , packet1.osd_screen , packet1.osd_index );
+ mavlink_msg_osd_param_show_config_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_osd_param_show_config_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.request_id , packet1.osd_screen , packet1.osd_index );
+ mavlink_msg_osd_param_show_config_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_REPLY >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_osd_param_show_config_reply_t packet_in = {
+ 963497464,45.0,73.0,101.0,53,"RSTUVWXYZABCDEF",168
+ };
+ mavlink_osd_param_show_config_reply_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.request_id = packet_in.request_id;
+ packet1.min_value = packet_in.min_value;
+ packet1.max_value = packet_in.max_value;
+ packet1.increment = packet_in.increment;
+ packet1.result = packet_in.result;
+ packet1.config_type = packet_in.config_type;
+
+ mav_array_memcpy(packet1.param_id, packet_in.param_id, sizeof(char)*16);
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_REPLY_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_OSD_PARAM_SHOW_CONFIG_REPLY_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_osd_param_show_config_reply_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_osd_param_show_config_reply_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_osd_param_show_config_reply_pack(system_id, component_id, &msg , packet1.request_id , packet1.result , packet1.param_id , packet1.config_type , packet1.min_value , packet1.max_value , packet1.increment );
+ mavlink_msg_osd_param_show_config_reply_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_osd_param_show_config_reply_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.request_id , packet1.result , packet1.param_id , packet1.config_type , packet1.min_value , packet1.max_value , packet1.increment );
+ mavlink_msg_osd_param_show_config_reply_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_OBSTACLE_DISTANCE_3D >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_obstacle_distance_3d_t packet_in = {
+ 963497464,45.0,73.0,101.0,129.0,157.0,18483,211,22
+ };
+ mavlink_obstacle_distance_3d_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.time_boot_ms = packet_in.time_boot_ms;
+ packet1.x = packet_in.x;
+ packet1.y = packet_in.y;
+ packet1.z = packet_in.z;
+ packet1.min_distance = packet_in.min_distance;
+ packet1.max_distance = packet_in.max_distance;
+ packet1.obstacle_id = packet_in.obstacle_id;
+ packet1.sensor_type = packet_in.sensor_type;
+ packet1.frame = packet_in.frame;
+
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_OBSTACLE_DISTANCE_3D_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_OBSTACLE_DISTANCE_3D_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_obstacle_distance_3d_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_obstacle_distance_3d_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_obstacle_distance_3d_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.sensor_type , packet1.frame , packet1.obstacle_id , packet1.x , packet1.y , packet1.z , packet1.min_distance , packet1.max_distance );
+ mavlink_msg_obstacle_distance_3d_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_obstacle_distance_3d_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.sensor_type , packet1.frame , packet1.obstacle_id , packet1.x , packet1.y , packet1.z , packet1.min_distance , packet1.max_distance );
+ mavlink_msg_obstacle_distance_3d_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_WATER_DEPTH >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_water_depth_t packet_in = {
+ 963497464,963497672,963497880,101.0,129.0,157.0,185.0,213.0,241.0,113,180
+ };
+ mavlink_water_depth_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.time_boot_ms = packet_in.time_boot_ms;
+ packet1.lat = packet_in.lat;
+ packet1.lng = packet_in.lng;
+ packet1.alt = packet_in.alt;
+ packet1.roll = packet_in.roll;
+ packet1.pitch = packet_in.pitch;
+ packet1.yaw = packet_in.yaw;
+ packet1.distance = packet_in.distance;
+ packet1.temperature = packet_in.temperature;
+ packet1.id = packet_in.id;
+ packet1.healthy = packet_in.healthy;
+
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_WATER_DEPTH_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_WATER_DEPTH_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_water_depth_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_water_depth_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_water_depth_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.id , packet1.healthy , packet1.lat , packet1.lng , packet1.alt , packet1.roll , packet1.pitch , packet1.yaw , packet1.distance , packet1.temperature );
+ mavlink_msg_water_depth_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_water_depth_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.id , packet1.healthy , packet1.lat , packet1.lng , packet1.alt , packet1.roll , packet1.pitch , packet1.yaw , packet1.distance , packet1.temperature );
+ mavlink_msg_water_depth_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_MCU_STATUS >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_mcu_status_t packet_in = {
+ 17235,17339,17443,17547,29
+ };
+ mavlink_mcu_status_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.MCU_temperature = packet_in.MCU_temperature;
+ packet1.MCU_voltage = packet_in.MCU_voltage;
+ packet1.MCU_voltage_min = packet_in.MCU_voltage_min;
+ packet1.MCU_voltage_max = packet_in.MCU_voltage_max;
+ packet1.id = packet_in.id;
+
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_MCU_STATUS_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_MCU_STATUS_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_mcu_status_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_mcu_status_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_mcu_status_pack(system_id, component_id, &msg , packet1.id , packet1.MCU_temperature , packet1.MCU_voltage , packet1.MCU_voltage_min , packet1.MCU_voltage_max );
+ mavlink_msg_mcu_status_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_mcu_status_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.id , packet1.MCU_temperature , packet1.MCU_voltage , packet1.MCU_voltage_min , packet1.MCU_voltage_max );
+ mavlink_msg_mcu_status_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_ESC_TELEMETRY_13_TO_16 >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_esc_telemetry_13_to_16_t packet_in = {
+ { 17235, 17236, 17237, 17238 },{ 17651, 17652, 17653, 17654 },{ 18067, 18068, 18069, 18070 },{ 18483, 18484, 18485, 18486 },{ 18899, 18900, 18901, 18902 },{ 125, 126, 127, 128 }
+ };
+ mavlink_esc_telemetry_13_to_16_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+
+ mav_array_memcpy(packet1.voltage, packet_in.voltage, sizeof(uint16_t)*4);
+ mav_array_memcpy(packet1.current, packet_in.current, sizeof(uint16_t)*4);
+ mav_array_memcpy(packet1.totalcurrent, packet_in.totalcurrent, sizeof(uint16_t)*4);
+ mav_array_memcpy(packet1.rpm, packet_in.rpm, sizeof(uint16_t)*4);
+ mav_array_memcpy(packet1.count, packet_in.count, sizeof(uint16_t)*4);
+ mav_array_memcpy(packet1.temperature, packet_in.temperature, sizeof(uint8_t)*4);
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_ESC_TELEMETRY_13_TO_16_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_ESC_TELEMETRY_13_TO_16_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_esc_telemetry_13_to_16_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_esc_telemetry_13_to_16_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_esc_telemetry_13_to_16_pack(system_id, component_id, &msg , packet1.temperature , packet1.voltage , packet1.current , packet1.totalcurrent , packet1.rpm , packet1.count );
+ mavlink_msg_esc_telemetry_13_to_16_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_esc_telemetry_13_to_16_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.temperature , packet1.voltage , packet1.current , packet1.totalcurrent , packet1.rpm , packet1.count );
+ mavlink_msg_esc_telemetry_13_to_16_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_ESC_TELEMETRY_17_TO_20 >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_esc_telemetry_17_to_20_t packet_in = {
+ { 17235, 17236, 17237, 17238 },{ 17651, 17652, 17653, 17654 },{ 18067, 18068, 18069, 18070 },{ 18483, 18484, 18485, 18486 },{ 18899, 18900, 18901, 18902 },{ 125, 126, 127, 128 }
+ };
+ mavlink_esc_telemetry_17_to_20_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+
+ mav_array_memcpy(packet1.voltage, packet_in.voltage, sizeof(uint16_t)*4);
+ mav_array_memcpy(packet1.current, packet_in.current, sizeof(uint16_t)*4);
+ mav_array_memcpy(packet1.totalcurrent, packet_in.totalcurrent, sizeof(uint16_t)*4);
+ mav_array_memcpy(packet1.rpm, packet_in.rpm, sizeof(uint16_t)*4);
+ mav_array_memcpy(packet1.count, packet_in.count, sizeof(uint16_t)*4);
+ mav_array_memcpy(packet1.temperature, packet_in.temperature, sizeof(uint8_t)*4);
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_ESC_TELEMETRY_17_TO_20_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_ESC_TELEMETRY_17_TO_20_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_esc_telemetry_17_to_20_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_esc_telemetry_17_to_20_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_esc_telemetry_17_to_20_pack(system_id, component_id, &msg , packet1.temperature , packet1.voltage , packet1.current , packet1.totalcurrent , packet1.rpm , packet1.count );
+ mavlink_msg_esc_telemetry_17_to_20_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_esc_telemetry_17_to_20_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.temperature , packet1.voltage , packet1.current , packet1.totalcurrent , packet1.rpm , packet1.count );
+ mavlink_msg_esc_telemetry_17_to_20_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_ESC_TELEMETRY_21_TO_24 >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_esc_telemetry_21_to_24_t packet_in = {
+ { 17235, 17236, 17237, 17238 },{ 17651, 17652, 17653, 17654 },{ 18067, 18068, 18069, 18070 },{ 18483, 18484, 18485, 18486 },{ 18899, 18900, 18901, 18902 },{ 125, 126, 127, 128 }
+ };
+ mavlink_esc_telemetry_21_to_24_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+
+ mav_array_memcpy(packet1.voltage, packet_in.voltage, sizeof(uint16_t)*4);
+ mav_array_memcpy(packet1.current, packet_in.current, sizeof(uint16_t)*4);
+ mav_array_memcpy(packet1.totalcurrent, packet_in.totalcurrent, sizeof(uint16_t)*4);
+ mav_array_memcpy(packet1.rpm, packet_in.rpm, sizeof(uint16_t)*4);
+ mav_array_memcpy(packet1.count, packet_in.count, sizeof(uint16_t)*4);
+ mav_array_memcpy(packet1.temperature, packet_in.temperature, sizeof(uint8_t)*4);
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_ESC_TELEMETRY_21_TO_24_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_ESC_TELEMETRY_21_TO_24_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_esc_telemetry_21_to_24_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_esc_telemetry_21_to_24_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_esc_telemetry_21_to_24_pack(system_id, component_id, &msg , packet1.temperature , packet1.voltage , packet1.current , packet1.totalcurrent , packet1.rpm , packet1.count );
+ mavlink_msg_esc_telemetry_21_to_24_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_esc_telemetry_21_to_24_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.temperature , packet1.voltage , packet1.current , packet1.totalcurrent , packet1.rpm , packet1.count );
+ mavlink_msg_esc_telemetry_21_to_24_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_ESC_TELEMETRY_25_TO_28 >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_esc_telemetry_25_to_28_t packet_in = {
+ { 17235, 17236, 17237, 17238 },{ 17651, 17652, 17653, 17654 },{ 18067, 18068, 18069, 18070 },{ 18483, 18484, 18485, 18486 },{ 18899, 18900, 18901, 18902 },{ 125, 126, 127, 128 }
+ };
+ mavlink_esc_telemetry_25_to_28_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+
+ mav_array_memcpy(packet1.voltage, packet_in.voltage, sizeof(uint16_t)*4);
+ mav_array_memcpy(packet1.current, packet_in.current, sizeof(uint16_t)*4);
+ mav_array_memcpy(packet1.totalcurrent, packet_in.totalcurrent, sizeof(uint16_t)*4);
+ mav_array_memcpy(packet1.rpm, packet_in.rpm, sizeof(uint16_t)*4);
+ mav_array_memcpy(packet1.count, packet_in.count, sizeof(uint16_t)*4);
+ mav_array_memcpy(packet1.temperature, packet_in.temperature, sizeof(uint8_t)*4);
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_ESC_TELEMETRY_25_TO_28_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_ESC_TELEMETRY_25_TO_28_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_esc_telemetry_25_to_28_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_esc_telemetry_25_to_28_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_esc_telemetry_25_to_28_pack(system_id, component_id, &msg , packet1.temperature , packet1.voltage , packet1.current , packet1.totalcurrent , packet1.rpm , packet1.count );
+ mavlink_msg_esc_telemetry_25_to_28_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_esc_telemetry_25_to_28_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.temperature , packet1.voltage , packet1.current , packet1.totalcurrent , packet1.rpm , packet1.count );
+ mavlink_msg_esc_telemetry_25_to_28_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_ESC_TELEMETRY_29_TO_32 >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_esc_telemetry_29_to_32_t packet_in = {
+ { 17235, 17236, 17237, 17238 },{ 17651, 17652, 17653, 17654 },{ 18067, 18068, 18069, 18070 },{ 18483, 18484, 18485, 18486 },{ 18899, 18900, 18901, 18902 },{ 125, 126, 127, 128 }
+ };
+ mavlink_esc_telemetry_29_to_32_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+
+ mav_array_memcpy(packet1.voltage, packet_in.voltage, sizeof(uint16_t)*4);
+ mav_array_memcpy(packet1.current, packet_in.current, sizeof(uint16_t)*4);
+ mav_array_memcpy(packet1.totalcurrent, packet_in.totalcurrent, sizeof(uint16_t)*4);
+ mav_array_memcpy(packet1.rpm, packet_in.rpm, sizeof(uint16_t)*4);
+ mav_array_memcpy(packet1.count, packet_in.count, sizeof(uint16_t)*4);
+ mav_array_memcpy(packet1.temperature, packet_in.temperature, sizeof(uint8_t)*4);
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_ESC_TELEMETRY_29_TO_32_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_ESC_TELEMETRY_29_TO_32_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_esc_telemetry_29_to_32_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_esc_telemetry_29_to_32_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_esc_telemetry_29_to_32_pack(system_id, component_id, &msg , packet1.temperature , packet1.voltage , packet1.current , packet1.totalcurrent , packet1.rpm , packet1.count );
+ mavlink_msg_esc_telemetry_29_to_32_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_esc_telemetry_29_to_32_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.temperature , packet1.voltage , packet1.current , packet1.totalcurrent , packet1.rpm , packet1.count );
+ mavlink_msg_esc_telemetry_29_to_32_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_NAMED_VALUE_STRING >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_named_value_string_t packet_in = {
+ 963497464,"EFGHIJKLM","OPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXY"
+ };
+ mavlink_named_value_string_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.time_boot_ms = packet_in.time_boot_ms;
+
+ mav_array_memcpy(packet1.name, packet_in.name, sizeof(char)*10);
+ mav_array_memcpy(packet1.value, packet_in.value, sizeof(char)*64);
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_NAMED_VALUE_STRING_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_NAMED_VALUE_STRING_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_named_value_string_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_named_value_string_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_named_value_string_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.name , packet1.value );
+ mavlink_msg_named_value_string_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_named_value_string_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.name , packet1.value );
+ mavlink_msg_named_value_string_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 0 radius to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control.| Desired yaw angle at waypoint (rotary wing). NaN to use the current system yaw heading mode (e.g. yaw towards next waypoint, yaw to home, etc.).| Latitude| Longitude| Altitude| */
- MAV_CMD_NAV_LOITER_UNLIM=17, /* Loiter around this waypoint an unlimited amount of time |Empty| Empty| Loiter radius around waypoint for forward-only moving vehicles (not multicopters). If positive loiter clockwise, else counter-clockwise| Desired yaw angle. NaN to use the current system yaw heading mode (e.g. yaw towards next waypoint, yaw to home, etc.).| Latitude| Longitude| Altitude| */
- MAV_CMD_NAV_LOITER_TURNS=18, /* Loiter around this waypoint for X turns |Number of turns.| Leave loiter circle only when track heads towards the next waypoint (MAV_BOOL_FALSE: Leave when turns complete). Values not equal to 0 or 1 are invalid.| Loiter radius around waypoint for forward-only moving vehicles (not multicopters). If positive loiter clockwise, else counter-clockwise| Loiter circle exit location and/or path to next waypoint ("xtrack") for forward-only moving vehicles (not multicopters). 0 for the vehicle to converge towards the center xtrack when it leaves the loiter (the line between the centers of the current and next waypoint), 1 to converge to the direct line between the location that the vehicle exits the loiter radius and the next waypoint. Otherwise the angle (in degrees) between the tangent of the loiter circle and the center xtrack at which the vehicle must leave the loiter (and converge to the center xtrack). NaN to use the current system default xtrack behaviour.| Latitude| Longitude| Altitude| */
- MAV_CMD_NAV_LOITER_TIME=19, /* Loiter at the specified latitude, longitude and altitude for a certain amount of time. Multicopter vehicles stop at the point (within a vehicle-specific acceptance radius). Forward-only moving vehicles (e.g. fixed-wing) circle the point with the specified radius/direction. If the Heading Required parameter (2) is non-zero forward moving aircraft will only leave the loiter circle once heading towards the next waypoint. |Loiter time (only starts once Lat, Lon and Alt is reached).| Leave loiter circle only when track heading towards the next waypoint (MAV_BOOL_FALSE: Leave on time expiry). Values not equal to 0 or 1 are invalid.| Loiter radius around waypoint for forward-only moving vehicles (not multicopters). If positive loiter clockwise, else counter-clockwise.| Loiter circle exit location and/or path to next waypoint ("xtrack") for forward-only moving vehicles (not multicopters). 0 for the vehicle to converge towards the center xtrack when it leaves the loiter (the line between the centers of the current and next waypoint), 1 to converge to the direct line between the location that the vehicle exits the loiter radius and the next waypoint. Otherwise the angle (in degrees) between the tangent of the loiter circle and the center xtrack at which the vehicle must leave the loiter (and converge to the center xtrack). NaN to use the current system default xtrack behaviour.| Latitude| Longitude| Altitude| */
- MAV_CMD_NAV_RETURN_TO_LAUNCH=20, /* Return to launch location |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */
- MAV_CMD_NAV_LAND=21, /* Land at location. |Minimum target altitude if landing is aborted (0 = undefined/use system default).| Precision land mode.| Empty.| Desired yaw angle. NaN to use the current system yaw heading mode (e.g. yaw towards next waypoint, yaw to home, etc.).| Latitude.| Longitude.| Landing altitude (ground level in current frame).| */
- MAV_CMD_NAV_TAKEOFF=22, /* Takeoff from ground / hand. Vehicles that support multiple takeoff modes (e.g. VTOL quadplane) should take off using the currently configured mode. |Minimum pitch (if airspeed sensor present), desired pitch without sensor| Empty| Empty| Yaw angle (if magnetometer present), ignored without magnetometer. NaN to use the current system yaw heading mode (e.g. yaw towards next waypoint, yaw to home, etc.).| Latitude| Longitude| Altitude| */
- MAV_CMD_NAV_LAND_LOCAL=23, /* Land at local position (local frame only) |Landing target number (if available)| Maximum accepted offset from desired landing position - computed magnitude from spherical coordinates: d = sqrt(x^2 + y^2 + z^2), which gives the maximum accepted distance between the desired landing position and the position where the vehicle is about to land| Landing descend rate| Desired yaw angle| Y-axis position| X-axis position| Z-axis / ground level position| */
- MAV_CMD_NAV_TAKEOFF_LOCAL=24, /* Takeoff from local position (local frame only) |Minimum pitch (if airspeed sensor present), desired pitch without sensor| Empty| Takeoff ascend rate| Yaw angle (if magnetometer or another yaw estimation source present), ignored without one of these| Y-axis position| X-axis position| Z-axis position| */
- MAV_CMD_NAV_FOLLOW=25, /* Vehicle following, i.e. this waypoint represents the position of a moving vehicle |Following logic to use (e.g. loitering or sinusoidal following) - depends on specific autopilot implementation| Ground speed of vehicle to be followed| Radius around waypoint. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */
- MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT=30, /* Continue on the current course and climb/descend to specified altitude. When the altitude is reached continue to the next command (i.e., don't proceed to the next command until the desired altitude is reached. |Climb or Descend (0 = Neutral, command completes when within 5m of this command's altitude, 1 = Climbing, command completes when at or above this command's altitude, 2 = Descending, command completes when at or below this command's altitude.| Empty| Empty| Empty| Empty| Empty| Desired altitude| */
- MAV_CMD_NAV_LOITER_TO_ALT=31, /* Begin loiter at the specified Latitude and Longitude. If Lat=Lon=0, then loiter at the current position. Don't consider the navigation command complete (don't leave loiter) until the altitude has been reached. Additionally, if the Heading Required parameter is non-zero the aircraft will not leave the loiter until heading toward the next waypoint. |Leave loiter circle only when track heading towards the next waypoint (MAV_BOOL_FALSE: Leave when altitude reached). Values not equal to 0 or 1 are invalid.| Loiter radius around waypoint for forward-only moving vehicles (not multicopters). If positive loiter clockwise, negative counter-clockwise, 0 means no change to standard loiter.| Empty| Loiter circle exit location and/or path to next waypoint ("xtrack") for forward-only moving vehicles (not multicopters). 0 for the vehicle to converge towards the center xtrack when it leaves the loiter (the line between the centers of the current and next waypoint), 1 to converge to the direct line between the location that the vehicle exits the loiter radius and the next waypoint. Otherwise the angle (in degrees) between the tangent of the loiter circle and the center xtrack at which the vehicle must leave the loiter (and converge to the center xtrack). NaN to use the current system default xtrack behaviour.| Latitude| Longitude| Altitude| */
- MAV_CMD_DO_FOLLOW=32, /* Begin following a target |System ID (of the FOLLOW_TARGET beacon). Send 0 to disable follow-me and return to the default position hold mode.| Reserved| Reserved| Altitude mode: 0: Keep current altitude, 1: keep altitude difference to target, 2: go to a fixed altitude above home.| Altitude above home. (used if mode=2)| Reserved| Time to land in which the MAV should go to the default position hold mode after a message RX timeout.| */
- MAV_CMD_DO_FOLLOW_REPOSITION=33, /* Reposition the MAV after a follow target command has been sent |Camera q1 (where 0 is on the ray from the camera to the tracking device)| Camera q2| Camera q3| Camera q4| altitude offset from target| X offset from target| Y offset from target| */
- MAV_CMD_DO_ORBIT=34, /* Start orbiting on the circumference of a circle defined by the parameters. Setting values to NaN/INT32_MAX (as appropriate) results in using defaults. |Radius of the circle. Positive: orbit clockwise. Negative: orbit counter-clockwise. NaN: Use vehicle default radius, or current radius if already orbiting.| Tangential Velocity. NaN: Use vehicle default velocity, or current velocity if already orbiting.| Yaw behavior of the vehicle.| Orbit around the centre point for this many radians (i.e. for a three-quarter orbit set 270*Pi/180). 0: Orbit forever. NaN: Use vehicle default, or current value if already orbiting.| Center point latitude (if no MAV_FRAME specified) / X coordinate according to MAV_FRAME. INT32_MAX (or NaN if sent in COMMAND_LONG): Use current vehicle position, or current center if already orbiting.| Center point longitude (if no MAV_FRAME specified) / Y coordinate according to MAV_FRAME. INT32_MAX (or NaN if sent in COMMAND_LONG): Use current vehicle position, or current center if already orbiting.| Center point altitude (MSL) (if no MAV_FRAME specified) / Z coordinate according to MAV_FRAME. NaN: Use current vehicle altitude.| */
- MAV_CMD_NAV_ROI=80, /* Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicle's control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Region of interest mode.| Waypoint index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z| */
- MAV_CMD_NAV_PATHPLANNING=81, /* Control autonomous path planning on the MAV. |0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning| 0: Disable full path planning (without resetting map), 1: Enable, 2: Enable and reset map/occupancy grid, 3: Enable and reset planned route, but not occupancy grid| Empty| Yaw angle at goal| Latitude/X of goal| Longitude/Y of goal| Altitude/Z of goal| */
- MAV_CMD_NAV_SPLINE_WAYPOINT=82, /* Navigate to waypoint using a spline path. |Hold time. (ignored by fixed wing, time to stay at waypoint for rotary wing)| Empty| Empty| Empty| Latitude/X of goal| Longitude/Y of goal| Altitude/Z of goal| */
- MAV_CMD_NAV_VTOL_TAKEOFF=84, /* Takeoff from ground using VTOL mode, and transition to forward flight with specified heading. The command should be ignored by vehicles that dont support both VTOL and fixed-wing flight (multicopters, boats,etc.). |Empty| Front transition heading.| Empty| Yaw angle. NaN to use the current system yaw heading mode (e.g. yaw towards next waypoint, yaw to home, etc.).| Latitude| Longitude| Altitude| */
- MAV_CMD_NAV_VTOL_LAND=85, /* Land using VTOL mode |Landing behaviour.| Empty| Approach altitude (with the same reference as the Altitude field). NaN if unspecified.| Yaw angle. NaN to use the current system yaw heading mode (e.g. yaw towards next waypoint, yaw to home, etc.).| Latitude| Longitude| Altitude (ground level) relative to the current coordinate frame. NaN to use system default landing altitude (ignore value).| */
- MAV_CMD_NAV_GUIDED_ENABLE=92, /* Hand control over to an external controller |Guided mode on (MAV_BOOL_FALSE: Off). Values not equal to 0 or 1 are invalid.| Empty| Empty| Empty| Empty| Empty| Empty| */
- MAV_CMD_NAV_DELAY=93, /* Delay the next navigation command a number of seconds or until a specified time |Delay (-1 to enable time-of-day fields)| hour (24h format, UTC, -1 to ignore)| minute (24h format, UTC, -1 to ignore)| second (24h format, UTC, -1 to ignore)| Empty| Empty| Empty| */
- MAV_CMD_NAV_PAYLOAD_PLACE=94, /* Descend and place payload. Vehicle moves to specified location, descends until it detects a hanging payload has reached the ground, and then releases the payload. If ground is not detected before the reaching the maximum descent value (param1), the command will complete without releasing the payload. |Maximum distance to descend.| Empty| Empty| Empty| Latitude| Longitude| Altitude| */
- MAV_CMD_NAV_LAST=95, /* NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */
- MAV_CMD_CONDITION_DELAY=112, /* Delay mission state machine. |Delay| Empty| Empty| Empty| Empty| Empty| Empty| */
- MAV_CMD_CONDITION_CHANGE_ALT=113, /* Ascend/descend to target altitude at specified rate. Delay mission state machine until desired altitude reached. |Descent / Ascend rate.| Empty| Empty| Empty| Empty| Empty| Target Altitude| */
- MAV_CMD_CONDITION_DISTANCE=114, /* Delay mission state machine until within desired distance of next NAV point. |Distance.| Empty| Empty| Empty| Empty| Empty| Empty| */
- MAV_CMD_CONDITION_YAW=115, /* Reach a certain target angle. |target angle [0-360]. Absolute angles: 0 is north. Relative angle: 0 is initial yaw. Direction set by param3.| angular speed| direction: -1: counter clockwise, 0: shortest direction, 1: clockwise| Relative offset (MAV_BOOL_FALSE: absolute angle). Values not equal to 0 or 1 are invalid.| Empty| Empty| Empty| */
- MAV_CMD_CONDITION_LAST=159, /* NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */
- MAV_CMD_DO_SET_MODE=176, /* Set system mode. |Mode flags. MAV_MODE values can be used to set some mode flag combinations.| Custom system-specific mode (see target autopilot specifications for mode information). If MAV_MODE_FLAG_CUSTOM_MODE_ENABLED is set in param1 (mode) this mode is used: otherwise the field is ignored.| Custom sub mode - this is system specific, please refer to the individual autopilot specifications for details.| Empty| Empty| Empty| Empty| */
- MAV_CMD_DO_JUMP=177, /* Jump to the desired command in the mission list. Repeat this action only the specified number of times |Sequence number| Repeat count| Empty| Empty| Empty| Empty| Empty| */
- MAV_CMD_DO_CHANGE_SPEED=178, /* Change speed and/or throttle set points. The value persists until it is overridden or there is a mode change |Speed type of value set in param2 (such as airspeed, ground speed, and so on)| Speed (-1 indicates no change, -2 indicates return to default vehicle speed)| Throttle (-1 indicates no change, -2 indicates return to default vehicle throttle value)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */
- MAV_CMD_DO_SET_HOME=179, /*
- Sets the home position to either to the current position or a specified position.
- The home position is the default position that the system will return to and land on.
- The position is set automatically by the system during the takeoff (and may also be set using this command).
- Note: the current home position may be emitted in a HOME_POSITION message on request (using MAV_CMD_REQUEST_MESSAGE with param1=242).
- |Use current location (MAV_BOOL_FALSE: use specified location). Values not equal to 0 or 1 are invalid.| Roll angle (of surface). Range: -180..180 degrees. NAN or 0 means value not set. 0.01 indicates zero roll.| Pitch angle (of surface). Range: -90..90 degrees. NAN or 0 means value not set. 0.01 means zero pitch.| Yaw angle. NaN to use default heading. Range: -180..180 degrees.| Latitude| Longitude| Altitude| */
- MAV_CMD_DO_SET_PARAMETER=180, /* Set a system parameter. Caution! Use of this command requires knowledge of the numeric enumeration value of the parameter. |Parameter number| Parameter value| Empty| Empty| Empty| Empty| Empty| */
- MAV_CMD_DO_SET_RELAY=181, /* Set a relay to a condition. |Relay instance number.| Setting. (1=on, 0=off, others possible depending on system hardware)| Empty| Empty| Empty| Empty| Empty| */
- MAV_CMD_DO_REPEAT_RELAY=182, /* Cycle a relay on and off for a desired number of cycles with a desired period. |Relay instance number.| Cycle count.| Cycle time.| Empty| Empty| Empty| Empty| */
- MAV_CMD_DO_SET_SERVO=183, /* Set a servo to a desired PWM value. |Servo instance number.| Pulse Width Modulation.| Empty| Empty| Empty| Empty| Empty| */
- MAV_CMD_DO_REPEAT_SERVO=184, /* Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period. |Servo instance number.| Pulse Width Modulation.| Cycle count.| Cycle time.| Empty| Empty| Empty| */
- MAV_CMD_DO_FLIGHTTERMINATION=185, /* Terminate flight immediately.
- Flight termination immediately and irreversibly terminates the current flight, returning the vehicle to ground.
- The vehicle will ignore RC or other input until it has been power-cycled.
- Termination may trigger safety measures, including: disabling motors and deployment of parachute on multicopters, and setting flight surfaces to initiate a landing pattern on fixed-wing).
- On multicopters without a parachute it may trigger a crash landing.
- Support for this command can be tested using the protocol bit: MAV_PROTOCOL_CAPABILITY_FLIGHT_TERMINATION.
- Support for this command can also be tested by sending the command with param1=0 (< 0.5); the ACK should be either MAV_RESULT_FAILED or MAV_RESULT_UNSUPPORTED.
- |Flight termination activated if > 0.5. Otherwise not activated and ACK with MAV_RESULT_FAILED.| Empty| Empty| Empty| Empty| Empty| Empty| */
- MAV_CMD_DO_CHANGE_ALTITUDE=186, /* Change altitude set point. |Altitude.| Frame of new altitude.| Empty| Empty| Empty| Empty| Empty| */
- MAV_CMD_DO_SET_ACTUATOR=187, /* Sets actuators (e.g. servos) to a desired value. The actuator numbers are mapped to specific outputs (e.g. on any MAIN or AUX PWM or UAVCAN) using a flight-stack specific mechanism (i.e. a parameter). |Actuator 1 value, scaled from [-1 to 1]. NaN to ignore.| Actuator 2 value, scaled from [-1 to 1]. NaN to ignore.| Actuator 3 value, scaled from [-1 to 1]. NaN to ignore.| Actuator 4 value, scaled from [-1 to 1]. NaN to ignore.| Actuator 5 value, scaled from [-1 to 1]. NaN to ignore.| Actuator 6 value, scaled from [-1 to 1]. NaN to ignore.| Index of actuator set (i.e if set to 1, Actuator 1 becomes Actuator 7)| */
- MAV_CMD_DO_RETURN_PATH_START=188, /* Mission item to specify the start of a failsafe/landing return-path segment (the end of the segment is the next MAV_CMD_DO_LAND_START item).
- A vehicle that is using missions for landing (e.g. in a return mode) will join the mission on the closest path of the return-path segment (instead of MAV_CMD_DO_LAND_START or the nearest waypoint).
- The main use case is to minimize the failsafe flight path in corridor missions, where the inbound/outbound paths are constrained (by geofences) to the same particular path.
- The MAV_CMD_NAV_RETURN_PATH_START would be placed at the start of the return path.
- If a failsafe occurs on the outbound path the vehicle will move to the nearest point on the return path (which is parallel for this kind of mission), effectively turning round and following the shortest path to landing.
- If a failsafe occurs on the inbound path the vehicle is already on the return segment and will continue to landing.
- The Latitude/Longitude/Altitude are optional, and may be set to 0 if not needed.
- If specified, the item defines the waypoint at which the return segment starts.
- If sent using as a command, the vehicle will perform a mission landing (using the land segment if defined) or reject the command if mission landings are not supported, or no mission landing is defined. When used as a command any position information in the command is ignored.
- |Empty| Empty| Empty| Empty| Latitudee. 0: not used.| Longitudee. 0: not used.| Altitudee. 0: not used.| */
- MAV_CMD_DO_LAND_START=189, /* Mission item to mark the start of a mission landing pattern, or a command to land with a mission landing pattern.
-
- When used in a mission, this is a marker for the start of a sequence of mission items that represent a landing pattern.
- It should be followed by a navigation item that defines the first waypoint of the landing sequence.
- The start marker positional params are used only for selecting what landing pattern to use if several are defined in the mission (the selected pattern will be the one with the marker position that is closest to the vehicle when a landing is commanded).
- If the marker item position has zero-values for latitude, longitude, and altitude, then landing pattern selection is instead based on the position of the first waypoint in the landing sequence.
-
- When sent as a command it triggers a landing using a mission landing pattern.
- The location parameters are not used in this case, and should be set to 0.
- |Empty| Empty| Empty| Empty| Latitude for landing sequence selection, or 0 (see description). Ignored in commands (set 0).| Longitude for landing sequence selection, or 0 (see description). Ignored in commands (set 0).| Altitude for landing sequence selection, or 0 (see description). Ignored in commands (set 0).| */
- MAV_CMD_DO_RALLY_LAND=190, /* Mission command to perform a landing from a rally point. |Break altitude| Landing speed| Empty| Empty| Empty| Empty| Empty| */
- MAV_CMD_DO_GO_AROUND=191, /* Mission command to safely abort an autonomous landing. |Altitude| Empty| Empty| Empty| Empty| Empty| Empty| */
- MAV_CMD_DO_REPOSITION=192, /* Reposition the vehicle to a specific WGS84 global position. This command is intended for guided commands (for missions use MAV_CMD_NAV_WAYPOINT instead). |Ground speed, less than 0 (-1) for default| Bitmask of option flags.| Loiter radius for planes. Positive values only, direction is controlled by Yaw value. A value of zero or NaN is ignored. | Yaw heading (heading reference defined in Bitmask field). NaN to use the current system yaw heading mode (e.g. yaw towards next waypoint, yaw to home, etc.). For planes indicates loiter direction (0: clockwise, 1: counter clockwise)| Latitude| Longitude| Altitude| */
- MAV_CMD_DO_PAUSE_CONTINUE=193, /* If in a GPS controlled position mode, hold the current position or continue. |Continue mission (MAV_BOOL_TRUE), Pause current mission or reposition command, hold current position (MAV_BOOL_FALSE). Values not equal to 0 or 1 are invalid. A VTOL capable vehicle should enter hover mode (multicopter and VTOL planes). A plane should loiter with the default loiter radius.| Reserved| Reserved| Reserved| Reserved| Reserved| Reserved| */
- MAV_CMD_DO_SET_REVERSE=194, /* Set moving direction to forward or reverse. |Reverse direction (MAV_BOOL_FALSE: Forward direction). Values not equal to 0 or 1 are invalid.| Empty| Empty| Empty| Empty| Empty| Empty| */
- MAV_CMD_DO_SET_ROI_LOCATION=195, /* Sets the region of interest (ROI) to a location. This can then be used by the vehicle's control system to control the vehicle attitude and the attitude of various sensors such as cameras. This command can be sent to a gimbal manager but not to a gimbal device. A gimbal is not to react to this message. |Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals).| Empty| Empty| Empty| Latitude of ROI location| Longitude of ROI location| Altitude of ROI location| */
- MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET=196, /* Sets the region of interest (ROI) to be toward next waypoint, with optional pitch/roll/yaw offset. This can then be used by the vehicle's control system to control the vehicle attitude and the attitude of various sensors such as cameras. This command can be sent to a gimbal manager but not to a gimbal device. A gimbal device is not to react to this message. |Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals).| Empty| Empty| Empty| Pitch offset from next waypoint, positive pitching up| Roll offset from next waypoint, positive rolling to the right| Yaw offset from next waypoint, positive yawing to the right| */
- MAV_CMD_DO_SET_ROI_NONE=197, /* Cancels any previous ROI command returning the vehicle/sensors to default flight characteristics. This can then be used by the vehicle's control system to control the vehicle attitude and the attitude of various sensors such as cameras. This command can be sent to a gimbal manager but not to a gimbal device. A gimbal device is not to react to this message. After this command the gimbal manager should go back to manual input if available, and otherwise assume a neutral position. |Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals).| Empty| Empty| Empty| Empty| Empty| Empty| */
- MAV_CMD_DO_SET_ROI_SYSID=198, /* Mount tracks system with specified system ID. Determination of target vehicle position may be done with GLOBAL_POSITION_INT or any other means. This command can be sent to a gimbal manager but not to a gimbal device. A gimbal device is not to react to this message. |System ID| Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals).| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */
- MAV_CMD_DO_CONTROL_VIDEO=200, /* Control onboard camera system. |Camera ID (-1 for all)| Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw| Transmission mode: 0: video stream, >0: single images every n seconds| Recording: 0: disabled, 1: enabled compressed, 2: enabled raw| Empty| Empty| Empty| */
- MAV_CMD_DO_SET_ROI=201, /* Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicle's control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Region of interest mode.| Waypoint index/ target ID (depends on param 1).| Region of interest index. (allows a vehicle to manage multiple ROI's)| Empty| MAV_ROI_WPNEXT: pitch offset from next waypoint, MAV_ROI_LOCATION: latitude| MAV_ROI_WPNEXT: roll offset from next waypoint, MAV_ROI_LOCATION: longitude| MAV_ROI_WPNEXT: yaw offset from next waypoint, MAV_ROI_LOCATION: altitude| */
- MAV_CMD_DO_DIGICAM_CONFIGURE=202, /* Configure digital camera. This is a fallback message for systems that have not yet implemented PARAM_EXT_XXX messages and camera definition files (see https://mavlink.io/en/services/camera_def.html ). |Modes: P, TV, AV, M, Etc.| Shutter speed: Divisor number for one second.| Aperture: F stop number.| ISO number e.g. 80, 100, 200, Etc.| Exposure type enumerator.| Command Identity.| Main engine cut-off time before camera trigger. (0 means no cut-off)| */
- MAV_CMD_DO_DIGICAM_CONTROL=203, /* Control digital camera. This is a fallback message for systems that have not yet implemented PARAM_EXT_XXX messages and camera definition files (see https://mavlink.io/en/services/camera_def.html ). |Session control e.g. show/hide lens| Zoom's absolute position| Zooming step value to offset zoom from the current position| Focus Locking, Unlocking or Re-locking| Shooting Command| Command Identity| Test shot identifier. If set to 1, image will only be captured, but not counted towards internal frame count.| */
- MAV_CMD_DO_MOUNT_CONFIGURE=204, /* Mission command to configure a camera or antenna mount |Mount operation mode| Stabilize roll (MAV_BOOL_TRUE). Values not equal to 0 or 1 are invalid.| Stabilize pitch (MAV_BOOL_TRUE). Values not equal to 0 or 1 are invalid.| Stabilize yaw (MAV_BOOL_TRUE). Values not equal to 0 or 1 are invalid.| Roll input (0 = angle body frame, 1 = angular rate, 2 = angle absolute frame)| Pitch input (0 = angle body frame, 1 = angular rate, 2 = angle absolute frame)| Yaw input (0 = angle body frame, 1 = angular rate, 2 = angle absolute frame)| */
- MAV_CMD_DO_MOUNT_CONTROL=205, /* Mission command to control a camera or antenna mount |pitch depending on mount mode (degrees or degrees/second depending on pitch input).| roll depending on mount mode (degrees or degrees/second depending on roll input).| yaw depending on mount mode (degrees or degrees/second depending on yaw input).| altitude depending on mount mode.| latitude, set if appropriate mount mode.| longitude, set if appropriate mount mode.| Mount mode.| */
- MAV_CMD_DO_SET_CAM_TRIGG_DIST=206, /* Mission command to set camera trigger distance for this flight. The camera is triggered each time this distance is exceeded. This command can also be used to set the shutter integration time for the camera. |Camera trigger distance. 0 to stop triggering.| Camera shutter integration time. -1 or 0 to ignore| Trigger camera once, immediately (MAV_BOOL_TRUE). Values not equal to 0 or 1 are invalid.| Target camera ID. 7 to 255: MAVLink camera component id. 1 to 6 for cameras attached to the autopilot, which don't have a distinct component id. 0: all cameras. This is used to target specific autopilot-connected cameras. It is also used to target specific cameras when the MAV_CMD is used in a mission.| Empty| Empty| Empty| */
- MAV_CMD_DO_FENCE_ENABLE=207, /*
- Enable the geofence.
- This can be used in a mission or via the command protocol.
- The persistence/lifetime of the setting is undefined.
- Depending on flight stack implementation it may persist until superseded, or it may revert to a system default at the end of a mission.
- Flight stacks typically reset the setting to system defaults on reboot.
- |enable? (0=disable, 1=enable, 2=disable_floor_only)| Fence types to enable or disable as a bitmask. 0: field is unused/all fences should be enabled or disabled (for compatibility reasons). Parameter is ignored if param1=2.| Empty| Empty| Empty| Empty| Empty| */
- MAV_CMD_DO_PARACHUTE=208, /* Mission item/command to release a parachute or enable/disable auto release. |Action| Empty| Empty| Empty| Empty| Empty| Empty| */
- MAV_CMD_DO_MOTOR_TEST=209, /* Command to perform motor test. |Motor instance number (from 1 to max number of motors on the vehicle).| Throttle type (whether the Throttle Value in param3 is a percentage, PWM value, etc.)| Throttle value.| Timeout between tests that are run in sequence.| Motor count. Number of motors to test in sequence: 0/1=one motor, 2= two motors, etc. The Timeout (param4) is used between tests.| Motor test order.| Empty| */
- MAV_CMD_DO_INVERTED_FLIGHT=210, /* Change to/from inverted flight. |Inverted flight (MAV_BOOL_False: normal flight). Values not equal to 0 or 1 are invalid.| Empty| Empty| Empty| Empty| Empty| Empty| */
- MAV_CMD_DO_GRIPPER=211, /* Mission command to operate a gripper. |Gripper ID. 1-6 for an autopilot connected gripper. In missions this may be set to 1-6 for an autopilot gripper, or the gripper component id for a MAVLink gripper. 0 targets all grippers.| Gripper action to perform.| Empty| Empty| Empty| Empty| Empty| */
- MAV_CMD_DO_AUTOTUNE_ENABLE=212, /* Enable/disable autotune. |Enable autotune (MAV_BOOL_FALSE: disable autotune). Values not equal to 0 or 1 are invalid.| Specify axes for which autotuning is enabled/disabled. 0 indicates the field is unused (for compatibility reasons). If 0 the autopilot will follow its default behaviour, which is usually to tune all axes.| Empty.| Empty.| Empty.| Empty.| Empty.| */
- MAV_CMD_NAV_SET_YAW_SPEED=213, /* Sets a desired vehicle turn angle and speed change. |Yaw angle to adjust steering by.| Speed.| Relative final angle (MAV_BOOL_FALSE: Absolute angle). Values not equal to 0 or 1 are invalid.| Empty| Empty| Empty| Empty| */
- MAV_CMD_DO_SET_CAM_TRIGG_INTERVAL=214, /* Mission command to set camera trigger interval for this flight. If triggering is enabled, the camera is triggered each time this interval expires. This command can also be used to set the shutter integration time for the camera. |Camera trigger cycle time. -1 or 0 to ignore.| Camera shutter integration time. Should be less than trigger cycle time. -1 or 0 to ignore.| Target camera ID. 7 to 255: MAVLink camera component id. 1 to 6 for cameras attached to the autopilot, which don't have a distinct component id. 0: all cameras. This is used to target specific autopilot-connected cameras. It is also used to target specific cameras when the MAV_CMD is used in a mission.| Empty| Empty| Empty| Empty| */
- MAV_CMD_DO_MOUNT_CONTROL_QUAT=220, /* Mission command to control a camera or antenna mount, using a quaternion as reference. |quaternion param q1, w (1 in null-rotation)| quaternion param q2, x (0 in null-rotation)| quaternion param q3, y (0 in null-rotation)| quaternion param q4, z (0 in null-rotation)| Empty| Empty| Empty| */
- MAV_CMD_DO_GUIDED_MASTER=221, /* set id of master controller |System ID| Component ID| Empty| Empty| Empty| Empty| Empty| */
- MAV_CMD_DO_GUIDED_LIMITS=222, /* Set limits for external control |Timeout - maximum time that external controller will be allowed to control vehicle. 0 means no timeout.| Altitude (MSL) min - if vehicle moves below this alt, the command will be aborted and the mission will continue. 0 means no lower altitude limit.| Altitude (MSL) max - if vehicle moves above this alt, the command will be aborted and the mission will continue. 0 means no upper altitude limit.| Horizontal move limit - if vehicle moves more than this distance from its location at the moment the command was executed, the command will be aborted and the mission will continue. 0 means no horizontal move limit.| Empty| Empty| Empty| */
- MAV_CMD_DO_ENGINE_CONTROL=223, /* Control vehicle engine. This is interpreted by the vehicles engine controller to change the target engine state. It is intended for vehicles with internal combustion engines |Start engine (MAV_BOOL_False: Stop engine). Values not equal to 0 or 1 are invalid.| Cold start engine (MAV_BOOL_FALSE: Warm start). Values not equal to 0 or 1 are invalid. Controls use of choke where applicable| Height delay. This is for commanding engine start only after the vehicle has gained the specified height. Used in VTOL vehicles during takeoff to start engine after the aircraft is off the ground. Zero for no delay.| Empty| Empty| Empty| Empty| */
- MAV_CMD_DO_SET_MISSION_CURRENT=224, /*
- Set the mission item with sequence number seq as the current item and emit MISSION_CURRENT (whether or not the mission number changed).
- If a mission is currently being executed, the system will continue to this new mission item on the shortest path, skipping any intermediate mission items.
- Note that mission jump repeat counters are not reset unless param2 is set (see MAV_CMD_DO_JUMP param2).
-
- This command may trigger a mission state-machine change on some systems: for example from MISSION_STATE_NOT_STARTED or MISSION_STATE_PAUSED to MISSION_STATE_ACTIVE.
- If the system is in mission mode, on those systems this command might therefore start, restart or resume the mission.
- If the system is not in mission mode this command must not trigger a switch to mission mode.
-
- The mission may be "reset" using param2.
- Resetting sets jump counters to initial values (to reset counters without changing the current mission item set the param1 to `-1`).
- Resetting also explicitly changes a mission state of MISSION_STATE_COMPLETE to MISSION_STATE_PAUSED or MISSION_STATE_ACTIVE, potentially allowing it to resume when it is (next) in a mission mode.
-
- The command will ACK with MAV_RESULT_FAILED if the sequence number is out of range (including if there is no mission item).
- |Mission sequence value to set. -1 for the current mission item (use to reset mission without changing current mission item).| Reset mission (MAV_BOOL_TRUE). Values not equal to 0 or 1 are invalid. Resets jump counters to initial values and changes mission state "completed" to be "active" or "paused".| Empty| Empty| Empty| Empty| Empty| */
- MAV_CMD_DO_LAST=240, /* NOP - This command is only used to mark the upper limit of the DO commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */
- MAV_CMD_PREFLIGHT_CALIBRATION=241, /* Trigger calibration. This command will be only accepted if in pre-flight mode. Except for Temperature Calibration, only one sensor should be set in a single message and all others should be zero. |1: gyro calibration, 3: gyro temperature calibration| Magnetometer calibration. Values not equal to 0 or 1 are invalid.| Ground pressure calibration. Values not equal to 0 or 1 are invalid.| 1: radio RC calibration, 2: RC trim calibration| 1: accelerometer calibration, 2: board level calibration, 3: accelerometer temperature calibration, 4: simple accelerometer calibration| 1: APM: compass/motor interference calibration (PX4: airspeed calibration, deprecated), 2: airspeed calibration| 1: ESC calibration, 3: barometer temperature calibration| */
- MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS=242, /* Set sensor offsets. This command will be only accepted if in pre-flight mode. |Sensor to adjust the offsets for: 0: gyros, 1: accelerometer, 2: magnetometer, 3: barometer, 4: optical flow, 5: second magnetometer, 6: third magnetometer| X axis offset (or generic dimension 1), in the sensor's raw units| Y axis offset (or generic dimension 2), in the sensor's raw units| Z axis offset (or generic dimension 3), in the sensor's raw units| Generic dimension 4, in the sensor's raw units| Generic dimension 5, in the sensor's raw units| Generic dimension 6, in the sensor's raw units| */
- MAV_CMD_PREFLIGHT_UAVCAN=243, /* Trigger UAVCAN configuration (actuator ID assignment and direction mapping). Note that this maps to the legacy UAVCAN v0 function UAVCAN_ENUMERATE, which is intended to be executed just once during initial vehicle configuration (it is not a normal pre-flight command and has been poorly named). |1: Trigger actuator ID assignment and direction mapping. 0: Cancel command.| Reserved| Reserved| Reserved| Reserved| Reserved| Reserved| */
- MAV_CMD_PREFLIGHT_STORAGE=245, /* Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode. |Action to perform on the persistent parameter storage| Action to perform on the persistent mission storage| Onboard logging: 0: Ignore, 1: Start default rate logging, -1: Stop logging, > 1: logging rate (e.g. set to 1000 for 1000 Hz logging)| Reserved| Empty| Empty| Empty| */
- MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN=246, /* Request the reboot or shutdown of system components. |Action to take for autopilot.| Action to take for onboard computer.| Action to take for component specified in param4.| MAVLink Component ID targeted in param3 (0 for all components).| Reserved (set to 0)| Conditions under which reboot/shutdown is allowed.| WIP: ID (e.g. camera ID -1 for all IDs)| */
- MAV_CMD_OVERRIDE_GOTO=252, /* Override current mission with command to pause mission, pause mission and move to position, continue/resume mission. When param 1 indicates that the mission is paused (MAV_GOTO_DO_HOLD), param 2 defines whether it holds in place or moves to another position. |MAV_GOTO_DO_HOLD: pause mission and either hold or move to specified position (depending on param2), MAV_GOTO_DO_CONTINUE: resume mission.| MAV_GOTO_HOLD_AT_CURRENT_POSITION: hold at current position, MAV_GOTO_HOLD_AT_SPECIFIED_POSITION: hold at specified position.| Coordinate frame of hold point.| Desired yaw angle.| Latitude/X position.| Longitude/Y position.| Altitude/Z position.| */
- MAV_CMD_OBLIQUE_SURVEY=260, /* Mission command to set a Camera Auto Mount Pivoting Oblique Survey (Replaces CAM_TRIGG_DIST for this purpose). The camera is triggered each time this distance is exceeded, then the mount moves to the next position. Params 4~6 set-up the angle limits and number of positions for oblique survey, where mount-enabled vehicles automatically roll the camera between shots to emulate an oblique camera setup (providing an increased HFOV). This command can also be used to set the shutter integration time for the camera. |Camera trigger distance. 0 to stop triggering.| Camera shutter integration time. 0 to ignore| The minimum interval in which the camera is capable of taking subsequent pictures repeatedly. 0 to ignore.| Total number of roll positions at which the camera will capture photos (images captures spread evenly across the limits defined by param5).| Angle limits that the camera can be rolled to left and right of center.| Fixed pitch angle that the camera will hold in oblique mode if the mount is actuated in the pitch axis.| Empty| */
- MAV_CMD_DO_SET_STANDARD_MODE=262, /* Enable the specified standard MAVLink mode.
- If the specified mode is not supported, the vehicle should ACK with MAV_RESULT_FAILED.
- See https://mavlink.io/en/services/standard_modes.html
- |The mode to set.| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:NaN)| */
- MAV_CMD_MISSION_START=300, /* start running a mission |first_item: the first mission item to run| last_item: the last mission item to run (after this item is run, the mission ends)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */
- MAV_CMD_ACTUATOR_TEST=310, /* Actuator testing command. This is similar to MAV_CMD_DO_MOTOR_TEST but operates on the level of output functions, i.e. it is possible to test Motor1 independent from which output it is configured on. Autopilots must NACK this command with MAV_RESULT_TEMPORARILY_REJECTED while armed. |Output value: 1 means maximum positive output, 0 to center servos or minimum motor thrust (expected to spin), -1 for maximum negative (if not supported by the motors, i.e. motor is not reversible, smaller than 0 maps to NaN). And NaN maps to disarmed (stop the motors).| Timeout after which the test command expires and the output is restored to the previous value. A timeout has to be set for safety reasons. A timeout of 0 means to restore the previous value immediately.| Reserved (default:0)| Reserved (default:0)| Actuator Output function| Reserved (default:0)| Reserved (default:0)| */
- MAV_CMD_CONFIGURE_ACTUATOR=311, /* Actuator configuration command. |Actuator configuration action| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Actuator Output function| Reserved (default:0)| Reserved (default:0)| */
- MAV_CMD_COMPONENT_ARM_DISARM=400, /* Arms / Disarms a component |Arm (MAV_BOOL_FALSE: disarm). Values not equal to 0 or 1 are invalid.| 0: arm-disarm unless prevented by safety checks (i.e. when landed), 21196: force arming/disarming (e.g. allow arming to override preflight checks and disarming in flight)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */
- MAV_CMD_RUN_PREARM_CHECKS=401, /* Instructs a target system to run pre-arm checks.
- This allows preflight checks to be run on demand, which may be useful on systems that normally run them at low rate, or which do not trigger checks when the armable state might have changed.
- This command should return MAV_RESULT_ACCEPTED if it will run the checks.
- The results of the checks are usually then reported in SYS_STATUS messages (this is system-specific).
- The command should return MAV_RESULT_TEMPORARILY_REJECTED if the system is already armed.
- |Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */
- MAV_CMD_ILLUMINATOR_ON_OFF=405, /* Turns illuminators ON/OFF. An illuminator is a light source that is used for lighting up dark areas external to the system: e.g. a torch or searchlight (as opposed to a light source for illuminating the system itself, e.g. an indicator light). |Illuminators on/off (MAV_BOOL_TRUE: illuminators on). Values not equal to 0 or 1 are invalid.| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */
- MAV_CMD_DO_ILLUMINATOR_CONFIGURE=406, /* Configures illuminator settings. An illuminator is a light source that is used for lighting up dark areas external to the system: e.g. a torch or searchlight (as opposed to a light source for illuminating the system itself, e.g. an indicator light). |Mode| 0%: Off, 100%: Max Brightness| Strobe period in seconds where 0 means strobing is not used| Strobe duty cycle where 100% means it is on constantly and 0 means strobing is not used| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */
- MAV_CMD_GET_HOME_POSITION=410, /* Request the home position from the vehicle.
- The vehicle will ACK the command and then emit the HOME_POSITION message. |Reserved| Reserved| Reserved| Reserved| Reserved| Reserved| Reserved| */
- MAV_CMD_INJECT_FAILURE=420, /* Inject artificial failure for testing purposes. Note that autopilots should implement an additional protection before accepting this command such as a specific param setting. |The unit which is affected by the failure.| The type how the failure manifests itself.| Instance affected by failure (0 to signal all).| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */
- MAV_CMD_START_RX_PAIR=500, /* Starts receiver pairing. |RC type.| RC sub type.| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */
- MAV_CMD_GET_MESSAGE_INTERVAL=510, /*
- Request the interval between messages for a particular MAVLink message ID.
- The receiver should ACK the command and then emit its response in a MESSAGE_INTERVAL message.
- |The MAVLink message ID| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */
- MAV_CMD_SET_MESSAGE_INTERVAL=511, /* Set the interval between messages for a particular MAVLink message ID. This interface replaces REQUEST_DATA_STREAM. |The MAVLink message ID| The interval between two messages. -1: disable. 0: request default rate (which may be zero).| Use for index ID, if required. Otherwise, the use of this parameter (if any) must be defined in the requested message. By default assumed not used (0). When used as an index ID, 0 means "all instances", "1" means the first instance in the sequence (the emitted message will have an id of 0 if message ids are 0-indexed, or 1 if index numbers start from one).| The use of this parameter (if any), must be defined in the requested message. By default assumed not used (0).| The use of this parameter (if any), must be defined in the requested message. By default assumed not used (0/NaN).| The use of this parameter (if any), must be defined in the requested message. By default assumed not used (0/NaN).| Target address of message stream (if message has target address fields). 0: Flight-stack default (recommended), 1: address of requester, 2: broadcast.| */
- MAV_CMD_REQUEST_MESSAGE=512, /* Request the target system(s) emit a single instance of a specified message (i.e. a "one-shot" version of MAV_CMD_SET_MESSAGE_INTERVAL). |The MAVLink message ID of the requested message.| Use for index ID, if required. Otherwise, the use of this parameter (if any) must be defined in the requested message. By default assumed not used (0).| The use of this parameter (if any), must be defined in the requested message. By default assumed not used (0).| The use of this parameter (if any), must be defined in the requested message. By default assumed not used (0).| The use of this parameter (if any), must be defined in the requested message. By default assumed not used (0).| The use of this parameter (if any), must be defined in the requested message. By default assumed not used (0).| Target address for requested message (if message has target address fields). 0: Flight-stack default, 1: address of requester, 2: broadcast.| */
- MAV_CMD_REQUEST_PROTOCOL_VERSION=519, /* Request MAVLink protocol version compatibility. All receivers should ACK the command and then emit their capabilities in an PROTOCOL_VERSION message |Request supported protocol versions by all nodes on the network (MAV_BOOL_TRUE). Values not equal to 0 or 1 are invalid.| Reserved (all remaining params)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */
- MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES=520, /* Request autopilot capabilities. The receiver should ACK the command and then emit its capabilities in an AUTOPILOT_VERSION message |Request autopilot version (MAV_BOOL_TRUE). Values not equal to 0 or 1 are invalid.| Reserved (all remaining params)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */
- MAV_CMD_REQUEST_CAMERA_INFORMATION=521, /* Request camera information (CAMERA_INFORMATION). |Request camera capabilities (MAV_BOOL_TRUE). Values not equal to 0 or 1 are invalid.| Reserved (all remaining params)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */
- MAV_CMD_REQUEST_CAMERA_SETTINGS=522, /* Request camera settings (CAMERA_SETTINGS). |Request camera settings (MAV_BOOL_TRUE). Values not equal to 0 or 1 are invalid.| Reserved (all remaining params)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */
- MAV_CMD_REQUEST_STORAGE_INFORMATION=525, /* Request storage information (STORAGE_INFORMATION). Use the command's target_component to target a specific component's storage. |Storage ID (0 for all, 1 for first, 2 for second, etc.)| Request storage information (MAV_BOOL_TRUE). Values not equal to 0 or 1 are invalid.| Reserved (all remaining params)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */
- MAV_CMD_STORAGE_FORMAT=526, /* Format a storage medium. Once format is complete, a STORAGE_INFORMATION message is sent. Use the command's target_component to target a specific component's storage. |Storage ID (1 for first, 2 for second, etc.)| Format storage (and reset image log). Values not equal to 0 or 1 are invalid.| Reset Image Log (without formatting storage medium). This will reset CAMERA_CAPTURE_STATUS.image_count and CAMERA_IMAGE_CAPTURED.image_index. Values not equal to 0 or 1 are invalid.| Reserved (all remaining params)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */
- MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS=527, /* Request camera capture status (CAMERA_CAPTURE_STATUS) |Request camera capture status (MAV_BOOL_TRUE). Values not equal to 0 or 1 are invalid.| Reserved (all remaining params)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */
- MAV_CMD_REQUEST_FLIGHT_INFORMATION=528, /* Request flight information (FLIGHT_INFORMATION) |Request flight information (MAV_BOOL_TRUE). Values not equal to 0 or 1 are invalid.| Reserved (all remaining params)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */
- MAV_CMD_RESET_CAMERA_SETTINGS=529, /* Reset all camera settings to Factory Default |Reset all settings (MAV_BOOL_TRUE). Values not equal to 0 or 1 are invalid.| Target camera ID. 7 to 255: MAVLink camera component id. 1 to 6 for cameras attached to the autopilot, which don't have a distinct component id. 0: all cameras. This is used to target specific autopilot-connected cameras. It is also used to target specific cameras when the MAV_CMD is used in a mission.| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */
- MAV_CMD_SET_CAMERA_MODE=530, /* Set camera running mode. Use NaN for reserved values. GCS will send a MAV_CMD_REQUEST_VIDEO_STREAM_STATUS command after a mode change if the camera supports video streaming. |Target camera ID. 7 to 255: MAVLink camera component id. 1 to 6 for cameras attached to the autopilot, which don't have a distinct component id. 0: all cameras. This is used to target specific autopilot-connected cameras. It is also used to target specific cameras when the MAV_CMD is used in a mission.| Camera mode| Reserved (default:NaN)| Reserved (default:NaN)| Reserved (default:0)| Reserved (default:0)| Reserved (default:NaN)| */
- MAV_CMD_SET_CAMERA_ZOOM=531, /* Set camera zoom. Camera must respond with a CAMERA_SETTINGS message (on success). |Zoom type| Zoom value. The range of valid values depend on the zoom type.| Target camera ID. 7 to 255: MAVLink camera component id. 1 to 6 for cameras attached to the autopilot, which don't have a distinct component id. 0: all cameras. This is used to target specific autopilot-connected cameras. It is also used to target specific cameras when the MAV_CMD is used in a mission.| Reserved (default:NaN)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */
- MAV_CMD_SET_CAMERA_FOCUS=532, /* Set camera focus. Camera must respond with a CAMERA_SETTINGS message (on success). |Focus type| Focus value| Target camera ID. 7 to 255: MAVLink camera component id. 1 to 6 for cameras attached to the autopilot, which don't have a distinct component id. 0: all cameras. This is used to target specific autopilot-connected cameras. It is also used to target specific cameras when the MAV_CMD is used in a mission.| Reserved (default:NaN)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */
- MAV_CMD_SET_STORAGE_USAGE=533, /* Set that a particular storage is the preferred location for saving photos, videos, and/or other media (e.g. to set that an SD card is used for storing videos).
- There can only be one preferred save location for each particular media type: setting a media usage flag will clear/reset that same flag if set on any other storage.
- If no flag is set the system should use its default storage.
- A target system can choose to always use default storage, in which case it should ACK the command with MAV_RESULT_UNSUPPORTED.
- A target system can choose to not allow a particular storage to be set as preferred storage, in which case it should ACK the command with MAV_RESULT_DENIED. |Storage ID (1 for first, 2 for second, etc.)| Usage flags| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */
- MAV_CMD_SET_CAMERA_SOURCE=534, /* Set camera source. Changes the camera's active sources on cameras with multiple image sensors. |Component Id of camera to address or 1-6 for non-MAVLink cameras, 0 for all cameras.| Primary Source| Secondary Source. If non-zero the second source will be displayed as picture-in-picture.| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */
- MAV_CMD_JUMP_TAG=600, /* Tagged jump target. Can be jumped to with MAV_CMD_DO_JUMP_TAG. |Tag.| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */
- MAV_CMD_DO_JUMP_TAG=601, /* Jump to the matching tag in the mission list. Repeat this action for the specified number of times. A mission should contain a single matching tag for each jump. If this is not the case then a jump to a missing tag should complete the mission, and a jump where there are multiple matching tags should always select the one with the lowest mission sequence number. |Target tag to jump to.| Repeat count.| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */
- MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW=1000, /* Set gimbal manager pitch/yaw setpoints (low rate command). It is possible to set combinations of the values below. E.g. an angle as well as a desired angular rate can be used to get to this angle at a certain angular rate, or an angular rate only will result in continuous turning. NaN is to be used to signal unset. Note: only the gimbal manager will react to this command - it will be ignored by a gimbal device. Use GIMBAL_MANAGER_SET_PITCHYAW if you need to stream pitch/yaw setpoints at higher rate. |Pitch angle (positive to pitch up, relative to vehicle for FOLLOW mode, relative to world horizon for LOCK mode).| Yaw angle (positive to yaw to the right, relative to vehicle for FOLLOW mode, absolute to North for LOCK mode).| Pitch rate (positive to pitch up).| Yaw rate (positive to yaw to the right).| Gimbal manager flags to use.| Reserved (default:0)| Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals).| */
- MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE=1001, /* Gimbal configuration to set which sysid/compid is in primary and secondary control. |Sysid for primary control (0: no one in control, -1: leave unchanged, -2: set itself in control (for missions where the own sysid is still unknown), -3: remove control if currently in control).| Compid for primary control (0: no one in control, -1: leave unchanged, -2: set itself in control (for missions where the own sysid is still unknown), -3: remove control if currently in control).| Sysid for secondary control (0: no one in control, -1: leave unchanged, -2: set itself in control (for missions where the own sysid is still unknown), -3: remove control if currently in control).| Compid for secondary control (0: no one in control, -1: leave unchanged, -2: set itself in control (for missions where the own sysid is still unknown), -3: remove control if currently in control).| Reserved (default:0)| Reserved (default:0)| Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals).| */
- MAV_CMD_IMAGE_START_CAPTURE=2000, /* Start image capture sequence. CAMERA_IMAGE_CAPTURED must be emitted after each capture.
-
- Param1 (id) may be used to specify the target camera: 0: all cameras, 1 to 6: autopilot-connected cameras, 7-255: MAVLink camera component ID.
- It is needed in order to target specific cameras connected to the autopilot, or specific sensors in a multi-sensor camera (neither of which have a distinct MAVLink component ID).
- It is also needed to specify the target camera in missions.
-
- When used in a mission, an autopilot should execute the MAV_CMD for a specified local camera (param1 = 1-6), or resend it as a command if it is intended for a MAVLink camera (param1 = 7 - 255), setting the command's target_component as the param1 value (and setting param1 in the command to zero).
- If the param1 is 0 the autopilot should do both.
-
- When sent in a command the target MAVLink address is set using target_component.
- If addressed specifically to an autopilot: param1 should be used in the same way as it is for missions (though command should NACK with MAV_RESULT_DENIED if a specified local camera does not exist).
- If addressed to a MAVLink camera, param 1 can be used to address all cameras (0), or to separately address 1 to 7 individual sensors. Other values should be NACKed with MAV_RESULT_DENIED.
- If the command is broadcast (target_component is 0) then param 1 should be set to 0 (any other value should be NACKED with MAV_RESULT_DENIED). An autopilot would trigger any local cameras and forward the command to all channels.
- |Target camera ID. 7 to 255: MAVLink camera component id. 1 to 6 for cameras attached to the autopilot, which don't have a distinct component id. 0: all cameras. This is used to target specific autopilot-connected cameras. It is also used to target specific cameras when the MAV_CMD is used in a mission.| Desired elapsed time between two consecutive pictures (in seconds). Minimum values depend on hardware (typically greater than 2 seconds).| Total number of images to capture. 0 to capture forever/until MAV_CMD_IMAGE_STOP_CAPTURE.| Capture sequence number starting from 1. This is only valid for single-capture (param3 == 1), otherwise set to 0. Increment the capture ID for each capture command to prevent double captures when a command is re-transmitted.| Reserved (default:0)| Reserved (default:0)| Reserved (default:NaN)| */
- MAV_CMD_IMAGE_STOP_CAPTURE=2001, /* Stop image capture sequence.
-
- Param1 (id) may be used to specify the target camera: 0: all cameras, 1 to 6: autopilot-connected cameras, 7-255: MAVLink camera component ID.
- It is needed in order to target specific cameras connected to the autopilot, or specific sensors in a multi-sensor camera (neither of which have a distinct MAVLink component ID).
- It is also needed to specify the target camera in missions.
-
- When used in a mission, an autopilot should execute the MAV_CMD for a specified local camera (param1 = 1-6), or resend it as a command if it is intended for a MAVLink camera (param1 = 7 - 255), setting the command's target_component as the param1 value (and setting param1 in the command to zero).
- If the param1 is 0 the autopilot should do both.
-
- When sent in a command the target MAVLink address is set using target_component.
- If addressed specifically to an autopilot: param1 should be used in the same way as it is for missions (though command should NACK with MAV_RESULT_DENIED if a specified local camera does not exist).
- If addressed to a MAVLink camera, param1 can be used to address all cameras (0), or to separately address 1 to 7 individual sensors. Other values should be NACKed with MAV_RESULT_DENIED.
- If the command is broadcast (target_component is 0) then param 1 should be set to 0 (any other value should be NACKED with MAV_RESULT_DENIED). An autopilot would trigger any local cameras and forward the command to all channels.
- |Target camera ID. 7 to 255: MAVLink camera component id. 1 to 6 for cameras attached to the autopilot, which don't have a distinct component id. 0: all cameras. This is used to target specific autopilot-connected cameras. It is also used to target specific cameras when the MAV_CMD is used in a mission.| Reserved (default:NaN)| Reserved (default:NaN)| Reserved (default:NaN)| Reserved (default:0)| Reserved (default:0)| Reserved (default:NaN)| */
- MAV_CMD_REQUEST_CAMERA_IMAGE_CAPTURE=2002, /* Re-request a CAMERA_IMAGE_CAPTURED message. |Sequence number for missing CAMERA_IMAGE_CAPTURED message| Reserved (default:NaN)| Reserved (default:NaN)| Reserved (default:NaN)| Reserved (default:0)| Reserved (default:0)| Reserved (default:NaN)| */
- MAV_CMD_DO_TRIGGER_CONTROL=2003, /* Enable or disable on-board camera triggering system. |Trigger enable/disable (0 for disable, 1 for start), -1 to ignore| 1 to reset the trigger sequence, -1 or 0 to ignore| 1 to pause triggering, but without switching the camera off or retracting it. -1 to ignore| Target camera ID. 7 to 255: MAVLink camera component id. 1 to 6 for cameras attached to the autopilot, which don't have a distinct component id. 0: all cameras. This is used to target specific autopilot-connected cameras. It is also used to target specific cameras when the MAV_CMD is used in a mission.| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */
- MAV_CMD_CAMERA_TRACK_POINT=2004, /* If the camera supports point visual tracking (CAMERA_CAP_FLAGS_HAS_TRACKING_POINT is set), this command allows to initiate the tracking. |Point to track x value (normalized 0..1, 0 is left, 1 is right).| Point to track y value (normalized 0..1, 0 is top, 1 is bottom).| Point radius (normalized 0..1, 0 is one pixel, 1 is full image width).| Target camera ID. 7 to 255: MAVLink camera component id. 1 to 6 for cameras attached to the autopilot, which don't have a distinct component id. 0: all cameras. This is used to target specific autopilot-connected cameras. It is also used to target specific cameras when the MAV_CMD is used in a mission.| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */
- MAV_CMD_CAMERA_TRACK_RECTANGLE=2005, /* If the camera supports rectangle visual tracking (CAMERA_CAP_FLAGS_HAS_TRACKING_RECTANGLE is set), this command allows to initiate the tracking. |Top left corner of rectangle x value (normalized 0..1, 0 is left, 1 is right).| Top left corner of rectangle y value (normalized 0..1, 0 is top, 1 is bottom).| Bottom right corner of rectangle x value (normalized 0..1, 0 is left, 1 is right).| Bottom right corner of rectangle y value (normalized 0..1, 0 is top, 1 is bottom).| Target camera ID. 7 to 255: MAVLink camera component id. 1 to 6 for cameras attached to the autopilot, which don't have a distinct component id. 0: all cameras. This is used to target specific autopilot-connected cameras. It is also used to target specific cameras when the MAV_CMD is used in a mission.| Reserved (default:0)| Reserved (default:0)| */
- MAV_CMD_CAMERA_STOP_TRACKING=2010, /* Stops ongoing tracking. |Target camera ID. 7 to 255: MAVLink camera component id. 1 to 6 for cameras attached to the autopilot, which don't have a distinct component id. 0: all cameras. This is used to target specific autopilot-connected cameras. It is also used to target specific cameras when the MAV_CMD is used in a mission.| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */
- MAV_CMD_VIDEO_START_CAPTURE=2500, /* Starts video capture (recording). |Video Stream ID (0 for all streams)| Frequency CAMERA_CAPTURE_STATUS messages should be sent while recording (0 for no messages, otherwise frequency)| Target camera ID. 7 to 255: MAVLink camera component id. 1 to 6 for cameras attached to the autopilot, which don't have a distinct component id. 0: all cameras. This is used to target specific autopilot-connected cameras. It is also used to target specific cameras when the MAV_CMD is used in a mission.| Reserved (default:NaN)| Reserved (default:0)| Reserved (default:0)| Reserved (default:NaN)| */
- MAV_CMD_VIDEO_STOP_CAPTURE=2501, /* Stop the current video capture (recording). |Video Stream ID (0 for all streams)| Target camera ID. 7 to 255: MAVLink camera component id. 1 to 6 for cameras attached to the autopilot, which don't have a distinct component id. 0: all cameras. This is used to target specific autopilot-connected cameras. It is also used to target specific cameras when the MAV_CMD is used in a mission.| Reserved (default:NaN)| Reserved (default:NaN)| Reserved (default:0)| Reserved (default:0)| Reserved (default:NaN)| */
- MAV_CMD_VIDEO_START_STREAMING=2502, /* Start video streaming |Video Stream ID (0 for all streams, 1 for first, 2 for second, etc.)| Target camera ID. 7 to 255: MAVLink camera component id. 1 to 6 for cameras attached to the autopilot, which don't have a distinct component id. 0: all cameras. This is used to target specific autopilot-connected cameras. It is also used to target specific cameras when the MAV_CMD is used in a mission.| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */
- MAV_CMD_VIDEO_STOP_STREAMING=2503, /* Stop the given video stream |Video Stream ID (0 for all streams, 1 for first, 2 for second, etc.)| Target camera ID. 7 to 255: MAVLink camera component id. 1 to 6 for cameras attached to the autopilot, which don't have a distinct component id. 0: all cameras. This is used to target specific autopilot-connected cameras. It is also used to target specific cameras when the MAV_CMD is used in a mission.| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */
- MAV_CMD_REQUEST_VIDEO_STREAM_INFORMATION=2504, /* Request video stream information (VIDEO_STREAM_INFORMATION) |Video Stream ID (0 for all streams, 1 for first, 2 for second, etc.)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */
- MAV_CMD_REQUEST_VIDEO_STREAM_STATUS=2505, /* Request video stream status (VIDEO_STREAM_STATUS) |Video Stream ID (0 for all streams, 1 for first, 2 for second, etc.)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */
- MAV_CMD_LOGGING_START=2510, /* Request to start streaming logging data over MAVLink (see also LOGGING_DATA message) |Format: 0: ULog| Reserved (set to 0)| Reserved (set to 0)| Reserved (set to 0)| Reserved (set to 0)| Reserved (set to 0)| Reserved (set to 0)| */
- MAV_CMD_LOGGING_STOP=2511, /* Request to stop streaming log data over MAVLink |Reserved (set to 0)| Reserved (set to 0)| Reserved (set to 0)| Reserved (set to 0)| Reserved (set to 0)| Reserved (set to 0)| Reserved (set to 0)| */
- MAV_CMD_AIRFRAME_CONFIGURATION=2520, /* |Landing gear ID (default: 0, -1 for all)| Landing gear position (Down: 0, Up: 1, NaN for no change)| Reserved (default:NaN)| Reserved (default:NaN)| Reserved (default:0)| Reserved (default:0)| Reserved (default:NaN)| */
- MAV_CMD_CONTROL_HIGH_LATENCY=2600, /* Request to start/stop transmitting over the high latency telemetry |Start transmission over high latency telemetry (MAV_BOOL_FALSE: stop transmission). Values not equal to 0 or 1 are invalid.| Empty| Empty| Empty| Empty| Empty| Empty| */
- MAV_CMD_PANORAMA_CREATE=2800, /* Create a panorama at the current position |Viewing angle horizontal of the panorama (+- 0.5 the total angle)| Viewing angle vertical of panorama.| Speed of the horizontal rotation.| Speed of the vertical rotation.| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */
- MAV_CMD_DO_VTOL_TRANSITION=3000, /* Request VTOL transition |The target VTOL state. For normal transitions, only MAV_VTOL_STATE_MC and MAV_VTOL_STATE_FW can be used.| Force immediate transition to the specified MAV_VTOL_STATE. 1: Force immediate, 0: normal transition. Can be used, for example, to trigger an emergency "Quadchute". Caution: Can be dangerous/damage vehicle, depending on autopilot implementation of this command.| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */
- MAV_CMD_ARM_AUTHORIZATION_REQUEST=3001, /* Request authorization to arm the vehicle to a external entity, the arm authorizer is responsible to request all data that is needs from the vehicle before authorize or deny the request.
- If approved the COMMAND_ACK message progress field should be set with period of time that this authorization is valid in seconds.
- If the authorization is denied COMMAND_ACK.result_param2 should be set with one of the reasons in ARM_AUTH_DENIED_REASON.
- |Vehicle system id, this way ground station can request arm authorization on behalf of any vehicle| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */
- MAV_CMD_SET_GUIDED_SUBMODE_STANDARD=4000, /* This command sets the submode to standard guided when vehicle is in guided mode. The vehicle holds position and altitude and the user can input the desired velocities along all three axes.
- |Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */
- MAV_CMD_SET_GUIDED_SUBMODE_CIRCLE=4001, /* This command sets submode circle when vehicle is in guided mode. Vehicle flies along a circle facing the center of the circle. The user can input the velocity along the circle and change the radius. If no input is given the vehicle will hold position.
- |Radius of desired circle in CIRCLE_MODE| User defined| User defined| User defined| Target latitude of center of circle in CIRCLE_MODE| Target longitude of center of circle in CIRCLE_MODE| Reserved (default:0)| */
- MAV_CMD_CONDITION_GATE=4501, /* Delay mission state machine until gate has been reached. |Geometry: 0: orthogonal to path between previous and next waypoint.| Use altitude (MAV_BOOL_FALSE: ignore altitude). Values not equal to 0 or 1 are invalid.| Empty| Empty| Latitude| Longitude| Altitude| */
- MAV_CMD_NAV_FENCE_RETURN_POINT=5000, /* Fence return point (there can only be one such point in a geofence definition). If rally points are supported they should be used instead. |Reserved| Reserved| Reserved| Reserved| Latitude| Longitude| Altitude| */
- MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION=5001, /* Fence vertex for an inclusion polygon (the polygon must not be self-intersecting). The vehicle must stay within this area. Minimum of 3 vertices required.
- The vertices for a polygon must be sent sequentially, each with param1 set to the total number of vertices in the polygon.
- |Polygon vertex count. This is the number of vertices in the current polygon (all vertices will have the same number).| Vehicle must be inside ALL inclusion zones in a single group, vehicle must be inside at least one group, must be the same for all points in each polygon| Reserved| Reserved| Latitude| Longitude| Reserved| */
- MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION=5002, /* Fence vertex for an exclusion polygon (the polygon must not be self-intersecting). The vehicle must stay outside this area. Minimum of 3 vertices required.
- The vertices for a polygon must be sent sequentially, each with param1 set to the total number of vertices in the polygon.
- |Polygon vertex count. This is the number of vertices in the current polygon (all vertices will have the same number).| Reserved| Reserved| Reserved| Latitude| Longitude| Reserved| */
- MAV_CMD_NAV_FENCE_CIRCLE_INCLUSION=5003, /* Circular fence area. The vehicle must stay inside this area.
- |Radius.| Vehicle must be inside ALL inclusion zones in a single group, vehicle must be inside at least one group| Reserved| Reserved| Latitude| Longitude| Reserved| */
- MAV_CMD_NAV_FENCE_CIRCLE_EXCLUSION=5004, /* Circular fence area. The vehicle must stay outside this area.
- |Radius.| Reserved| Reserved| Reserved| Latitude| Longitude| Reserved| */
- MAV_CMD_NAV_RALLY_POINT=5100, /* Rally point. You can have multiple rally points defined.
- |Reserved| Reserved| Reserved| Reserved| Latitude| Longitude| Altitude| */
- MAV_CMD_UAVCAN_GET_NODE_INFO=5200, /* Commands the vehicle to respond with a sequence of messages UAVCAN_NODE_INFO, one message per every UAVCAN node that is online. Note that some of the response messages can be lost, which the receiver can detect easily by checking whether every received UAVCAN_NODE_STATUS has a matching message UAVCAN_NODE_INFO received earlier; if not, this command should be sent again in order to request re-transmission of the node information messages. |Reserved (set to 0)| Reserved (set to 0)| Reserved (set to 0)| Reserved (set to 0)| Reserved (set to 0)| Reserved (set to 0)| Reserved (set to 0)| */
- MAV_CMD_DO_SET_SAFETY_SWITCH_STATE=5300, /* Change state of safety switch. |New safety switch state.| Empty.| Empty.| Empty| Empty.| Empty.| Empty.| */
- MAV_CMD_DO_ADSB_OUT_IDENT=10001, /* Trigger the start of an ADSB-out IDENT. This should only be used when requested to do so by an Air Traffic Controller in controlled airspace. This starts the IDENT which is then typically held for 18 seconds by the hardware per the Mode A, C, and S transponder spec. |Reserved (set to 0)| Reserved (set to 0)| Reserved (set to 0)| Reserved (set to 0)| Reserved (set to 0)| Reserved (set to 0)| Reserved (set to 0)| */
- MAV_CMD_PAYLOAD_PREPARE_DEPLOY=30001, /* Deploy payload on a Lat / Lon / Alt position. This includes the navigation to reach the required release position and velocity. |Operation mode. 0: prepare single payload deploy (overwriting previous requests), but do not execute it. 1: execute payload deploy immediately (rejecting further deploy commands during execution, but allowing abort). 2: add payload deploy to existing deployment list.| Desired approach vector in compass heading. A negative value indicates the system can define the approach vector at will.| Desired ground speed at release time. This can be overridden by the airframe in case it needs to meet minimum airspeed. A negative value indicates the system can define the ground speed at will.| Minimum altitude clearance to the release position. A negative value indicates the system can define the clearance at will.| Latitude.| Longitude.| Altitude (MSL)| */
- MAV_CMD_PAYLOAD_CONTROL_DEPLOY=30002, /* Control the payload deployment. |Operation mode. 0: Abort deployment, continue normal mission. 1: switch to payload deployment mode. 100: delete first payload deployment request. 101: delete all payload deployment requests.| Reserved| Reserved| Reserved| Reserved| Reserved| Reserved| */
- MAV_CMD_WAYPOINT_USER_1=31000, /* User defined waypoint item. Ground Station will show the Vehicle as flying through this item. |User defined| User defined| User defined| User defined| Latitude unscaled| Longitude unscaled| Altitude (MSL)| */
- MAV_CMD_WAYPOINT_USER_2=31001, /* User defined waypoint item. Ground Station will show the Vehicle as flying through this item. |User defined| User defined| User defined| User defined| Latitude unscaled| Longitude unscaled| Altitude (MSL)| */
- MAV_CMD_WAYPOINT_USER_3=31002, /* User defined waypoint item. Ground Station will show the Vehicle as flying through this item. |User defined| User defined| User defined| User defined| Latitude unscaled| Longitude unscaled| Altitude (MSL)| */
- MAV_CMD_WAYPOINT_USER_4=31003, /* User defined waypoint item. Ground Station will show the Vehicle as flying through this item. |User defined| User defined| User defined| User defined| Latitude unscaled| Longitude unscaled| Altitude (MSL)| */
- MAV_CMD_WAYPOINT_USER_5=31004, /* User defined waypoint item. Ground Station will show the Vehicle as flying through this item. |User defined| User defined| User defined| User defined| Latitude unscaled| Longitude unscaled| Altitude (MSL)| */
- MAV_CMD_SPATIAL_USER_1=31005, /* User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item. |User defined| User defined| User defined| User defined| Latitude unscaled| Longitude unscaled| Altitude (MSL)| */
- MAV_CMD_SPATIAL_USER_2=31006, /* User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item. |User defined| User defined| User defined| User defined| Latitude unscaled| Longitude unscaled| Altitude (MSL)| */
- MAV_CMD_SPATIAL_USER_3=31007, /* User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item. |User defined| User defined| User defined| User defined| Latitude unscaled| Longitude unscaled| Altitude (MSL)| */
- MAV_CMD_SPATIAL_USER_4=31008, /* User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item. |User defined| User defined| User defined| User defined| Latitude unscaled| Longitude unscaled| Altitude (MSL)| */
- MAV_CMD_SPATIAL_USER_5=31009, /* User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item. |User defined| User defined| User defined| User defined| Latitude unscaled| Longitude unscaled| Altitude (MSL)| */
- MAV_CMD_USER_1=31010, /* User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item. |User defined| User defined| User defined| User defined| User defined| User defined| User defined| */
- MAV_CMD_USER_2=31011, /* User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item. |User defined| User defined| User defined| User defined| User defined| User defined| User defined| */
- MAV_CMD_USER_3=31012, /* User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item. |User defined| User defined| User defined| User defined| User defined| User defined| User defined| */
- MAV_CMD_USER_4=31013, /* User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item. |User defined| User defined| User defined| User defined| User defined| User defined| User defined| */
- MAV_CMD_USER_5=31014, /* User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item. |User defined| User defined| User defined| User defined| User defined| User defined| User defined| */
- MAV_CMD_CAN_FORWARD=32000, /* Request forwarding of CAN packets from the given CAN bus to this component. CAN Frames are sent using CAN_FRAME and CANFD_FRAME messages |Bus number (0 to disable forwarding, 1 for first bus, 2 for 2nd bus, 3 for 3rd bus).| Empty.| Empty.| Empty.| Empty.| Empty.| Empty.| */
- MAV_CMD_FIXED_MAG_CAL_YAW=42006, /* Magnetometer calibration based on provided known yaw. This allows for fast calibration using WMM field tables in the vehicle, given only the known yaw of the vehicle. If Latitude and longitude are both zero then use the current vehicle location. |Yaw of vehicle in earth frame.| CompassMask, 0 for all.| Latitude.| Longitude.| Empty.| Empty.| Empty.| */
- MAV_CMD_DO_WINCH=42600, /* Command to operate winch. |Winch instance number.| Action to perform.| Length of line to release (negative to wind).| Release rate (negative to wind).| Empty.| Empty.| Empty.| */
- MAV_CMD_EXTERNAL_POSITION_ESTIMATE=43003, /* Provide an external position estimate for use when dead-reckoning. This is meant to be used for occasional position resets that may be provided by a external system such as a remote pilot using landmarks over a video link. |Timestamp that this message was sent as a time in the transmitters time domain. The sender should wrap this time back to zero based on required timing accuracy for the application and the limitations of a 32 bit float. For example, wrapping at 10 hours would give approximately 1ms accuracy. Recipient must handle time wrap in any timing jitter correction applied to this field. Wrap rollover time should not be at not more than 250 seconds, which would give approximately 10 microsecond accuracy.| The time spent in processing the sensor data that is the basis for this position. The recipient can use this to improve time alignment of the data. Set to zero if not known.| estimated one standard deviation accuracy of the measurement. Set to NaN if not known.| Empty| Latitude| Longitude| Altitude, not used. Should be sent as NaN. May be supported in a future version of this message.| */
- MAV_CMD_ENUM_END=43004, /* | */
-} MAV_CMD;
+/** @brief Action for the magnetometer (param2) of MAV_CMD_PREFLIGHT_CALIBRATION. */
+#ifndef HAVE_ENUM_PREFLIGHT_CALIBRATION_MAGNETOMETER
+#define HAVE_ENUM_PREFLIGHT_CALIBRATION_MAGNETOMETER
+typedef enum PREFLIGHT_CALIBRATION_MAGNETOMETER
+{
+ PREFLIGHT_CALIBRATION_MAGNETOMETER_NONE=0, /* No action. | */
+ PREFLIGHT_CALIBRATION_MAGNETOMETER_START=1, /* Start magnetometer calibration. | */
+ PREFLIGHT_CALIBRATION_MAGNETOMETER_FORCE_SAVE=76, /* Force-accept the existing compass calibration as valid without re-running it. Useful after a parameter reload that cleared calibration validity flags. | */
+ PREFLIGHT_CALIBRATION_MAGNETOMETER_ENUM_END=77, /* | */
+} PREFLIGHT_CALIBRATION_MAGNETOMETER;
+#endif
+
+/** @brief Action for the accelerometer (param5) of MAV_CMD_PREFLIGHT_CALIBRATION. */
+#ifndef HAVE_ENUM_PREFLIGHT_CALIBRATION_ACCELEROMETER
+#define HAVE_ENUM_PREFLIGHT_CALIBRATION_ACCELEROMETER
+typedef enum PREFLIGHT_CALIBRATION_ACCELEROMETER
+{
+ PREFLIGHT_CALIBRATION_ACCELEROMETER_NONE=0, /* No action. | */
+ PREFLIGHT_CALIBRATION_ACCELEROMETER_FULL=1, /* Full 6-position accelerometer calibration. | */
+ PREFLIGHT_CALIBRATION_ACCELEROMETER_TRIM=2, /* Board level (trim) calibration. | */
+ PREFLIGHT_CALIBRATION_ACCELEROMETER_TEMPERATURE=3, /* Accelerometer temperature calibration. | */
+ PREFLIGHT_CALIBRATION_ACCELEROMETER_SIMPLE=4, /* Simple accelerometer calibration. | */
+ PREFLIGHT_CALIBRATION_ACCELEROMETER_FORCE_SAVE=76, /* Force-accept the existing accelerometer calibration as valid without re-running it. Useful after a parameter reload that cleared calibration validity flags. | */
+ PREFLIGHT_CALIBRATION_ACCELEROMETER_ENUM_END=77, /* | */
+} PREFLIGHT_CALIBRATION_ACCELEROMETER;
+#endif
+
+/** @brief */
+#ifndef HAVE_ENUM_NAV_TAKEOFF_FLAGS
+#define HAVE_ENUM_NAV_TAKEOFF_FLAGS
+typedef enum NAV_TAKEOFF_FLAGS
+{
+ NAV_TAKEOFF_FLAGS_HORIZONTAL_POSITION_NOT_REQUIRED=1, /* Accept the command even if the autopilot does not have control over its horizontal position (note that it might not have altitude control either). | */
+ NAV_TAKEOFF_FLAGS_ENUM_END=2, /* | */
+} NAV_TAKEOFF_FLAGS;
#endif
/** @brief A data stream is not a fixed set of messages, but rather a
@@ -1029,6 +792,24 @@ typedef enum MAV_PARAM_TYPE
} MAV_PARAM_TYPE;
#endif
+/** @brief Parameter protocol error types (see PARAM_ERROR). */
+#ifndef HAVE_ENUM_MAV_PARAM_ERROR
+#define HAVE_ENUM_MAV_PARAM_ERROR
+typedef enum MAV_PARAM_ERROR
+{
+ MAV_PARAM_ERROR_NO_ERROR=0, /* No error occurred (not expected in PARAM_ERROR but may be used in future implementations. | */
+ MAV_PARAM_ERROR_DOES_NOT_EXIST=1, /* Parameter does not exist | */
+ MAV_PARAM_ERROR_VALUE_OUT_OF_RANGE=2, /* Parameter value does not fit within accepted range | */
+ MAV_PARAM_ERROR_PERMISSION_DENIED=3, /* Caller is not permitted to set the value of this parameter | */
+ MAV_PARAM_ERROR_COMPONENT_NOT_FOUND=4, /* Unknown component specified | */
+ MAV_PARAM_ERROR_READ_ONLY=5, /* Parameter is read-only | */
+ MAV_PARAM_ERROR_TYPE_UNSUPPORTED=6, /* Parameter data type (MAV_PARAM_TYPE) is not supported by flight stack (at all) | */
+ MAV_PARAM_ERROR_TYPE_MISMATCH=7, /* Parameter type does not match expected type | */
+ MAV_PARAM_ERROR_READ_FAIL=8, /* Parameter exists but reading failed | */
+ MAV_PARAM_ERROR_ENUM_END=9, /* | */
+} MAV_PARAM_ERROR;
+#endif
+
/** @brief Specifies the datatype of a MAVLink extended parameter. */
#ifndef HAVE_ENUM_MAV_PARAM_EXT_TYPE
#define HAVE_ENUM_MAV_PARAM_EXT_TYPE
@@ -1056,7 +837,7 @@ typedef enum MAV_RESULT
{
MAV_RESULT_ACCEPTED=0, /* Command is valid (is supported and has valid parameters), and was executed. | */
MAV_RESULT_TEMPORARILY_REJECTED=1, /* Command is valid, but cannot be executed at this time. This is used to indicate a problem that should be fixed just by waiting (e.g. a state machine is busy, can't arm because have not got GPS lock, etc.). Retrying later should work. | */
- MAV_RESULT_DENIED=2, /* Command is invalid (is supported but has invalid parameters). Retrying same command and parameters will not work. | */
+ MAV_RESULT_DENIED=2, /* Command is invalid; it is supported but one or more parameter values are invalid (i.e. parameter reserved, value allowed by spec but not supported by flight stack, and so on). Retrying the same command and parameters will not work. | */
MAV_RESULT_UNSUPPORTED=3, /* Command is not supported (unknown). | */
MAV_RESULT_FAILED=4, /* Command is valid, but execution has failed. This is used to indicate any non-temporary or unexpected problem, i.e. any problem that must be fixed before the command can succeed/be retried. For example, attempting to write a file when out of memory, attempting to arm when sensors are not calibrated, etc. | */
MAV_RESULT_IN_PROGRESS=5, /* Command is valid and is being executed. This will be followed by further progress updates, i.e. the component may send further COMMAND_ACK messages with result MAV_RESULT_IN_PROGRESS (at a rate decided by the implementation), and must terminate by sending a COMMAND_ACK message with final result of the operation. The COMMAND_ACK.progress field can be used to indicate the progress of the operation. | */
@@ -1064,7 +845,8 @@ typedef enum MAV_RESULT
MAV_RESULT_COMMAND_LONG_ONLY=7, /* Command is only accepted when sent as a COMMAND_LONG. | */
MAV_RESULT_COMMAND_INT_ONLY=8, /* Command is only accepted when sent as a COMMAND_INT. | */
MAV_RESULT_COMMAND_UNSUPPORTED_MAV_FRAME=9, /* Command is invalid because a frame is required and the specified frame is not supported. | */
- MAV_RESULT_ENUM_END=10, /* | */
+ MAV_RESULT_NOT_IN_CONTROL=10, /* Command has been rejected because source system is not in control of the target system/component. | */
+ MAV_RESULT_ENUM_END=11, /* | */
} MAV_RESULT;
#endif
@@ -1813,7 +1595,7 @@ typedef enum CAMERA_MODE
} CAMERA_MODE;
#endif
-/** @brief */
+/** @brief Reasons for denying an authorization request made with MAV_CMD_ARM_AUTHORIZATION_REQUEST. If the COMMAND_ACK result is MAV_RESULT_DENIED, this is used to set the reason in the result_param2 field. */
#ifndef HAVE_ENUM_MAV_ARM_AUTH_DENIED_REASON
#define HAVE_ENUM_MAV_ARM_AUTH_DENIED_REASON
typedef enum MAV_ARM_AUTH_DENIED_REASON
@@ -1851,6 +1633,16 @@ typedef enum RC_SUB_TYPE
} RC_SUB_TYPE;
#endif
+/** @brief Engine control options */
+#ifndef HAVE_ENUM_ENGINE_CONTROL_OPTIONS
+#define HAVE_ENUM_ENGINE_CONTROL_OPTIONS
+typedef enum ENGINE_CONTROL_OPTIONS
+{
+ ENGINE_CONTROL_OPTIONS_ALLOW_START_WHILE_DISARMED=1, /* Allow starting the engine while disarmed (without changing the vehicle's armed state). This effectively arms just the ICE, without arming the vehicle to start other motors or propellers. | */
+ ENGINE_CONTROL_OPTIONS_ENUM_END=2, /* | */
+} ENGINE_CONTROL_OPTIONS;
+#endif
+
/** @brief Bitmap to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 9 is set the floats afx afy afz should be interpreted as force instead of acceleration. */
#ifndef HAVE_ENUM_POSITION_TARGET_TYPEMASK
#define HAVE_ENUM_POSITION_TARGET_TYPEMASK
@@ -2406,19 +2198,19 @@ typedef enum AIS_NAV_STATUS
#define HAVE_ENUM_AIS_FLAGS
typedef enum AIS_FLAGS
{
- AIS_FLAGS_POSITION_ACCURACY=1, /* 1 = Position accuracy less than 10m, 0 = position accuracy greater than 10m. | */
- AIS_FLAGS_VALID_COG=2, /* | */
- AIS_FLAGS_VALID_VELOCITY=4, /* | */
+ AIS_FLAGS_POSITION_ACCURACY=1, /* 1 = High (Position accuracy less than or equal to 10m), 0 = Low (position accuracy greater than 10m). | */
+ AIS_FLAGS_VALID_COG=2, /* The COG field contains valid data | */
+ AIS_FLAGS_VALID_VELOCITY=4, /* The velocity field contains valid data | */
AIS_FLAGS_HIGH_VELOCITY=8, /* 1 = Velocity over 52.5765m/s (102.2 knots) | */
- AIS_FLAGS_VALID_TURN_RATE=16, /* | */
- AIS_FLAGS_TURN_RATE_SIGN_ONLY=32, /* Only the sign of the returned turn rate value is valid, either greater than 5deg/30s or less than -5deg/30s | */
+ AIS_FLAGS_VALID_TURN_RATE=16, /* The turn_rate field contains valid data | */
+ AIS_FLAGS_TURN_RATE_SIGN_ONLY=32, /* Only the sign of the returned turn_rate value is valid. The actual turn rate is either greater than 5deg/30s or less than -5deg/30s. | */
AIS_FLAGS_VALID_DIMENSIONS=64, /* | */
- AIS_FLAGS_LARGE_BOW_DIMENSION=128, /* Distance to bow is larger than 511m | */
- AIS_FLAGS_LARGE_STERN_DIMENSION=256, /* Distance to stern is larger than 511m | */
- AIS_FLAGS_LARGE_PORT_DIMENSION=512, /* Distance to port side is larger than 63m | */
- AIS_FLAGS_LARGE_STARBOARD_DIMENSION=1024, /* Distance to starboard side is larger than 63m | */
- AIS_FLAGS_VALID_CALLSIGN=2048, /* | */
- AIS_FLAGS_VALID_NAME=4096, /* | */
+ AIS_FLAGS_LARGE_BOW_DIMENSION=128, /* Distance to bow is greater than or equal to 511m | */
+ AIS_FLAGS_LARGE_STERN_DIMENSION=256, /* Distance to stern is greater than or equal to 511m | */
+ AIS_FLAGS_LARGE_PORT_DIMENSION=512, /* Distance to port side is greater than or equal to 63m | */
+ AIS_FLAGS_LARGE_STARBOARD_DIMENSION=1024, /* Distance to starboard side is greater than or equal to 63m | */
+ AIS_FLAGS_VALID_CALLSIGN=2048, /* The callsign field contains valid data | */
+ AIS_FLAGS_VALID_NAME=4096, /* The name field contains valid data | */
AIS_FLAGS_ENUM_END=4097, /* | */
} AIS_FLAGS;
#endif
@@ -2470,10 +2262,8 @@ typedef enum FAILURE_TYPE
typedef enum NAV_VTOL_LAND_OPTIONS
{
NAV_VTOL_LAND_OPTIONS_DEFAULT=0, /* Default autopilot landing behaviour. | */
- NAV_VTOL_LAND_OPTIONS_FW_DESCENT=1, /* Descend in fixed wing mode, transitioning to multicopter mode for vertical landing when close to the ground.
- The fixed wing descent pattern is at the discretion of the vehicle (e.g. transition altitude, loiter direction, radius, and speed, etc.).
- | */
- NAV_VTOL_LAND_OPTIONS_HOVER_DESCENT=2, /* Land in multicopter mode on reaching the landing coordinates (the whole landing is by "hover descent"). | */
+ NAV_VTOL_LAND_OPTIONS_FW_SPIRAL_APPROACH=1, /* Use a fixed wing spiral desent approach before landing. | */
+ NAV_VTOL_LAND_OPTIONS_FW_APPROACH=2, /* Use a fixed wing approach before detransitioning and landing vertically. | */
NAV_VTOL_LAND_OPTIONS_ENUM_END=3, /* | */
} NAV_VTOL_LAND_OPTIONS;
#endif
@@ -2595,7 +2385,7 @@ typedef enum CAN_FILTER_OP
} CAN_FILTER_OP;
#endif
-/** @brief MAV FTP error codes (https://mavlink.io/en/services/ftp.html) */
+/** @brief MAV FTP error codes (may be used in FILE_TRANSFER_PROTOCOL). See https://mavlink.io/en/services/ftp.html. */
#ifndef HAVE_ENUM_MAV_FTP_ERR
#define HAVE_ENUM_MAV_FTP_ERR
typedef enum MAV_FTP_ERR
@@ -2616,7 +2406,7 @@ typedef enum MAV_FTP_ERR
} MAV_FTP_ERR;
#endif
-/** @brief MAV FTP opcodes: https://mavlink.io/en/services/ftp.html */
+/** @brief MAV FTP opcodes (may be used in FILE_TRANSFER_PROTOCOL). See https://mavlink.io/en/services/ftp.html. */
#ifndef HAVE_ENUM_MAV_FTP_OPCODE
#define HAVE_ENUM_MAV_FTP_OPCODE
typedef enum MAV_FTP_OPCODE
@@ -2798,6 +2588,57 @@ typedef enum HIL_ACTUATOR_CONTROLS_FLAGS
} HIL_ACTUATOR_CONTROLS_FLAGS;
#endif
+/** @brief Flags used to report computer status. */
+#ifndef HAVE_ENUM_COMPUTER_STATUS_FLAGS
+#define HAVE_ENUM_COMPUTER_STATUS_FLAGS
+typedef enum COMPUTER_STATUS_FLAGS
+{
+ COMPUTER_STATUS_FLAGS_UNDER_VOLTAGE=1, /* Indicates if the system is experiencing voltage outside of acceptable range. | */
+ COMPUTER_STATUS_FLAGS_CPU_THROTTLE=2, /* Indicates if CPU throttling is active. | */
+ COMPUTER_STATUS_FLAGS_THERMAL_THROTTLE=4, /* Indicates if thermal throttling is active. | */
+ COMPUTER_STATUS_FLAGS_DISK_FULL=8, /* Indicates if main disk is full. | */
+ COMPUTER_STATUS_FLAGS_ENUM_END=9, /* | */
+} COMPUTER_STATUS_FLAGS;
+#endif
+
+/** @brief Airspeed sensor flags */
+#ifndef HAVE_ENUM_AIRSPEED_SENSOR_FLAGS
+#define HAVE_ENUM_AIRSPEED_SENSOR_FLAGS
+typedef enum AIRSPEED_SENSOR_FLAGS
+{
+ AIRSPEED_SENSOR_UNHEALTHY=1, /* Airspeed sensor is unhealthy | */
+ AIRSPEED_SENSOR_USING=2, /* True if the data from this sensor is being actively used by the flight controller for guidance, navigation or control. | */
+ AIRSPEED_SENSOR_FLAGS_ENUM_END=3, /* | */
+} AIRSPEED_SENSOR_FLAGS;
+#endif
+
+/** @brief Source for GLOBAL_POSITION measurement or estimate. */
+#ifndef HAVE_ENUM_GLOBAL_POSITION_SRC
+#define HAVE_ENUM_GLOBAL_POSITION_SRC
+typedef enum GLOBAL_POSITION_SRC
+{
+ GLOBAL_POSITION_SRC_UNKNOWN=0, /* Source is unknown or not one of the listed types. | */
+ GLOBAL_POSITION_SRC_GNSS=1, /* Global Navigation Satellite System (e.g.: GPS, Galileo, Glonass, BeiDou). | */
+ GLOBAL_POSITION_SRC_VISION=2, /* Vision system (e.g.: map matching). | */
+ GLOBAL_POSITION_SRC_PSEUDOLITES=3, /* A pseudo-satellite system using transceiver beacons to perform GNSS-like positioning. | */
+ GLOBAL_POSITION_SRC_TERRAIN=4, /* Terrain referenced navigation. | */
+ GLOBAL_POSITION_SRC_MAGNETIC=5, /* Magnetic positioning. | */
+ GLOBAL_POSITION_SRC_ESTIMATOR=6, /* Estimated position based on various sensors (eg. a Kalman Filter). | */
+ GLOBAL_POSITION_SRC_ENUM_END=7, /* | */
+} GLOBAL_POSITION_SRC;
+#endif
+
+/** @brief Status flags for GLOBAL_POSITION */
+#ifndef HAVE_ENUM_GLOBAL_POSITION_FLAGS
+#define HAVE_ENUM_GLOBAL_POSITION_FLAGS
+typedef enum GLOBAL_POSITION_FLAGS
+{
+ GLOBAL_POSITION_UNHEALTHY=1, /* Unhealthy sensor/estimator. | */
+ GLOBAL_POSITION_PRIMARY=2, /* True if the data originates from or is consumed by the primary estimator. | */
+ GLOBAL_POSITION_FLAGS_ENUM_END=3, /* | */
+} GLOBAL_POSITION_FLAGS;
+#endif
+
// MAVLINK VERSION
#ifndef MAVLINK_VERSION
@@ -2831,7 +2672,6 @@ typedef enum HIL_ACTUATOR_CONTROLS_FLAGS
#include "./mavlink_msg_attitude.h"
#include "./mavlink_msg_attitude_quaternion.h"
#include "./mavlink_msg_local_position_ned.h"
-#include "./mavlink_msg_global_position_int.h"
#include "./mavlink_msg_rc_channels_scaled.h"
#include "./mavlink_msg_rc_channels_raw.h"
#include "./mavlink_msg_servo_output_raw.h"
@@ -2980,7 +2820,10 @@ typedef enum HIL_ACTUATOR_CONTROLS_FLAGS
#include "./mavlink_msg_gimbal_manager_set_manual_control.h"
#include "./mavlink_msg_esc_info.h"
#include "./mavlink_msg_esc_status.h"
+#include "./mavlink_msg_airspeed.h"
+#include "./mavlink_msg_global_position_sensor.h"
#include "./mavlink_msg_wifi_config_ap.h"
+#include "./mavlink_msg_protocol_version.h"
#include "./mavlink_msg_ais_vessel.h"
#include "./mavlink_msg_uavcan_node_status.h"
#include "./mavlink_msg_uavcan_node_info.h"
@@ -2998,13 +2841,16 @@ typedef enum HIL_ACTUATOR_CONTROLS_FLAGS
#include "./mavlink_msg_cellular_config.h"
#include "./mavlink_msg_raw_rpm.h"
#include "./mavlink_msg_utm_global_position.h"
+#include "./mavlink_msg_param_error.h"
#include "./mavlink_msg_debug_float_array.h"
#include "./mavlink_msg_orbit_execution_status.h"
#include "./mavlink_msg_smart_battery_info.h"
+#include "./mavlink_msg_figure_eight_execution_status.h"
#include "./mavlink_msg_fuel_status.h"
#include "./mavlink_msg_battery_info.h"
#include "./mavlink_msg_generator_status.h"
#include "./mavlink_msg_actuator_output_status.h"
+#include "./mavlink_msg_relay_status.h"
#include "./mavlink_msg_time_estimate_to_target.h"
#include "./mavlink_msg_tunnel.h"
#include "./mavlink_msg_can_frame.h"
@@ -3042,8 +2888,8 @@ typedef enum HIL_ACTUATOR_CONTROLS_FLAGS
#if MAVLINK_COMMON_XML_HASH == MAVLINK_PRIMARY_XML_HASH
-# define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_SYS_STATUS, MAVLINK_MESSAGE_INFO_SYSTEM_TIME, MAVLINK_MESSAGE_INFO_PING, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK, MAVLINK_MESSAGE_INFO_AUTH_KEY, MAVLINK_MESSAGE_INFO_LINK_NODE_STATUS, MAVLINK_MESSAGE_INFO_SET_MODE, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_VALUE, MAVLINK_MESSAGE_INFO_PARAM_SET, MAVLINK_MESSAGE_INFO_GPS_RAW_INT, MAVLINK_MESSAGE_INFO_GPS_STATUS, MAVLINK_MESSAGE_INFO_SCALED_IMU, MAVLINK_MESSAGE_INFO_RAW_IMU, MAVLINK_MESSAGE_INFO_RAW_PRESSURE, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE, MAVLINK_MESSAGE_INFO_ATTITUDE, MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT, MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED, MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW, MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_WRITE_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_ITEM, MAVLINK_MESSAGE_INFO_MISSION_REQUEST, MAVLINK_MESSAGE_INFO_MISSION_SET_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_LIST, MAVLINK_MESSAGE_INFO_MISSION_COUNT, MAVLINK_MESSAGE_INFO_MISSION_CLEAR_ALL, MAVLINK_MESSAGE_INFO_MISSION_ITEM_REACHED, MAVLINK_MESSAGE_INFO_MISSION_ACK, MAVLINK_MESSAGE_INFO_SET_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_PARAM_MAP_RC, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_INT, MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION_COV, MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT_COV, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_COV, MAVLINK_MESSAGE_INFO_RC_CHANNELS, MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM, MAVLINK_MESSAGE_INFO_DATA_STREAM, MAVLINK_MESSAGE_INFO_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE, MAVLINK_MESSAGE_INFO_MISSION_ITEM_INT, MAVLINK_MESSAGE_INFO_VFR_HUD, MAVLINK_MESSAGE_INFO_COMMAND_INT, MAVLINK_MESSAGE_INFO_COMMAND_LONG, MAVLINK_MESSAGE_INFO_COMMAND_ACK, MAVLINK_MESSAGE_INFO_COMMAND_CANCEL, MAVLINK_MESSAGE_INFO_MANUAL_SETPOINT, MAVLINK_MESSAGE_INFO_SET_ATTITUDE_TARGET, MAVLINK_MESSAGE_INFO_ATTITUDE_TARGET, MAVLINK_MESSAGE_INFO_SET_POSITION_TARGET_LOCAL_NED, MAVLINK_MESSAGE_INFO_POSITION_TARGET_LOCAL_NED, MAVLINK_MESSAGE_INFO_SET_POSITION_TARGET_GLOBAL_INT, MAVLINK_MESSAGE_INFO_POSITION_TARGET_GLOBAL_INT, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, MAVLINK_MESSAGE_INFO_HIL_STATE, MAVLINK_MESSAGE_INFO_HIL_CONTROLS, MAVLINK_MESSAGE_INFO_HIL_RC_INPUTS_RAW, MAVLINK_MESSAGE_INFO_HIL_ACTUATOR_CONTROLS, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_GLOBAL_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE, MAVLINK_MESSAGE_INFO_VICON_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_HIGHRES_IMU, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW_RAD, MAVLINK_MESSAGE_INFO_HIL_SENSOR, MAVLINK_MESSAGE_INFO_SIM_STATE, MAVLINK_MESSAGE_INFO_RADIO_STATUS, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_PROTOCOL, MAVLINK_MESSAGE_INFO_TIMESYNC, MAVLINK_MESSAGE_INFO_CAMERA_TRIGGER, MAVLINK_MESSAGE_INFO_HIL_GPS, MAVLINK_MESSAGE_INFO_HIL_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_HIL_STATE_QUATERNION, MAVLINK_MESSAGE_INFO_SCALED_IMU2, MAVLINK_MESSAGE_INFO_LOG_REQUEST_LIST, MAVLINK_MESSAGE_INFO_LOG_ENTRY, MAVLINK_MESSAGE_INFO_LOG_REQUEST_DATA, MAVLINK_MESSAGE_INFO_LOG_DATA, MAVLINK_MESSAGE_INFO_LOG_ERASE, MAVLINK_MESSAGE_INFO_LOG_REQUEST_END, MAVLINK_MESSAGE_INFO_GPS_INJECT_DATA, MAVLINK_MESSAGE_INFO_GPS2_RAW, MAVLINK_MESSAGE_INFO_POWER_STATUS, MAVLINK_MESSAGE_INFO_SERIAL_CONTROL, MAVLINK_MESSAGE_INFO_GPS_RTK, MAVLINK_MESSAGE_INFO_GPS2_RTK, MAVLINK_MESSAGE_INFO_SCALED_IMU3, MAVLINK_MESSAGE_INFO_DATA_TRANSMISSION_HANDSHAKE, MAVLINK_MESSAGE_INFO_ENCAPSULATED_DATA, MAVLINK_MESSAGE_INFO_DISTANCE_SENSOR, MAVLINK_MESSAGE_INFO_TERRAIN_REQUEST, MAVLINK_MESSAGE_INFO_TERRAIN_DATA, MAVLINK_MESSAGE_INFO_TERRAIN_CHECK, MAVLINK_MESSAGE_INFO_TERRAIN_REPORT, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE2, MAVLINK_MESSAGE_INFO_ATT_POS_MOCAP, MAVLINK_MESSAGE_INFO_SET_ACTUATOR_CONTROL_TARGET, MAVLINK_MESSAGE_INFO_ACTUATOR_CONTROL_TARGET, MAVLINK_MESSAGE_INFO_ALTITUDE, MAVLINK_MESSAGE_INFO_RESOURCE_REQUEST, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE3, MAVLINK_MESSAGE_INFO_FOLLOW_TARGET, MAVLINK_MESSAGE_INFO_CONTROL_SYSTEM_STATE, MAVLINK_MESSAGE_INFO_BATTERY_STATUS, MAVLINK_MESSAGE_INFO_AUTOPILOT_VERSION, MAVLINK_MESSAGE_INFO_LANDING_TARGET, MAVLINK_MESSAGE_INFO_FENCE_STATUS, MAVLINK_MESSAGE_INFO_MAG_CAL_REPORT, MAVLINK_MESSAGE_INFO_EFI_STATUS, MAVLINK_MESSAGE_INFO_ESTIMATOR_STATUS, MAVLINK_MESSAGE_INFO_WIND_COV, MAVLINK_MESSAGE_INFO_GPS_INPUT, MAVLINK_MESSAGE_INFO_GPS_RTCM_DATA, MAVLINK_MESSAGE_INFO_HIGH_LATENCY, MAVLINK_MESSAGE_INFO_HIGH_LATENCY2, MAVLINK_MESSAGE_INFO_VIBRATION, MAVLINK_MESSAGE_INFO_HOME_POSITION, MAVLINK_MESSAGE_INFO_SET_HOME_POSITION, MAVLINK_MESSAGE_INFO_MESSAGE_INTERVAL, MAVLINK_MESSAGE_INFO_EXTENDED_SYS_STATE, MAVLINK_MESSAGE_INFO_ADSB_VEHICLE, MAVLINK_MESSAGE_INFO_COLLISION, MAVLINK_MESSAGE_INFO_V2_EXTENSION, MAVLINK_MESSAGE_INFO_MEMORY_VECT, MAVLINK_MESSAGE_INFO_DEBUG_VECT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT, MAVLINK_MESSAGE_INFO_STATUSTEXT, MAVLINK_MESSAGE_INFO_DEBUG, MAVLINK_MESSAGE_INFO_SETUP_SIGNING, MAVLINK_MESSAGE_INFO_BUTTON_CHANGE, MAVLINK_MESSAGE_INFO_PLAY_TUNE, MAVLINK_MESSAGE_INFO_CAMERA_INFORMATION, MAVLINK_MESSAGE_INFO_CAMERA_SETTINGS, MAVLINK_MESSAGE_INFO_STORAGE_INFORMATION, MAVLINK_MESSAGE_INFO_CAMERA_CAPTURE_STATUS, MAVLINK_MESSAGE_INFO_CAMERA_IMAGE_CAPTURED, MAVLINK_MESSAGE_INFO_FLIGHT_INFORMATION, MAVLINK_MESSAGE_INFO_MOUNT_ORIENTATION, MAVLINK_MESSAGE_INFO_LOGGING_DATA, MAVLINK_MESSAGE_INFO_LOGGING_DATA_ACKED, MAVLINK_MESSAGE_INFO_LOGGING_ACK, MAVLINK_MESSAGE_INFO_VIDEO_STREAM_INFORMATION, MAVLINK_MESSAGE_INFO_VIDEO_STREAM_STATUS, MAVLINK_MESSAGE_INFO_CAMERA_FOV_STATUS, MAVLINK_MESSAGE_INFO_CAMERA_TRACKING_IMAGE_STATUS, MAVLINK_MESSAGE_INFO_CAMERA_TRACKING_GEO_STATUS, MAVLINK_MESSAGE_INFO_CAMERA_THERMAL_RANGE, MAVLINK_MESSAGE_INFO_GIMBAL_MANAGER_INFORMATION, MAVLINK_MESSAGE_INFO_GIMBAL_MANAGER_STATUS, MAVLINK_MESSAGE_INFO_GIMBAL_MANAGER_SET_ATTITUDE, MAVLINK_MESSAGE_INFO_GIMBAL_DEVICE_INFORMATION, MAVLINK_MESSAGE_INFO_GIMBAL_DEVICE_SET_ATTITUDE, MAVLINK_MESSAGE_INFO_GIMBAL_DEVICE_ATTITUDE_STATUS, MAVLINK_MESSAGE_INFO_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE, MAVLINK_MESSAGE_INFO_GIMBAL_MANAGER_SET_PITCHYAW, MAVLINK_MESSAGE_INFO_GIMBAL_MANAGER_SET_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_ESC_INFO, MAVLINK_MESSAGE_INFO_ESC_STATUS, MAVLINK_MESSAGE_INFO_WIFI_CONFIG_AP, MAVLINK_MESSAGE_INFO_PROTOCOL_VERSION, MAVLINK_MESSAGE_INFO_AIS_VESSEL, MAVLINK_MESSAGE_INFO_UAVCAN_NODE_STATUS, MAVLINK_MESSAGE_INFO_UAVCAN_NODE_INFO, MAVLINK_MESSAGE_INFO_PARAM_EXT_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_EXT_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_EXT_VALUE, MAVLINK_MESSAGE_INFO_PARAM_EXT_SET, MAVLINK_MESSAGE_INFO_PARAM_EXT_ACK, MAVLINK_MESSAGE_INFO_OBSTACLE_DISTANCE, MAVLINK_MESSAGE_INFO_ODOMETRY, MAVLINK_MESSAGE_INFO_TRAJECTORY_REPRESENTATION_WAYPOINTS, MAVLINK_MESSAGE_INFO_TRAJECTORY_REPRESENTATION_BEZIER, MAVLINK_MESSAGE_INFO_CELLULAR_STATUS, MAVLINK_MESSAGE_INFO_ISBD_LINK_STATUS, MAVLINK_MESSAGE_INFO_CELLULAR_CONFIG, MAVLINK_MESSAGE_INFO_RAW_RPM, MAVLINK_MESSAGE_INFO_UTM_GLOBAL_POSITION, MAVLINK_MESSAGE_INFO_DEBUG_FLOAT_ARRAY, MAVLINK_MESSAGE_INFO_ORBIT_EXECUTION_STATUS, MAVLINK_MESSAGE_INFO_SMART_BATTERY_INFO, MAVLINK_MESSAGE_INFO_FUEL_STATUS, MAVLINK_MESSAGE_INFO_BATTERY_INFO, MAVLINK_MESSAGE_INFO_GENERATOR_STATUS, MAVLINK_MESSAGE_INFO_ACTUATOR_OUTPUT_STATUS, MAVLINK_MESSAGE_INFO_TIME_ESTIMATE_TO_TARGET, MAVLINK_MESSAGE_INFO_TUNNEL, MAVLINK_MESSAGE_INFO_CAN_FRAME, MAVLINK_MESSAGE_INFO_CANFD_FRAME, MAVLINK_MESSAGE_INFO_CAN_FILTER_MODIFY, MAVLINK_MESSAGE_INFO_ONBOARD_COMPUTER_STATUS, MAVLINK_MESSAGE_INFO_COMPONENT_INFORMATION, MAVLINK_MESSAGE_INFO_COMPONENT_INFORMATION_BASIC, MAVLINK_MESSAGE_INFO_COMPONENT_METADATA, MAVLINK_MESSAGE_INFO_PLAY_TUNE_V2, MAVLINK_MESSAGE_INFO_SUPPORTED_TUNES, MAVLINK_MESSAGE_INFO_EVENT, MAVLINK_MESSAGE_INFO_CURRENT_EVENT_SEQUENCE, MAVLINK_MESSAGE_INFO_REQUEST_EVENT, MAVLINK_MESSAGE_INFO_RESPONSE_EVENT_ERROR, MAVLINK_MESSAGE_INFO_AVAILABLE_MODES, MAVLINK_MESSAGE_INFO_CURRENT_MODE, MAVLINK_MESSAGE_INFO_AVAILABLE_MODES_MONITOR, MAVLINK_MESSAGE_INFO_ILLUMINATOR_STATUS, MAVLINK_MESSAGE_INFO_WHEEL_DISTANCE, MAVLINK_MESSAGE_INFO_WINCH_STATUS, MAVLINK_MESSAGE_INFO_OPEN_DRONE_ID_BASIC_ID, MAVLINK_MESSAGE_INFO_OPEN_DRONE_ID_LOCATION, MAVLINK_MESSAGE_INFO_OPEN_DRONE_ID_AUTHENTICATION, MAVLINK_MESSAGE_INFO_OPEN_DRONE_ID_SELF_ID, MAVLINK_MESSAGE_INFO_OPEN_DRONE_ID_SYSTEM, MAVLINK_MESSAGE_INFO_OPEN_DRONE_ID_OPERATOR_ID, MAVLINK_MESSAGE_INFO_OPEN_DRONE_ID_MESSAGE_PACK, MAVLINK_MESSAGE_INFO_OPEN_DRONE_ID_ARM_STATUS, MAVLINK_MESSAGE_INFO_OPEN_DRONE_ID_SYSTEM_UPDATE, MAVLINK_MESSAGE_INFO_HYGROMETER_SENSOR}
-# define MAVLINK_MESSAGE_NAMES {{ "ACTUATOR_CONTROL_TARGET", 140 }, { "ACTUATOR_OUTPUT_STATUS", 375 }, { "ADSB_VEHICLE", 246 }, { "AIS_VESSEL", 301 }, { "ALTITUDE", 141 }, { "ATTITUDE", 30 }, { "ATTITUDE_QUATERNION", 31 }, { "ATTITUDE_QUATERNION_COV", 61 }, { "ATTITUDE_TARGET", 83 }, { "ATT_POS_MOCAP", 138 }, { "AUTH_KEY", 7 }, { "AUTOPILOT_STATE_FOR_GIMBAL_DEVICE", 286 }, { "AUTOPILOT_VERSION", 148 }, { "AVAILABLE_MODES", 435 }, { "AVAILABLE_MODES_MONITOR", 437 }, { "BATTERY_INFO", 372 }, { "BATTERY_STATUS", 147 }, { "BUTTON_CHANGE", 257 }, { "CAMERA_CAPTURE_STATUS", 262 }, { "CAMERA_FOV_STATUS", 271 }, { "CAMERA_IMAGE_CAPTURED", 263 }, { "CAMERA_INFORMATION", 259 }, { "CAMERA_SETTINGS", 260 }, { "CAMERA_THERMAL_RANGE", 277 }, { "CAMERA_TRACKING_GEO_STATUS", 276 }, { "CAMERA_TRACKING_IMAGE_STATUS", 275 }, { "CAMERA_TRIGGER", 112 }, { "CANFD_FRAME", 387 }, { "CAN_FILTER_MODIFY", 388 }, { "CAN_FRAME", 386 }, { "CELLULAR_CONFIG", 336 }, { "CELLULAR_STATUS", 334 }, { "CHANGE_OPERATOR_CONTROL", 5 }, { "CHANGE_OPERATOR_CONTROL_ACK", 6 }, { "COLLISION", 247 }, { "COMMAND_ACK", 77 }, { "COMMAND_CANCEL", 80 }, { "COMMAND_INT", 75 }, { "COMMAND_LONG", 76 }, { "COMPONENT_INFORMATION", 395 }, { "COMPONENT_INFORMATION_BASIC", 396 }, { "COMPONENT_METADATA", 397 }, { "CONTROL_SYSTEM_STATE", 146 }, { "CURRENT_EVENT_SEQUENCE", 411 }, { "CURRENT_MODE", 436 }, { "DATA_STREAM", 67 }, { "DATA_TRANSMISSION_HANDSHAKE", 130 }, { "DEBUG", 254 }, { "DEBUG_FLOAT_ARRAY", 350 }, { "DEBUG_VECT", 250 }, { "DISTANCE_SENSOR", 132 }, { "EFI_STATUS", 225 }, { "ENCAPSULATED_DATA", 131 }, { "ESC_INFO", 290 }, { "ESC_STATUS", 291 }, { "ESTIMATOR_STATUS", 230 }, { "EVENT", 410 }, { "EXTENDED_SYS_STATE", 245 }, { "FENCE_STATUS", 162 }, { "FILE_TRANSFER_PROTOCOL", 110 }, { "FLIGHT_INFORMATION", 264 }, { "FOLLOW_TARGET", 144 }, { "FUEL_STATUS", 371 }, { "GENERATOR_STATUS", 373 }, { "GIMBAL_DEVICE_ATTITUDE_STATUS", 285 }, { "GIMBAL_DEVICE_INFORMATION", 283 }, { "GIMBAL_DEVICE_SET_ATTITUDE", 284 }, { "GIMBAL_MANAGER_INFORMATION", 280 }, { "GIMBAL_MANAGER_SET_ATTITUDE", 282 }, { "GIMBAL_MANAGER_SET_MANUAL_CONTROL", 288 }, { "GIMBAL_MANAGER_SET_PITCHYAW", 287 }, { "GIMBAL_MANAGER_STATUS", 281 }, { "GLOBAL_POSITION_INT", 33 }, { "GLOBAL_POSITION_INT_COV", 63 }, { "GLOBAL_VISION_POSITION_ESTIMATE", 101 }, { "GPS2_RAW", 124 }, { "GPS2_RTK", 128 }, { "GPS_GLOBAL_ORIGIN", 49 }, { "GPS_INJECT_DATA", 123 }, { "GPS_INPUT", 232 }, { "GPS_RAW_INT", 24 }, { "GPS_RTCM_DATA", 233 }, { "GPS_RTK", 127 }, { "GPS_STATUS", 25 }, { "HEARTBEAT", 0 }, { "HIGHRES_IMU", 105 }, { "HIGH_LATENCY", 234 }, { "HIGH_LATENCY2", 235 }, { "HIL_ACTUATOR_CONTROLS", 93 }, { "HIL_CONTROLS", 91 }, { "HIL_GPS", 113 }, { "HIL_OPTICAL_FLOW", 114 }, { "HIL_RC_INPUTS_RAW", 92 }, { "HIL_SENSOR", 107 }, { "HIL_STATE", 90 }, { "HIL_STATE_QUATERNION", 115 }, { "HOME_POSITION", 242 }, { "HYGROMETER_SENSOR", 12920 }, { "ILLUMINATOR_STATUS", 440 }, { "ISBD_LINK_STATUS", 335 }, { "LANDING_TARGET", 149 }, { "LINK_NODE_STATUS", 8 }, { "LOCAL_POSITION_NED", 32 }, { "LOCAL_POSITION_NED_COV", 64 }, { "LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET", 89 }, { "LOGGING_ACK", 268 }, { "LOGGING_DATA", 266 }, { "LOGGING_DATA_ACKED", 267 }, { "LOG_DATA", 120 }, { "LOG_ENTRY", 118 }, { "LOG_ERASE", 121 }, { "LOG_REQUEST_DATA", 119 }, { "LOG_REQUEST_END", 122 }, { "LOG_REQUEST_LIST", 117 }, { "MAG_CAL_REPORT", 192 }, { "MANUAL_CONTROL", 69 }, { "MANUAL_SETPOINT", 81 }, { "MEMORY_VECT", 249 }, { "MESSAGE_INTERVAL", 244 }, { "MISSION_ACK", 47 }, { "MISSION_CLEAR_ALL", 45 }, { "MISSION_COUNT", 44 }, { "MISSION_CURRENT", 42 }, { "MISSION_ITEM", 39 }, { "MISSION_ITEM_INT", 73 }, { "MISSION_ITEM_REACHED", 46 }, { "MISSION_REQUEST", 40 }, { "MISSION_REQUEST_INT", 51 }, { "MISSION_REQUEST_LIST", 43 }, { "MISSION_REQUEST_PARTIAL_LIST", 37 }, { "MISSION_SET_CURRENT", 41 }, { "MISSION_WRITE_PARTIAL_LIST", 38 }, { "MOUNT_ORIENTATION", 265 }, { "NAMED_VALUE_FLOAT", 251 }, { "NAMED_VALUE_INT", 252 }, { "NAV_CONTROLLER_OUTPUT", 62 }, { "OBSTACLE_DISTANCE", 330 }, { "ODOMETRY", 331 }, { "ONBOARD_COMPUTER_STATUS", 390 }, { "OPEN_DRONE_ID_ARM_STATUS", 12918 }, { "OPEN_DRONE_ID_AUTHENTICATION", 12902 }, { "OPEN_DRONE_ID_BASIC_ID", 12900 }, { "OPEN_DRONE_ID_LOCATION", 12901 }, { "OPEN_DRONE_ID_MESSAGE_PACK", 12915 }, { "OPEN_DRONE_ID_OPERATOR_ID", 12905 }, { "OPEN_DRONE_ID_SELF_ID", 12903 }, { "OPEN_DRONE_ID_SYSTEM", 12904 }, { "OPEN_DRONE_ID_SYSTEM_UPDATE", 12919 }, { "OPTICAL_FLOW", 100 }, { "OPTICAL_FLOW_RAD", 106 }, { "ORBIT_EXECUTION_STATUS", 360 }, { "PARAM_EXT_ACK", 324 }, { "PARAM_EXT_REQUEST_LIST", 321 }, { "PARAM_EXT_REQUEST_READ", 320 }, { "PARAM_EXT_SET", 323 }, { "PARAM_EXT_VALUE", 322 }, { "PARAM_MAP_RC", 50 }, { "PARAM_REQUEST_LIST", 21 }, { "PARAM_REQUEST_READ", 20 }, { "PARAM_SET", 23 }, { "PARAM_VALUE", 22 }, { "PING", 4 }, { "PLAY_TUNE", 258 }, { "PLAY_TUNE_V2", 400 }, { "POSITION_TARGET_GLOBAL_INT", 87 }, { "POSITION_TARGET_LOCAL_NED", 85 }, { "POWER_STATUS", 125 }, { "PROTOCOL_VERSION", 300 }, { "RADIO_STATUS", 109 }, { "RAW_IMU", 27 }, { "RAW_PRESSURE", 28 }, { "RAW_RPM", 339 }, { "RC_CHANNELS", 65 }, { "RC_CHANNELS_OVERRIDE", 70 }, { "RC_CHANNELS_RAW", 35 }, { "RC_CHANNELS_SCALED", 34 }, { "REQUEST_DATA_STREAM", 66 }, { "REQUEST_EVENT", 412 }, { "RESOURCE_REQUEST", 142 }, { "RESPONSE_EVENT_ERROR", 413 }, { "SAFETY_ALLOWED_AREA", 55 }, { "SAFETY_SET_ALLOWED_AREA", 54 }, { "SCALED_IMU", 26 }, { "SCALED_IMU2", 116 }, { "SCALED_IMU3", 129 }, { "SCALED_PRESSURE", 29 }, { "SCALED_PRESSURE2", 137 }, { "SCALED_PRESSURE3", 143 }, { "SERIAL_CONTROL", 126 }, { "SERVO_OUTPUT_RAW", 36 }, { "SETUP_SIGNING", 256 }, { "SET_ACTUATOR_CONTROL_TARGET", 139 }, { "SET_ATTITUDE_TARGET", 82 }, { "SET_GPS_GLOBAL_ORIGIN", 48 }, { "SET_HOME_POSITION", 243 }, { "SET_MODE", 11 }, { "SET_POSITION_TARGET_GLOBAL_INT", 86 }, { "SET_POSITION_TARGET_LOCAL_NED", 84 }, { "SIM_STATE", 108 }, { "SMART_BATTERY_INFO", 370 }, { "STATUSTEXT", 253 }, { "STORAGE_INFORMATION", 261 }, { "SUPPORTED_TUNES", 401 }, { "SYSTEM_TIME", 2 }, { "SYS_STATUS", 1 }, { "TERRAIN_CHECK", 135 }, { "TERRAIN_DATA", 134 }, { "TERRAIN_REPORT", 136 }, { "TERRAIN_REQUEST", 133 }, { "TIMESYNC", 111 }, { "TIME_ESTIMATE_TO_TARGET", 380 }, { "TRAJECTORY_REPRESENTATION_BEZIER", 333 }, { "TRAJECTORY_REPRESENTATION_WAYPOINTS", 332 }, { "TUNNEL", 385 }, { "UAVCAN_NODE_INFO", 311 }, { "UAVCAN_NODE_STATUS", 310 }, { "UTM_GLOBAL_POSITION", 340 }, { "V2_EXTENSION", 248 }, { "VFR_HUD", 74 }, { "VIBRATION", 241 }, { "VICON_POSITION_ESTIMATE", 104 }, { "VIDEO_STREAM_INFORMATION", 269 }, { "VIDEO_STREAM_STATUS", 270 }, { "VISION_POSITION_ESTIMATE", 102 }, { "VISION_SPEED_ESTIMATE", 103 }, { "WHEEL_DISTANCE", 9000 }, { "WIFI_CONFIG_AP", 299 }, { "WINCH_STATUS", 9005 }, { "WIND_COV", 231 }}
+# define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_SYS_STATUS, MAVLINK_MESSAGE_INFO_SYSTEM_TIME, MAVLINK_MESSAGE_INFO_PING, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK, MAVLINK_MESSAGE_INFO_AUTH_KEY, MAVLINK_MESSAGE_INFO_LINK_NODE_STATUS, MAVLINK_MESSAGE_INFO_SET_MODE, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_VALUE, MAVLINK_MESSAGE_INFO_PARAM_SET, MAVLINK_MESSAGE_INFO_GPS_RAW_INT, MAVLINK_MESSAGE_INFO_GPS_STATUS, MAVLINK_MESSAGE_INFO_SCALED_IMU, MAVLINK_MESSAGE_INFO_RAW_IMU, MAVLINK_MESSAGE_INFO_RAW_PRESSURE, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE, MAVLINK_MESSAGE_INFO_ATTITUDE, MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT, MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED, MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW, MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_WRITE_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_ITEM, MAVLINK_MESSAGE_INFO_MISSION_REQUEST, MAVLINK_MESSAGE_INFO_MISSION_SET_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_LIST, MAVLINK_MESSAGE_INFO_MISSION_COUNT, MAVLINK_MESSAGE_INFO_MISSION_CLEAR_ALL, MAVLINK_MESSAGE_INFO_MISSION_ITEM_REACHED, MAVLINK_MESSAGE_INFO_MISSION_ACK, MAVLINK_MESSAGE_INFO_SET_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_PARAM_MAP_RC, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_INT, MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION_COV, MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT_COV, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_COV, MAVLINK_MESSAGE_INFO_RC_CHANNELS, MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM, MAVLINK_MESSAGE_INFO_DATA_STREAM, MAVLINK_MESSAGE_INFO_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE, MAVLINK_MESSAGE_INFO_MISSION_ITEM_INT, MAVLINK_MESSAGE_INFO_VFR_HUD, MAVLINK_MESSAGE_INFO_COMMAND_INT, MAVLINK_MESSAGE_INFO_COMMAND_LONG, MAVLINK_MESSAGE_INFO_COMMAND_ACK, MAVLINK_MESSAGE_INFO_COMMAND_CANCEL, MAVLINK_MESSAGE_INFO_MANUAL_SETPOINT, MAVLINK_MESSAGE_INFO_SET_ATTITUDE_TARGET, MAVLINK_MESSAGE_INFO_ATTITUDE_TARGET, MAVLINK_MESSAGE_INFO_SET_POSITION_TARGET_LOCAL_NED, MAVLINK_MESSAGE_INFO_POSITION_TARGET_LOCAL_NED, MAVLINK_MESSAGE_INFO_SET_POSITION_TARGET_GLOBAL_INT, MAVLINK_MESSAGE_INFO_POSITION_TARGET_GLOBAL_INT, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, MAVLINK_MESSAGE_INFO_HIL_STATE, MAVLINK_MESSAGE_INFO_HIL_CONTROLS, MAVLINK_MESSAGE_INFO_HIL_RC_INPUTS_RAW, MAVLINK_MESSAGE_INFO_HIL_ACTUATOR_CONTROLS, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_GLOBAL_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE, MAVLINK_MESSAGE_INFO_VICON_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_HIGHRES_IMU, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW_RAD, MAVLINK_MESSAGE_INFO_HIL_SENSOR, MAVLINK_MESSAGE_INFO_SIM_STATE, MAVLINK_MESSAGE_INFO_RADIO_STATUS, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_PROTOCOL, MAVLINK_MESSAGE_INFO_TIMESYNC, MAVLINK_MESSAGE_INFO_CAMERA_TRIGGER, MAVLINK_MESSAGE_INFO_HIL_GPS, MAVLINK_MESSAGE_INFO_HIL_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_HIL_STATE_QUATERNION, MAVLINK_MESSAGE_INFO_SCALED_IMU2, MAVLINK_MESSAGE_INFO_LOG_REQUEST_LIST, MAVLINK_MESSAGE_INFO_LOG_ENTRY, MAVLINK_MESSAGE_INFO_LOG_REQUEST_DATA, MAVLINK_MESSAGE_INFO_LOG_DATA, MAVLINK_MESSAGE_INFO_LOG_ERASE, MAVLINK_MESSAGE_INFO_LOG_REQUEST_END, MAVLINK_MESSAGE_INFO_GPS_INJECT_DATA, MAVLINK_MESSAGE_INFO_GPS2_RAW, MAVLINK_MESSAGE_INFO_POWER_STATUS, MAVLINK_MESSAGE_INFO_SERIAL_CONTROL, MAVLINK_MESSAGE_INFO_GPS_RTK, MAVLINK_MESSAGE_INFO_GPS2_RTK, MAVLINK_MESSAGE_INFO_SCALED_IMU3, MAVLINK_MESSAGE_INFO_DATA_TRANSMISSION_HANDSHAKE, MAVLINK_MESSAGE_INFO_ENCAPSULATED_DATA, MAVLINK_MESSAGE_INFO_DISTANCE_SENSOR, MAVLINK_MESSAGE_INFO_TERRAIN_REQUEST, MAVLINK_MESSAGE_INFO_TERRAIN_DATA, MAVLINK_MESSAGE_INFO_TERRAIN_CHECK, MAVLINK_MESSAGE_INFO_TERRAIN_REPORT, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE2, MAVLINK_MESSAGE_INFO_ATT_POS_MOCAP, MAVLINK_MESSAGE_INFO_SET_ACTUATOR_CONTROL_TARGET, MAVLINK_MESSAGE_INFO_ACTUATOR_CONTROL_TARGET, MAVLINK_MESSAGE_INFO_ALTITUDE, MAVLINK_MESSAGE_INFO_RESOURCE_REQUEST, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE3, MAVLINK_MESSAGE_INFO_FOLLOW_TARGET, MAVLINK_MESSAGE_INFO_CONTROL_SYSTEM_STATE, MAVLINK_MESSAGE_INFO_BATTERY_STATUS, MAVLINK_MESSAGE_INFO_AUTOPILOT_VERSION, MAVLINK_MESSAGE_INFO_LANDING_TARGET, MAVLINK_MESSAGE_INFO_FENCE_STATUS, MAVLINK_MESSAGE_INFO_MAG_CAL_REPORT, MAVLINK_MESSAGE_INFO_EFI_STATUS, MAVLINK_MESSAGE_INFO_ESTIMATOR_STATUS, MAVLINK_MESSAGE_INFO_WIND_COV, MAVLINK_MESSAGE_INFO_GPS_INPUT, MAVLINK_MESSAGE_INFO_GPS_RTCM_DATA, MAVLINK_MESSAGE_INFO_HIGH_LATENCY, MAVLINK_MESSAGE_INFO_HIGH_LATENCY2, MAVLINK_MESSAGE_INFO_VIBRATION, MAVLINK_MESSAGE_INFO_HOME_POSITION, MAVLINK_MESSAGE_INFO_SET_HOME_POSITION, MAVLINK_MESSAGE_INFO_MESSAGE_INTERVAL, MAVLINK_MESSAGE_INFO_EXTENDED_SYS_STATE, MAVLINK_MESSAGE_INFO_ADSB_VEHICLE, MAVLINK_MESSAGE_INFO_COLLISION, MAVLINK_MESSAGE_INFO_V2_EXTENSION, MAVLINK_MESSAGE_INFO_MEMORY_VECT, MAVLINK_MESSAGE_INFO_DEBUG_VECT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT, MAVLINK_MESSAGE_INFO_STATUSTEXT, MAVLINK_MESSAGE_INFO_DEBUG, MAVLINK_MESSAGE_INFO_SETUP_SIGNING, MAVLINK_MESSAGE_INFO_BUTTON_CHANGE, MAVLINK_MESSAGE_INFO_PLAY_TUNE, MAVLINK_MESSAGE_INFO_CAMERA_INFORMATION, MAVLINK_MESSAGE_INFO_CAMERA_SETTINGS, MAVLINK_MESSAGE_INFO_STORAGE_INFORMATION, MAVLINK_MESSAGE_INFO_CAMERA_CAPTURE_STATUS, MAVLINK_MESSAGE_INFO_CAMERA_IMAGE_CAPTURED, MAVLINK_MESSAGE_INFO_FLIGHT_INFORMATION, MAVLINK_MESSAGE_INFO_MOUNT_ORIENTATION, MAVLINK_MESSAGE_INFO_LOGGING_DATA, MAVLINK_MESSAGE_INFO_LOGGING_DATA_ACKED, MAVLINK_MESSAGE_INFO_LOGGING_ACK, MAVLINK_MESSAGE_INFO_VIDEO_STREAM_INFORMATION, MAVLINK_MESSAGE_INFO_VIDEO_STREAM_STATUS, MAVLINK_MESSAGE_INFO_CAMERA_FOV_STATUS, MAVLINK_MESSAGE_INFO_CAMERA_TRACKING_IMAGE_STATUS, MAVLINK_MESSAGE_INFO_CAMERA_TRACKING_GEO_STATUS, MAVLINK_MESSAGE_INFO_CAMERA_THERMAL_RANGE, MAVLINK_MESSAGE_INFO_GIMBAL_MANAGER_INFORMATION, MAVLINK_MESSAGE_INFO_GIMBAL_MANAGER_STATUS, MAVLINK_MESSAGE_INFO_GIMBAL_MANAGER_SET_ATTITUDE, MAVLINK_MESSAGE_INFO_GIMBAL_DEVICE_INFORMATION, MAVLINK_MESSAGE_INFO_GIMBAL_DEVICE_SET_ATTITUDE, MAVLINK_MESSAGE_INFO_GIMBAL_DEVICE_ATTITUDE_STATUS, MAVLINK_MESSAGE_INFO_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE, MAVLINK_MESSAGE_INFO_GIMBAL_MANAGER_SET_PITCHYAW, MAVLINK_MESSAGE_INFO_GIMBAL_MANAGER_SET_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_ESC_INFO, MAVLINK_MESSAGE_INFO_ESC_STATUS, MAVLINK_MESSAGE_INFO_AIRSPEED, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_SENSOR, MAVLINK_MESSAGE_INFO_WIFI_CONFIG_AP, MAVLINK_MESSAGE_INFO_PROTOCOL_VERSION, MAVLINK_MESSAGE_INFO_AIS_VESSEL, MAVLINK_MESSAGE_INFO_UAVCAN_NODE_STATUS, MAVLINK_MESSAGE_INFO_UAVCAN_NODE_INFO, MAVLINK_MESSAGE_INFO_PARAM_EXT_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_EXT_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_EXT_VALUE, MAVLINK_MESSAGE_INFO_PARAM_EXT_SET, MAVLINK_MESSAGE_INFO_PARAM_EXT_ACK, MAVLINK_MESSAGE_INFO_OBSTACLE_DISTANCE, MAVLINK_MESSAGE_INFO_ODOMETRY, MAVLINK_MESSAGE_INFO_TRAJECTORY_REPRESENTATION_WAYPOINTS, MAVLINK_MESSAGE_INFO_TRAJECTORY_REPRESENTATION_BEZIER, MAVLINK_MESSAGE_INFO_CELLULAR_STATUS, MAVLINK_MESSAGE_INFO_ISBD_LINK_STATUS, MAVLINK_MESSAGE_INFO_CELLULAR_CONFIG, MAVLINK_MESSAGE_INFO_RAW_RPM, MAVLINK_MESSAGE_INFO_UTM_GLOBAL_POSITION, MAVLINK_MESSAGE_INFO_PARAM_ERROR, MAVLINK_MESSAGE_INFO_DEBUG_FLOAT_ARRAY, MAVLINK_MESSAGE_INFO_ORBIT_EXECUTION_STATUS, MAVLINK_MESSAGE_INFO_FIGURE_EIGHT_EXECUTION_STATUS, MAVLINK_MESSAGE_INFO_SMART_BATTERY_INFO, MAVLINK_MESSAGE_INFO_FUEL_STATUS, MAVLINK_MESSAGE_INFO_BATTERY_INFO, MAVLINK_MESSAGE_INFO_GENERATOR_STATUS, MAVLINK_MESSAGE_INFO_ACTUATOR_OUTPUT_STATUS, MAVLINK_MESSAGE_INFO_RELAY_STATUS, MAVLINK_MESSAGE_INFO_TIME_ESTIMATE_TO_TARGET, MAVLINK_MESSAGE_INFO_TUNNEL, MAVLINK_MESSAGE_INFO_CAN_FRAME, MAVLINK_MESSAGE_INFO_CANFD_FRAME, MAVLINK_MESSAGE_INFO_CAN_FILTER_MODIFY, MAVLINK_MESSAGE_INFO_ONBOARD_COMPUTER_STATUS, MAVLINK_MESSAGE_INFO_COMPONENT_INFORMATION, MAVLINK_MESSAGE_INFO_COMPONENT_INFORMATION_BASIC, MAVLINK_MESSAGE_INFO_COMPONENT_METADATA, MAVLINK_MESSAGE_INFO_PLAY_TUNE_V2, MAVLINK_MESSAGE_INFO_SUPPORTED_TUNES, MAVLINK_MESSAGE_INFO_EVENT, MAVLINK_MESSAGE_INFO_CURRENT_EVENT_SEQUENCE, MAVLINK_MESSAGE_INFO_REQUEST_EVENT, MAVLINK_MESSAGE_INFO_RESPONSE_EVENT_ERROR, MAVLINK_MESSAGE_INFO_AVAILABLE_MODES, MAVLINK_MESSAGE_INFO_CURRENT_MODE, MAVLINK_MESSAGE_INFO_AVAILABLE_MODES_MONITOR, MAVLINK_MESSAGE_INFO_ILLUMINATOR_STATUS, MAVLINK_MESSAGE_INFO_WHEEL_DISTANCE, MAVLINK_MESSAGE_INFO_WINCH_STATUS, MAVLINK_MESSAGE_INFO_OPEN_DRONE_ID_BASIC_ID, MAVLINK_MESSAGE_INFO_OPEN_DRONE_ID_LOCATION, MAVLINK_MESSAGE_INFO_OPEN_DRONE_ID_AUTHENTICATION, MAVLINK_MESSAGE_INFO_OPEN_DRONE_ID_SELF_ID, MAVLINK_MESSAGE_INFO_OPEN_DRONE_ID_SYSTEM, MAVLINK_MESSAGE_INFO_OPEN_DRONE_ID_OPERATOR_ID, MAVLINK_MESSAGE_INFO_OPEN_DRONE_ID_MESSAGE_PACK, MAVLINK_MESSAGE_INFO_OPEN_DRONE_ID_ARM_STATUS, MAVLINK_MESSAGE_INFO_OPEN_DRONE_ID_SYSTEM_UPDATE, MAVLINK_MESSAGE_INFO_HYGROMETER_SENSOR}
+# define MAVLINK_MESSAGE_NAMES {{ "ACTUATOR_CONTROL_TARGET", 140 }, { "ACTUATOR_OUTPUT_STATUS", 375 }, { "ADSB_VEHICLE", 246 }, { "AIRSPEED", 295 }, { "AIS_VESSEL", 301 }, { "ALTITUDE", 141 }, { "ATTITUDE", 30 }, { "ATTITUDE_QUATERNION", 31 }, { "ATTITUDE_QUATERNION_COV", 61 }, { "ATTITUDE_TARGET", 83 }, { "ATT_POS_MOCAP", 138 }, { "AUTH_KEY", 7 }, { "AUTOPILOT_STATE_FOR_GIMBAL_DEVICE", 286 }, { "AUTOPILOT_VERSION", 148 }, { "AVAILABLE_MODES", 435 }, { "AVAILABLE_MODES_MONITOR", 437 }, { "BATTERY_INFO", 372 }, { "BATTERY_STATUS", 147 }, { "BUTTON_CHANGE", 257 }, { "CAMERA_CAPTURE_STATUS", 262 }, { "CAMERA_FOV_STATUS", 271 }, { "CAMERA_IMAGE_CAPTURED", 263 }, { "CAMERA_INFORMATION", 259 }, { "CAMERA_SETTINGS", 260 }, { "CAMERA_THERMAL_RANGE", 277 }, { "CAMERA_TRACKING_GEO_STATUS", 276 }, { "CAMERA_TRACKING_IMAGE_STATUS", 275 }, { "CAMERA_TRIGGER", 112 }, { "CANFD_FRAME", 387 }, { "CAN_FILTER_MODIFY", 388 }, { "CAN_FRAME", 386 }, { "CELLULAR_CONFIG", 336 }, { "CELLULAR_STATUS", 334 }, { "CHANGE_OPERATOR_CONTROL", 5 }, { "CHANGE_OPERATOR_CONTROL_ACK", 6 }, { "COLLISION", 247 }, { "COMMAND_ACK", 77 }, { "COMMAND_CANCEL", 80 }, { "COMMAND_INT", 75 }, { "COMMAND_LONG", 76 }, { "COMPONENT_INFORMATION", 395 }, { "COMPONENT_INFORMATION_BASIC", 396 }, { "COMPONENT_METADATA", 397 }, { "CONTROL_SYSTEM_STATE", 146 }, { "CURRENT_EVENT_SEQUENCE", 411 }, { "CURRENT_MODE", 436 }, { "DATA_STREAM", 67 }, { "DATA_TRANSMISSION_HANDSHAKE", 130 }, { "DEBUG", 254 }, { "DEBUG_FLOAT_ARRAY", 350 }, { "DEBUG_VECT", 250 }, { "DISTANCE_SENSOR", 132 }, { "EFI_STATUS", 225 }, { "ENCAPSULATED_DATA", 131 }, { "ESC_INFO", 290 }, { "ESC_STATUS", 291 }, { "ESTIMATOR_STATUS", 230 }, { "EVENT", 410 }, { "EXTENDED_SYS_STATE", 245 }, { "FENCE_STATUS", 162 }, { "FIGURE_EIGHT_EXECUTION_STATUS", 361 }, { "FILE_TRANSFER_PROTOCOL", 110 }, { "FLIGHT_INFORMATION", 264 }, { "FOLLOW_TARGET", 144 }, { "FUEL_STATUS", 371 }, { "GENERATOR_STATUS", 373 }, { "GIMBAL_DEVICE_ATTITUDE_STATUS", 285 }, { "GIMBAL_DEVICE_INFORMATION", 283 }, { "GIMBAL_DEVICE_SET_ATTITUDE", 284 }, { "GIMBAL_MANAGER_INFORMATION", 280 }, { "GIMBAL_MANAGER_SET_ATTITUDE", 282 }, { "GIMBAL_MANAGER_SET_MANUAL_CONTROL", 288 }, { "GIMBAL_MANAGER_SET_PITCHYAW", 287 }, { "GIMBAL_MANAGER_STATUS", 281 }, { "GLOBAL_POSITION_INT", 33 }, { "GLOBAL_POSITION_INT_COV", 63 }, { "GLOBAL_POSITION_SENSOR", 296 }, { "GLOBAL_VISION_POSITION_ESTIMATE", 101 }, { "GPS2_RAW", 124 }, { "GPS2_RTK", 128 }, { "GPS_GLOBAL_ORIGIN", 49 }, { "GPS_INJECT_DATA", 123 }, { "GPS_INPUT", 232 }, { "GPS_RAW_INT", 24 }, { "GPS_RTCM_DATA", 233 }, { "GPS_RTK", 127 }, { "GPS_STATUS", 25 }, { "HEARTBEAT", 0 }, { "HIGHRES_IMU", 105 }, { "HIGH_LATENCY", 234 }, { "HIGH_LATENCY2", 235 }, { "HIL_ACTUATOR_CONTROLS", 93 }, { "HIL_CONTROLS", 91 }, { "HIL_GPS", 113 }, { "HIL_OPTICAL_FLOW", 114 }, { "HIL_RC_INPUTS_RAW", 92 }, { "HIL_SENSOR", 107 }, { "HIL_STATE", 90 }, { "HIL_STATE_QUATERNION", 115 }, { "HOME_POSITION", 242 }, { "HYGROMETER_SENSOR", 12920 }, { "ILLUMINATOR_STATUS", 440 }, { "ISBD_LINK_STATUS", 335 }, { "LANDING_TARGET", 149 }, { "LINK_NODE_STATUS", 8 }, { "LOCAL_POSITION_NED", 32 }, { "LOCAL_POSITION_NED_COV", 64 }, { "LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET", 89 }, { "LOGGING_ACK", 268 }, { "LOGGING_DATA", 266 }, { "LOGGING_DATA_ACKED", 267 }, { "LOG_DATA", 120 }, { "LOG_ENTRY", 118 }, { "LOG_ERASE", 121 }, { "LOG_REQUEST_DATA", 119 }, { "LOG_REQUEST_END", 122 }, { "LOG_REQUEST_LIST", 117 }, { "MAG_CAL_REPORT", 192 }, { "MANUAL_CONTROL", 69 }, { "MANUAL_SETPOINT", 81 }, { "MEMORY_VECT", 249 }, { "MESSAGE_INTERVAL", 244 }, { "MISSION_ACK", 47 }, { "MISSION_CLEAR_ALL", 45 }, { "MISSION_COUNT", 44 }, { "MISSION_CURRENT", 42 }, { "MISSION_ITEM", 39 }, { "MISSION_ITEM_INT", 73 }, { "MISSION_ITEM_REACHED", 46 }, { "MISSION_REQUEST", 40 }, { "MISSION_REQUEST_INT", 51 }, { "MISSION_REQUEST_LIST", 43 }, { "MISSION_REQUEST_PARTIAL_LIST", 37 }, { "MISSION_SET_CURRENT", 41 }, { "MISSION_WRITE_PARTIAL_LIST", 38 }, { "MOUNT_ORIENTATION", 265 }, { "NAMED_VALUE_FLOAT", 251 }, { "NAMED_VALUE_INT", 252 }, { "NAV_CONTROLLER_OUTPUT", 62 }, { "OBSTACLE_DISTANCE", 330 }, { "ODOMETRY", 331 }, { "ONBOARD_COMPUTER_STATUS", 390 }, { "OPEN_DRONE_ID_ARM_STATUS", 12918 }, { "OPEN_DRONE_ID_AUTHENTICATION", 12902 }, { "OPEN_DRONE_ID_BASIC_ID", 12900 }, { "OPEN_DRONE_ID_LOCATION", 12901 }, { "OPEN_DRONE_ID_MESSAGE_PACK", 12915 }, { "OPEN_DRONE_ID_OPERATOR_ID", 12905 }, { "OPEN_DRONE_ID_SELF_ID", 12903 }, { "OPEN_DRONE_ID_SYSTEM", 12904 }, { "OPEN_DRONE_ID_SYSTEM_UPDATE", 12919 }, { "OPTICAL_FLOW", 100 }, { "OPTICAL_FLOW_RAD", 106 }, { "ORBIT_EXECUTION_STATUS", 360 }, { "PARAM_ERROR", 345 }, { "PARAM_EXT_ACK", 324 }, { "PARAM_EXT_REQUEST_LIST", 321 }, { "PARAM_EXT_REQUEST_READ", 320 }, { "PARAM_EXT_SET", 323 }, { "PARAM_EXT_VALUE", 322 }, { "PARAM_MAP_RC", 50 }, { "PARAM_REQUEST_LIST", 21 }, { "PARAM_REQUEST_READ", 20 }, { "PARAM_SET", 23 }, { "PARAM_VALUE", 22 }, { "PING", 4 }, { "PLAY_TUNE", 258 }, { "PLAY_TUNE_V2", 400 }, { "POSITION_TARGET_GLOBAL_INT", 87 }, { "POSITION_TARGET_LOCAL_NED", 85 }, { "POWER_STATUS", 125 }, { "PROTOCOL_VERSION", 300 }, { "RADIO_STATUS", 109 }, { "RAW_IMU", 27 }, { "RAW_PRESSURE", 28 }, { "RAW_RPM", 339 }, { "RC_CHANNELS", 65 }, { "RC_CHANNELS_OVERRIDE", 70 }, { "RC_CHANNELS_RAW", 35 }, { "RC_CHANNELS_SCALED", 34 }, { "RELAY_STATUS", 376 }, { "REQUEST_DATA_STREAM", 66 }, { "REQUEST_EVENT", 412 }, { "RESOURCE_REQUEST", 142 }, { "RESPONSE_EVENT_ERROR", 413 }, { "SAFETY_ALLOWED_AREA", 55 }, { "SAFETY_SET_ALLOWED_AREA", 54 }, { "SCALED_IMU", 26 }, { "SCALED_IMU2", 116 }, { "SCALED_IMU3", 129 }, { "SCALED_PRESSURE", 29 }, { "SCALED_PRESSURE2", 137 }, { "SCALED_PRESSURE3", 143 }, { "SERIAL_CONTROL", 126 }, { "SERVO_OUTPUT_RAW", 36 }, { "SETUP_SIGNING", 256 }, { "SET_ACTUATOR_CONTROL_TARGET", 139 }, { "SET_ATTITUDE_TARGET", 82 }, { "SET_GPS_GLOBAL_ORIGIN", 48 }, { "SET_HOME_POSITION", 243 }, { "SET_MODE", 11 }, { "SET_POSITION_TARGET_GLOBAL_INT", 86 }, { "SET_POSITION_TARGET_LOCAL_NED", 84 }, { "SIM_STATE", 108 }, { "SMART_BATTERY_INFO", 370 }, { "STATUSTEXT", 253 }, { "STORAGE_INFORMATION", 261 }, { "SUPPORTED_TUNES", 401 }, { "SYSTEM_TIME", 2 }, { "SYS_STATUS", 1 }, { "TERRAIN_CHECK", 135 }, { "TERRAIN_DATA", 134 }, { "TERRAIN_REPORT", 136 }, { "TERRAIN_REQUEST", 133 }, { "TIMESYNC", 111 }, { "TIME_ESTIMATE_TO_TARGET", 380 }, { "TRAJECTORY_REPRESENTATION_BEZIER", 333 }, { "TRAJECTORY_REPRESENTATION_WAYPOINTS", 332 }, { "TUNNEL", 385 }, { "UAVCAN_NODE_INFO", 311 }, { "UAVCAN_NODE_STATUS", 310 }, { "UTM_GLOBAL_POSITION", 340 }, { "V2_EXTENSION", 248 }, { "VFR_HUD", 74 }, { "VIBRATION", 241 }, { "VICON_POSITION_ESTIMATE", 104 }, { "VIDEO_STREAM_INFORMATION", 269 }, { "VIDEO_STREAM_STATUS", 270 }, { "VISION_POSITION_ESTIMATE", 102 }, { "VISION_SPEED_ESTIMATE", 103 }, { "WHEEL_DISTANCE", 9000 }, { "WIFI_CONFIG_AP", 299 }, { "WINCH_STATUS", 9005 }, { "WIND_COV", 231 }}
# if MAVLINK_COMMAND_24BIT
# include "../mavlink_get_info.h"
# endif
diff --git a/lib/main/MAVLink/common/mavlink.h b/lib/main/MAVLink/common/mavlink.h
index c4350341463..0899ad25e5e 100755
--- a/lib/main/MAVLink/common/mavlink.h
+++ b/lib/main/MAVLink/common/mavlink.h
@@ -6,7 +6,7 @@
#ifndef MAVLINK_H
#define MAVLINK_H
-#define MAVLINK_PRIMARY_XML_HASH 1337309235272790416
+#define MAVLINK_PRIMARY_XML_HASH 8089369068283731242
#ifndef MAVLINK_STX
#define MAVLINK_STX 253
diff --git a/lib/main/MAVLink/common/mavlink_msg_adsb_vehicle.h b/lib/main/MAVLink/common/mavlink_msg_adsb_vehicle.h
index fcdb9257ed6..bf23f7929cc 100755
--- a/lib/main/MAVLink/common/mavlink_msg_adsb_vehicle.h
+++ b/lib/main/MAVLink/common/mavlink_msg_adsb_vehicle.h
@@ -8,7 +8,7 @@ typedef struct __mavlink_adsb_vehicle_t {
uint32_t ICAO_address; /*< ICAO address*/
int32_t lat; /*< [degE7] Latitude*/
int32_t lon; /*< [degE7] Longitude*/
- int32_t altitude; /*< [mm] Altitude(ASL)*/
+ int32_t altitude; /*< [mm] Altitude (ASL)*/
uint16_t heading; /*< [cdeg] Course over ground*/
uint16_t hor_velocity; /*< [cm/s] The horizontal velocity*/
int16_t ver_velocity; /*< [cm/s] The vertical velocity. Positive is up*/
@@ -17,7 +17,7 @@ typedef struct __mavlink_adsb_vehicle_t {
uint8_t altitude_type; /*< ADSB altitude type.*/
char callsign[9]; /*< The callsign, 8+null*/
uint8_t emitter_type; /*< ADSB emitter type.*/
- uint8_t tslc; /*< [s] Time since last communication in seconds*/
+ uint8_t tslc; /*< [s] Time since last communication from the remote vehicle, in seconds.*/
} mavlink_adsb_vehicle_t;
#define MAVLINK_MSG_ID_ADSB_VEHICLE_LEN 38
@@ -81,13 +81,13 @@ typedef struct __mavlink_adsb_vehicle_t {
* @param lat [degE7] Latitude
* @param lon [degE7] Longitude
* @param altitude_type ADSB altitude type.
- * @param altitude [mm] Altitude(ASL)
+ * @param altitude [mm] Altitude (ASL)
* @param heading [cdeg] Course over ground
* @param hor_velocity [cm/s] The horizontal velocity
* @param ver_velocity [cm/s] The vertical velocity. Positive is up
* @param callsign The callsign, 8+null
* @param emitter_type ADSB emitter type.
- * @param tslc [s] Time since last communication in seconds
+ * @param tslc [s] Time since last communication from the remote vehicle, in seconds.
* @param flags Bitmap to indicate various statuses including valid data fields
* @param squawk Squawk code. Note that the code is in decimal: e.g. 7700 (general emergency) is encoded as binary 0b0001_1110_0001_0100, not(!) as 0b0000_111_111_000_000
* @return length of the message in bytes (excluding serial stream start sign)
@@ -144,13 +144,13 @@ static inline uint16_t mavlink_msg_adsb_vehicle_pack(uint8_t system_id, uint8_t
* @param lat [degE7] Latitude
* @param lon [degE7] Longitude
* @param altitude_type ADSB altitude type.
- * @param altitude [mm] Altitude(ASL)
+ * @param altitude [mm] Altitude (ASL)
* @param heading [cdeg] Course over ground
* @param hor_velocity [cm/s] The horizontal velocity
* @param ver_velocity [cm/s] The vertical velocity. Positive is up
* @param callsign The callsign, 8+null
* @param emitter_type ADSB emitter type.
- * @param tslc [s] Time since last communication in seconds
+ * @param tslc [s] Time since last communication from the remote vehicle, in seconds.
* @param flags Bitmap to indicate various statuses including valid data fields
* @param squawk Squawk code. Note that the code is in decimal: e.g. 7700 (general emergency) is encoded as binary 0b0001_1110_0001_0100, not(!) as 0b0000_111_111_000_000
* @return length of the message in bytes (excluding serial stream start sign)
@@ -210,13 +210,13 @@ static inline uint16_t mavlink_msg_adsb_vehicle_pack_status(uint8_t system_id, u
* @param lat [degE7] Latitude
* @param lon [degE7] Longitude
* @param altitude_type ADSB altitude type.
- * @param altitude [mm] Altitude(ASL)
+ * @param altitude [mm] Altitude (ASL)
* @param heading [cdeg] Course over ground
* @param hor_velocity [cm/s] The horizontal velocity
* @param ver_velocity [cm/s] The vertical velocity. Positive is up
* @param callsign The callsign, 8+null
* @param emitter_type ADSB emitter type.
- * @param tslc [s] Time since last communication in seconds
+ * @param tslc [s] Time since last communication from the remote vehicle, in seconds.
* @param flags Bitmap to indicate various statuses including valid data fields
* @param squawk Squawk code. Note that the code is in decimal: e.g. 7700 (general emergency) is encoded as binary 0b0001_1110_0001_0100, not(!) as 0b0000_111_111_000_000
* @return length of the message in bytes (excluding serial stream start sign)
@@ -312,13 +312,13 @@ static inline uint16_t mavlink_msg_adsb_vehicle_encode_status(uint8_t system_id,
* @param lat [degE7] Latitude
* @param lon [degE7] Longitude
* @param altitude_type ADSB altitude type.
- * @param altitude [mm] Altitude(ASL)
+ * @param altitude [mm] Altitude (ASL)
* @param heading [cdeg] Course over ground
* @param hor_velocity [cm/s] The horizontal velocity
* @param ver_velocity [cm/s] The vertical velocity. Positive is up
* @param callsign The callsign, 8+null
* @param emitter_type ADSB emitter type.
- * @param tslc [s] Time since last communication in seconds
+ * @param tslc [s] Time since last communication from the remote vehicle, in seconds.
* @param flags Bitmap to indicate various statuses including valid data fields
* @param squawk Squawk code. Note that the code is in decimal: e.g. 7700 (general emergency) is encoded as binary 0b0001_1110_0001_0100, not(!) as 0b0000_111_111_000_000
*/
@@ -469,7 +469,7 @@ static inline uint8_t mavlink_msg_adsb_vehicle_get_altitude_type(const mavlink_m
/**
* @brief Get field altitude from adsb_vehicle message
*
- * @return [mm] Altitude(ASL)
+ * @return [mm] Altitude (ASL)
*/
static inline int32_t mavlink_msg_adsb_vehicle_get_altitude(const mavlink_message_t* msg)
{
@@ -529,7 +529,7 @@ static inline uint8_t mavlink_msg_adsb_vehicle_get_emitter_type(const mavlink_me
/**
* @brief Get field tslc from adsb_vehicle message
*
- * @return [s] Time since last communication in seconds
+ * @return [s] Time since last communication from the remote vehicle, in seconds.
*/
static inline uint8_t mavlink_msg_adsb_vehicle_get_tslc(const mavlink_message_t* msg)
{
diff --git a/lib/main/MAVLink/common/mavlink_msg_airspeed.h b/lib/main/MAVLink/common/mavlink_msg_airspeed.h
new file mode 100644
index 00000000000..2e0c2bf08ef
--- /dev/null
+++ b/lib/main/MAVLink/common/mavlink_msg_airspeed.h
@@ -0,0 +1,372 @@
+#pragma once
+// MESSAGE AIRSPEED PACKING
+
+#define MAVLINK_MSG_ID_AIRSPEED 295
+
+
+typedef struct __mavlink_airspeed_t {
+ float airspeed; /*< [m/s] Calibrated airspeed (CAS).*/
+ float raw_press; /*< [hPa] Raw differential pressure.*/
+ int16_t temperature; /*< [cdegC] Temperature.*/
+ uint8_t id; /*< Sensor ID.*/
+ uint8_t flags; /*< Airspeed sensor flags.*/
+} mavlink_airspeed_t;
+
+#define MAVLINK_MSG_ID_AIRSPEED_LEN 12
+#define MAVLINK_MSG_ID_AIRSPEED_MIN_LEN 12
+#define MAVLINK_MSG_ID_295_LEN 12
+#define MAVLINK_MSG_ID_295_MIN_LEN 12
+
+#define MAVLINK_MSG_ID_AIRSPEED_CRC 234
+#define MAVLINK_MSG_ID_295_CRC 234
+
+
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_AIRSPEED { \
+ 295, \
+ "AIRSPEED", \
+ 5, \
+ { { "id", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_airspeed_t, id) }, \
+ { "airspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_airspeed_t, airspeed) }, \
+ { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_airspeed_t, temperature) }, \
+ { "raw_press", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_airspeed_t, raw_press) }, \
+ { "flags", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_airspeed_t, flags) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_AIRSPEED { \
+ "AIRSPEED", \
+ 5, \
+ { { "id", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_airspeed_t, id) }, \
+ { "airspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_airspeed_t, airspeed) }, \
+ { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_airspeed_t, temperature) }, \
+ { "raw_press", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_airspeed_t, raw_press) }, \
+ { "flags", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_airspeed_t, flags) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a airspeed 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 id Sensor ID.
+ * @param airspeed [m/s] Calibrated airspeed (CAS).
+ * @param temperature [cdegC] Temperature.
+ * @param raw_press [hPa] Raw differential pressure.
+ * @param flags Airspeed sensor flags.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_airspeed_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint8_t id, float airspeed, int16_t temperature, float raw_press, uint8_t flags)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_AIRSPEED_LEN];
+ _mav_put_float(buf, 0, airspeed);
+ _mav_put_float(buf, 4, raw_press);
+ _mav_put_int16_t(buf, 8, temperature);
+ _mav_put_uint8_t(buf, 10, id);
+ _mav_put_uint8_t(buf, 11, flags);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AIRSPEED_LEN);
+#else
+ mavlink_airspeed_t packet;
+ packet.airspeed = airspeed;
+ packet.raw_press = raw_press;
+ packet.temperature = temperature;
+ packet.id = id;
+ packet.flags = flags;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AIRSPEED_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_AIRSPEED;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_AIRSPEED_MIN_LEN, MAVLINK_MSG_ID_AIRSPEED_LEN, MAVLINK_MSG_ID_AIRSPEED_CRC);
+}
+
+/**
+ * @brief Pack a airspeed 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 id Sensor ID.
+ * @param airspeed [m/s] Calibrated airspeed (CAS).
+ * @param temperature [cdegC] Temperature.
+ * @param raw_press [hPa] Raw differential pressure.
+ * @param flags Airspeed sensor flags.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_airspeed_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ uint8_t id, float airspeed, int16_t temperature, float raw_press, uint8_t flags)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_AIRSPEED_LEN];
+ _mav_put_float(buf, 0, airspeed);
+ _mav_put_float(buf, 4, raw_press);
+ _mav_put_int16_t(buf, 8, temperature);
+ _mav_put_uint8_t(buf, 10, id);
+ _mav_put_uint8_t(buf, 11, flags);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AIRSPEED_LEN);
+#else
+ mavlink_airspeed_t packet;
+ packet.airspeed = airspeed;
+ packet.raw_press = raw_press;
+ packet.temperature = temperature;
+ packet.id = id;
+ packet.flags = flags;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AIRSPEED_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_AIRSPEED;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_AIRSPEED_MIN_LEN, MAVLINK_MSG_ID_AIRSPEED_LEN, MAVLINK_MSG_ID_AIRSPEED_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_AIRSPEED_MIN_LEN, MAVLINK_MSG_ID_AIRSPEED_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a airspeed 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 id Sensor ID.
+ * @param airspeed [m/s] Calibrated airspeed (CAS).
+ * @param temperature [cdegC] Temperature.
+ * @param raw_press [hPa] Raw differential pressure.
+ * @param flags Airspeed sensor flags.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_airspeed_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint8_t id,float airspeed,int16_t temperature,float raw_press,uint8_t flags)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_AIRSPEED_LEN];
+ _mav_put_float(buf, 0, airspeed);
+ _mav_put_float(buf, 4, raw_press);
+ _mav_put_int16_t(buf, 8, temperature);
+ _mav_put_uint8_t(buf, 10, id);
+ _mav_put_uint8_t(buf, 11, flags);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AIRSPEED_LEN);
+#else
+ mavlink_airspeed_t packet;
+ packet.airspeed = airspeed;
+ packet.raw_press = raw_press;
+ packet.temperature = temperature;
+ packet.id = id;
+ packet.flags = flags;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AIRSPEED_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_AIRSPEED;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_AIRSPEED_MIN_LEN, MAVLINK_MSG_ID_AIRSPEED_LEN, MAVLINK_MSG_ID_AIRSPEED_CRC);
+}
+
+/**
+ * @brief Encode a airspeed 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 airspeed C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_airspeed_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_airspeed_t* airspeed)
+{
+ return mavlink_msg_airspeed_pack(system_id, component_id, msg, airspeed->id, airspeed->airspeed, airspeed->temperature, airspeed->raw_press, airspeed->flags);
+}
+
+/**
+ * @brief Encode a airspeed 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 airspeed C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_airspeed_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_airspeed_t* airspeed)
+{
+ return mavlink_msg_airspeed_pack_chan(system_id, component_id, chan, msg, airspeed->id, airspeed->airspeed, airspeed->temperature, airspeed->raw_press, airspeed->flags);
+}
+
+/**
+ * @brief Encode a airspeed 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 airspeed C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_airspeed_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_airspeed_t* airspeed)
+{
+ return mavlink_msg_airspeed_pack_status(system_id, component_id, _status, msg, airspeed->id, airspeed->airspeed, airspeed->temperature, airspeed->raw_press, airspeed->flags);
+}
+
+/**
+ * @brief Send a airspeed message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param id Sensor ID.
+ * @param airspeed [m/s] Calibrated airspeed (CAS).
+ * @param temperature [cdegC] Temperature.
+ * @param raw_press [hPa] Raw differential pressure.
+ * @param flags Airspeed sensor flags.
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_airspeed_send(mavlink_channel_t chan, uint8_t id, float airspeed, int16_t temperature, float raw_press, uint8_t flags)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_AIRSPEED_LEN];
+ _mav_put_float(buf, 0, airspeed);
+ _mav_put_float(buf, 4, raw_press);
+ _mav_put_int16_t(buf, 8, temperature);
+ _mav_put_uint8_t(buf, 10, id);
+ _mav_put_uint8_t(buf, 11, flags);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AIRSPEED, buf, MAVLINK_MSG_ID_AIRSPEED_MIN_LEN, MAVLINK_MSG_ID_AIRSPEED_LEN, MAVLINK_MSG_ID_AIRSPEED_CRC);
+#else
+ mavlink_airspeed_t packet;
+ packet.airspeed = airspeed;
+ packet.raw_press = raw_press;
+ packet.temperature = temperature;
+ packet.id = id;
+ packet.flags = flags;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AIRSPEED, (const char *)&packet, MAVLINK_MSG_ID_AIRSPEED_MIN_LEN, MAVLINK_MSG_ID_AIRSPEED_LEN, MAVLINK_MSG_ID_AIRSPEED_CRC);
+#endif
+}
+
+/**
+ * @brief Send a airspeed message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_airspeed_send_struct(mavlink_channel_t chan, const mavlink_airspeed_t* airspeed)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_airspeed_send(chan, airspeed->id, airspeed->airspeed, airspeed->temperature, airspeed->raw_press, airspeed->flags);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AIRSPEED, (const char *)airspeed, MAVLINK_MSG_ID_AIRSPEED_MIN_LEN, MAVLINK_MSG_ID_AIRSPEED_LEN, MAVLINK_MSG_ID_AIRSPEED_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_AIRSPEED_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_airspeed_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t id, float airspeed, int16_t temperature, float raw_press, uint8_t flags)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_float(buf, 0, airspeed);
+ _mav_put_float(buf, 4, raw_press);
+ _mav_put_int16_t(buf, 8, temperature);
+ _mav_put_uint8_t(buf, 10, id);
+ _mav_put_uint8_t(buf, 11, flags);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AIRSPEED, buf, MAVLINK_MSG_ID_AIRSPEED_MIN_LEN, MAVLINK_MSG_ID_AIRSPEED_LEN, MAVLINK_MSG_ID_AIRSPEED_CRC);
+#else
+ mavlink_airspeed_t *packet = (mavlink_airspeed_t *)msgbuf;
+ packet->airspeed = airspeed;
+ packet->raw_press = raw_press;
+ packet->temperature = temperature;
+ packet->id = id;
+ packet->flags = flags;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AIRSPEED, (const char *)packet, MAVLINK_MSG_ID_AIRSPEED_MIN_LEN, MAVLINK_MSG_ID_AIRSPEED_LEN, MAVLINK_MSG_ID_AIRSPEED_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE AIRSPEED UNPACKING
+
+
+/**
+ * @brief Get field id from airspeed message
+ *
+ * @return Sensor ID.
+ */
+static inline uint8_t mavlink_msg_airspeed_get_id(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 10);
+}
+
+/**
+ * @brief Get field airspeed from airspeed message
+ *
+ * @return [m/s] Calibrated airspeed (CAS).
+ */
+static inline float mavlink_msg_airspeed_get_airspeed(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 0);
+}
+
+/**
+ * @brief Get field temperature from airspeed message
+ *
+ * @return [cdegC] Temperature.
+ */
+static inline int16_t mavlink_msg_airspeed_get_temperature(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_int16_t(msg, 8);
+}
+
+/**
+ * @brief Get field raw_press from airspeed message
+ *
+ * @return [hPa] Raw differential pressure.
+ */
+static inline float mavlink_msg_airspeed_get_raw_press(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 4);
+}
+
+/**
+ * @brief Get field flags from airspeed message
+ *
+ * @return Airspeed sensor flags.
+ */
+static inline uint8_t mavlink_msg_airspeed_get_flags(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 11);
+}
+
+/**
+ * @brief Decode a airspeed message into a struct
+ *
+ * @param msg The message to decode
+ * @param airspeed C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_airspeed_decode(const mavlink_message_t* msg, mavlink_airspeed_t* airspeed)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ airspeed->airspeed = mavlink_msg_airspeed_get_airspeed(msg);
+ airspeed->raw_press = mavlink_msg_airspeed_get_raw_press(msg);
+ airspeed->temperature = mavlink_msg_airspeed_get_temperature(msg);
+ airspeed->id = mavlink_msg_airspeed_get_id(msg);
+ airspeed->flags = mavlink_msg_airspeed_get_flags(msg);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_AIRSPEED_LEN? msg->len : MAVLINK_MSG_ID_AIRSPEED_LEN;
+ memset(airspeed, 0, MAVLINK_MSG_ID_AIRSPEED_LEN);
+ memcpy(airspeed, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/common/mavlink_msg_ais_vessel.h b/lib/main/MAVLink/common/mavlink_msg_ais_vessel.h
index 1fd7e6091a7..fdd0effed59 100644
--- a/lib/main/MAVLink/common/mavlink_msg_ais_vessel.h
+++ b/lib/main/MAVLink/common/mavlink_msg_ais_vessel.h
@@ -13,15 +13,15 @@ typedef struct __mavlink_ais_vessel_t {
uint16_t velocity; /*< [cm/s] Speed over ground*/
uint16_t dimension_bow; /*< [m] Distance from lat/lon location to bow*/
uint16_t dimension_stern; /*< [m] Distance from lat/lon location to stern*/
- uint16_t tslc; /*< [s] Time since last communication in seconds*/
+ uint16_t tslc; /*< [s] Time since last communication from the vessel, in seconds*/
uint16_t flags; /*< Bitmask to indicate various statuses including valid data fields*/
int8_t turn_rate; /*< [ddeg/s] Turn rate, 0.1 degrees per second*/
uint8_t navigational_status; /*< Navigational status*/
uint8_t type; /*< Type of vessels*/
uint8_t dimension_port; /*< [m] Distance from lat/lon location to port side*/
uint8_t dimension_starboard; /*< [m] Distance from lat/lon location to starboard side*/
- char callsign[7]; /*< The vessel callsign*/
- char name[20]; /*< The vessel name*/
+ char callsign[7]; /*< The vessel callsign. Characters are encoded as 7-bit ASCII, but only characters in the [AIS 6-bit ASCII subset](https://en.wikipedia.org/wiki/Six-bit_character_code#AIS_SixBit_ASCII) are permitted. Also set AIS_FLAGS_VALID_CALLSIGN if valid. The string is NULL-terminated if it is shorter than the array length.*/
+ char name[20]; /*< The vessel name. Characters are encoded as 7-bit ASCII, but only characters in the [AIS 6-bit ASCII subset](https://en.wikipedia.org/wiki/Six-bit_character_code#AIS_SixBit_ASCII) are permitted. Also set AIS_FLAGS_VALID_NAME if valid. The string is NULL-terminated if it is shorter than the array length.*/
} mavlink_ais_vessel_t;
#define MAVLINK_MSG_ID_AIS_VESSEL_LEN 58
@@ -103,9 +103,9 @@ typedef struct __mavlink_ais_vessel_t {
* @param dimension_stern [m] Distance from lat/lon location to stern
* @param dimension_port [m] Distance from lat/lon location to port side
* @param dimension_starboard [m] Distance from lat/lon location to starboard side
- * @param callsign The vessel callsign
- * @param name The vessel name
- * @param tslc [s] Time since last communication in seconds
+ * @param callsign The vessel callsign. Characters are encoded as 7-bit ASCII, but only characters in the [AIS 6-bit ASCII subset](https://en.wikipedia.org/wiki/Six-bit_character_code#AIS_SixBit_ASCII) are permitted. Also set AIS_FLAGS_VALID_CALLSIGN if valid. The string is NULL-terminated if it is shorter than the array length.
+ * @param name The vessel name. Characters are encoded as 7-bit ASCII, but only characters in the [AIS 6-bit ASCII subset](https://en.wikipedia.org/wiki/Six-bit_character_code#AIS_SixBit_ASCII) are permitted. Also set AIS_FLAGS_VALID_NAME if valid. The string is NULL-terminated if it is shorter than the array length.
+ * @param tslc [s] Time since last communication from the vessel, in seconds
* @param flags Bitmask to indicate various statuses including valid data fields
* @return length of the message in bytes (excluding serial stream start sign)
*/
@@ -178,9 +178,9 @@ static inline uint16_t mavlink_msg_ais_vessel_pack(uint8_t system_id, uint8_t co
* @param dimension_stern [m] Distance from lat/lon location to stern
* @param dimension_port [m] Distance from lat/lon location to port side
* @param dimension_starboard [m] Distance from lat/lon location to starboard side
- * @param callsign The vessel callsign
- * @param name The vessel name
- * @param tslc [s] Time since last communication in seconds
+ * @param callsign The vessel callsign. Characters are encoded as 7-bit ASCII, but only characters in the [AIS 6-bit ASCII subset](https://en.wikipedia.org/wiki/Six-bit_character_code#AIS_SixBit_ASCII) are permitted. Also set AIS_FLAGS_VALID_CALLSIGN if valid. The string is NULL-terminated if it is shorter than the array length.
+ * @param name The vessel name. Characters are encoded as 7-bit ASCII, but only characters in the [AIS 6-bit ASCII subset](https://en.wikipedia.org/wiki/Six-bit_character_code#AIS_SixBit_ASCII) are permitted. Also set AIS_FLAGS_VALID_NAME if valid. The string is NULL-terminated if it is shorter than the array length.
+ * @param tslc [s] Time since last communication from the vessel, in seconds
* @param flags Bitmask to indicate various statuses including valid data fields
* @return length of the message in bytes (excluding serial stream start sign)
*/
@@ -256,9 +256,9 @@ static inline uint16_t mavlink_msg_ais_vessel_pack_status(uint8_t system_id, uin
* @param dimension_stern [m] Distance from lat/lon location to stern
* @param dimension_port [m] Distance from lat/lon location to port side
* @param dimension_starboard [m] Distance from lat/lon location to starboard side
- * @param callsign The vessel callsign
- * @param name The vessel name
- * @param tslc [s] Time since last communication in seconds
+ * @param callsign The vessel callsign. Characters are encoded as 7-bit ASCII, but only characters in the [AIS 6-bit ASCII subset](https://en.wikipedia.org/wiki/Six-bit_character_code#AIS_SixBit_ASCII) are permitted. Also set AIS_FLAGS_VALID_CALLSIGN if valid. The string is NULL-terminated if it is shorter than the array length.
+ * @param name The vessel name. Characters are encoded as 7-bit ASCII, but only characters in the [AIS 6-bit ASCII subset](https://en.wikipedia.org/wiki/Six-bit_character_code#AIS_SixBit_ASCII) are permitted. Also set AIS_FLAGS_VALID_NAME if valid. The string is NULL-terminated if it is shorter than the array length.
+ * @param tslc [s] Time since last communication from the vessel, in seconds
* @param flags Bitmask to indicate various statuses including valid data fields
* @return length of the message in bytes (excluding serial stream start sign)
*/
@@ -370,9 +370,9 @@ static inline uint16_t mavlink_msg_ais_vessel_encode_status(uint8_t system_id, u
* @param dimension_stern [m] Distance from lat/lon location to stern
* @param dimension_port [m] Distance from lat/lon location to port side
* @param dimension_starboard [m] Distance from lat/lon location to starboard side
- * @param callsign The vessel callsign
- * @param name The vessel name
- * @param tslc [s] Time since last communication in seconds
+ * @param callsign The vessel callsign. Characters are encoded as 7-bit ASCII, but only characters in the [AIS 6-bit ASCII subset](https://en.wikipedia.org/wiki/Six-bit_character_code#AIS_SixBit_ASCII) are permitted. Also set AIS_FLAGS_VALID_CALLSIGN if valid. The string is NULL-terminated if it is shorter than the array length.
+ * @param name The vessel name. Characters are encoded as 7-bit ASCII, but only characters in the [AIS 6-bit ASCII subset](https://en.wikipedia.org/wiki/Six-bit_character_code#AIS_SixBit_ASCII) are permitted. Also set AIS_FLAGS_VALID_NAME if valid. The string is NULL-terminated if it is shorter than the array length.
+ * @param tslc [s] Time since last communication from the vessel, in seconds
* @param flags Bitmask to indicate various statuses including valid data fields
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
@@ -628,7 +628,7 @@ static inline uint8_t mavlink_msg_ais_vessel_get_dimension_starboard(const mavli
/**
* @brief Get field callsign from ais_vessel message
*
- * @return The vessel callsign
+ * @return The vessel callsign. Characters are encoded as 7-bit ASCII, but only characters in the [AIS 6-bit ASCII subset](https://en.wikipedia.org/wiki/Six-bit_character_code#AIS_SixBit_ASCII) are permitted. Also set AIS_FLAGS_VALID_CALLSIGN if valid. The string is NULL-terminated if it is shorter than the array length.
*/
static inline uint16_t mavlink_msg_ais_vessel_get_callsign(const mavlink_message_t* msg, char *callsign)
{
@@ -638,7 +638,7 @@ static inline uint16_t mavlink_msg_ais_vessel_get_callsign(const mavlink_message
/**
* @brief Get field name from ais_vessel message
*
- * @return The vessel name
+ * @return The vessel name. Characters are encoded as 7-bit ASCII, but only characters in the [AIS 6-bit ASCII subset](https://en.wikipedia.org/wiki/Six-bit_character_code#AIS_SixBit_ASCII) are permitted. Also set AIS_FLAGS_VALID_NAME if valid. The string is NULL-terminated if it is shorter than the array length.
*/
static inline uint16_t mavlink_msg_ais_vessel_get_name(const mavlink_message_t* msg, char *name)
{
@@ -648,7 +648,7 @@ static inline uint16_t mavlink_msg_ais_vessel_get_name(const mavlink_message_t*
/**
* @brief Get field tslc from ais_vessel message
*
- * @return [s] Time since last communication in seconds
+ * @return [s] Time since last communication from the vessel, in seconds
*/
static inline uint16_t mavlink_msg_ais_vessel_get_tslc(const mavlink_message_t* msg)
{
diff --git a/lib/main/MAVLink/common/mavlink_msg_attitude_target.h b/lib/main/MAVLink/common/mavlink_msg_attitude_target.h
index 89de26e1f77..4068f1a36d1 100755
--- a/lib/main/MAVLink/common/mavlink_msg_attitude_target.h
+++ b/lib/main/MAVLink/common/mavlink_msg_attitude_target.h
@@ -10,7 +10,7 @@ typedef struct __mavlink_attitude_target_t {
float body_roll_rate; /*< [rad/s] Body roll rate*/
float body_pitch_rate; /*< [rad/s] Body pitch rate*/
float body_yaw_rate; /*< [rad/s] Body yaw rate*/
- float thrust; /*< Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust)*/
+ float thrust; /*< Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse thrust)*/
uint8_t type_mask; /*< Bitmap to indicate which dimensions should be ignored by the vehicle.*/
} mavlink_attitude_target_t;
@@ -65,7 +65,7 @@ typedef struct __mavlink_attitude_target_t {
* @param body_roll_rate [rad/s] Body roll rate
* @param body_pitch_rate [rad/s] Body pitch rate
* @param body_yaw_rate [rad/s] Body yaw rate
- * @param thrust Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust)
+ * @param thrust Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse thrust)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_attitude_target_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
@@ -110,7 +110,7 @@ static inline uint16_t mavlink_msg_attitude_target_pack(uint8_t system_id, uint8
* @param body_roll_rate [rad/s] Body roll rate
* @param body_pitch_rate [rad/s] Body pitch rate
* @param body_yaw_rate [rad/s] Body yaw rate
- * @param thrust Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust)
+ * @param thrust Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse thrust)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_attitude_target_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_attitude_target_pack_status(uint8_t system_id
* @param body_roll_rate [rad/s] Body roll rate
* @param body_pitch_rate [rad/s] Body pitch rate
* @param body_yaw_rate [rad/s] Body yaw rate
- * @param thrust Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust)
+ * @param thrust Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse thrust)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_attitude_target_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
@@ -242,7 +242,7 @@ static inline uint16_t mavlink_msg_attitude_target_encode_status(uint8_t system_
* @param body_roll_rate [rad/s] Body roll rate
* @param body_pitch_rate [rad/s] Body pitch rate
* @param body_yaw_rate [rad/s] Body yaw rate
- * @param thrust Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust)
+ * @param thrust Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse thrust)
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
@@ -387,7 +387,7 @@ static inline float mavlink_msg_attitude_target_get_body_yaw_rate(const mavlink_
/**
* @brief Get field thrust from attitude_target message
*
- * @return Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust)
+ * @return Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse thrust)
*/
static inline float mavlink_msg_attitude_target_get_thrust(const mavlink_message_t* msg)
{
diff --git a/lib/main/MAVLink/common/mavlink_msg_camera_information.h b/lib/main/MAVLink/common/mavlink_msg_camera_information.h
index bc876acf18b..30bebcfce0e 100644
--- a/lib/main/MAVLink/common/mavlink_msg_camera_information.h
+++ b/lib/main/MAVLink/common/mavlink_msg_camera_information.h
@@ -6,7 +6,7 @@
typedef struct __mavlink_camera_information_t {
uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/
- uint32_t firmware_version; /*< Version of the camera firmware, encoded as: `(Dev & 0xff) << 24 \| (Patch & 0xff) << 16 \| (Minor & 0xff) << 8 \| (Major & 0xff)`. Use 0 if not known.*/
+ uint32_t firmware_version; /*< Version of the camera firmware, encoded as: `(Dev & 0xff) << 24 + (Patch & 0xff) << 16 + (Minor & 0xff) << 8 + (Major & 0xff)`. Use 0 if not known.*/
float focal_length; /*< [mm] Focal length. Use NaN if not known.*/
float sensor_size_h; /*< [mm] Image sensor size horizontal. Use NaN if not known.*/
float sensor_size_v; /*< [mm] Image sensor size vertical. Use NaN if not known.*/
@@ -88,7 +88,7 @@ typedef struct __mavlink_camera_information_t {
* @param time_boot_ms [ms] Timestamp (time since system boot).
* @param vendor_name Name of the camera vendor
* @param model_name Name of the camera model
- * @param firmware_version Version of the camera firmware, encoded as: `(Dev & 0xff) << 24 \| (Patch & 0xff) << 16 \| (Minor & 0xff) << 8 \| (Major & 0xff)`. Use 0 if not known.
+ * @param firmware_version Version of the camera firmware, encoded as: `(Dev & 0xff) << 24 + (Patch & 0xff) << 16 + (Minor & 0xff) << 8 + (Major & 0xff)`. Use 0 if not known.
* @param focal_length [mm] Focal length. Use NaN if not known.
* @param sensor_size_h [mm] Image sensor size horizontal. Use NaN if not known.
* @param sensor_size_v [mm] Image sensor size vertical. Use NaN if not known.
@@ -157,7 +157,7 @@ static inline uint16_t mavlink_msg_camera_information_pack(uint8_t system_id, ui
* @param time_boot_ms [ms] Timestamp (time since system boot).
* @param vendor_name Name of the camera vendor
* @param model_name Name of the camera model
- * @param firmware_version Version of the camera firmware, encoded as: `(Dev & 0xff) << 24 \| (Patch & 0xff) << 16 \| (Minor & 0xff) << 8 \| (Major & 0xff)`. Use 0 if not known.
+ * @param firmware_version Version of the camera firmware, encoded as: `(Dev & 0xff) << 24 + (Patch & 0xff) << 16 + (Minor & 0xff) << 8 + (Major & 0xff)`. Use 0 if not known.
* @param focal_length [mm] Focal length. Use NaN if not known.
* @param sensor_size_h [mm] Image sensor size horizontal. Use NaN if not known.
* @param sensor_size_v [mm] Image sensor size vertical. Use NaN if not known.
@@ -229,7 +229,7 @@ static inline uint16_t mavlink_msg_camera_information_pack_status(uint8_t system
* @param time_boot_ms [ms] Timestamp (time since system boot).
* @param vendor_name Name of the camera vendor
* @param model_name Name of the camera model
- * @param firmware_version Version of the camera firmware, encoded as: `(Dev & 0xff) << 24 \| (Patch & 0xff) << 16 \| (Minor & 0xff) << 8 \| (Major & 0xff)`. Use 0 if not known.
+ * @param firmware_version Version of the camera firmware, encoded as: `(Dev & 0xff) << 24 + (Patch & 0xff) << 16 + (Minor & 0xff) << 8 + (Major & 0xff)`. Use 0 if not known.
* @param focal_length [mm] Focal length. Use NaN if not known.
* @param sensor_size_h [mm] Image sensor size horizontal. Use NaN if not known.
* @param sensor_size_v [mm] Image sensor size vertical. Use NaN if not known.
@@ -337,7 +337,7 @@ static inline uint16_t mavlink_msg_camera_information_encode_status(uint8_t syst
* @param time_boot_ms [ms] Timestamp (time since system boot).
* @param vendor_name Name of the camera vendor
* @param model_name Name of the camera model
- * @param firmware_version Version of the camera firmware, encoded as: `(Dev & 0xff) << 24 \| (Patch & 0xff) << 16 \| (Minor & 0xff) << 8 \| (Major & 0xff)`. Use 0 if not known.
+ * @param firmware_version Version of the camera firmware, encoded as: `(Dev & 0xff) << 24 + (Patch & 0xff) << 16 + (Minor & 0xff) << 8 + (Major & 0xff)`. Use 0 if not known.
* @param focal_length [mm] Focal length. Use NaN if not known.
* @param sensor_size_h [mm] Image sensor size horizontal. Use NaN if not known.
* @param sensor_size_v [mm] Image sensor size vertical. Use NaN if not known.
@@ -495,7 +495,7 @@ static inline uint16_t mavlink_msg_camera_information_get_model_name(const mavli
/**
* @brief Get field firmware_version from camera_information message
*
- * @return Version of the camera firmware, encoded as: `(Dev & 0xff) << 24 \| (Patch & 0xff) << 16 \| (Minor & 0xff) << 8 \| (Major & 0xff)`. Use 0 if not known.
+ * @return Version of the camera firmware, encoded as: `(Dev & 0xff) << 24 + (Patch & 0xff) << 16 + (Minor & 0xff) << 8 + (Major & 0xff)`. Use 0 if not known.
*/
static inline uint32_t mavlink_msg_camera_information_get_firmware_version(const mavlink_message_t* msg)
{
diff --git a/lib/main/MAVLink/common/mavlink_msg_change_operator_control.h b/lib/main/MAVLink/common/mavlink_msg_change_operator_control.h
index 1391cde0415..9923375e00b 100755
--- a/lib/main/MAVLink/common/mavlink_msg_change_operator_control.h
+++ b/lib/main/MAVLink/common/mavlink_msg_change_operator_control.h
@@ -7,7 +7,7 @@
typedef struct __mavlink_change_operator_control_t {
uint8_t target_system; /*< System the GCS requests control for*/
uint8_t control_request; /*< 0: request control of this MAV, 1: Release control of this MAV*/
- uint8_t version; /*< [rad] 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch.*/
+ uint8_t version; /*< 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch.*/
char passkey[25]; /*< Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-"*/
} mavlink_change_operator_control_t;
@@ -52,7 +52,7 @@ typedef struct __mavlink_change_operator_control_t {
*
* @param target_system System the GCS requests control for
* @param control_request 0: request control of this MAV, 1: Release control of this MAV
- * @param version [rad] 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch.
+ * @param version 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch.
* @param passkey Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-"
* @return length of the message in bytes (excluding serial stream start sign)
*/
@@ -88,7 +88,7 @@ static inline uint16_t mavlink_msg_change_operator_control_pack(uint8_t system_i
*
* @param target_system System the GCS requests control for
* @param control_request 0: request control of this MAV, 1: Release control of this MAV
- * @param version [rad] 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch.
+ * @param version 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch.
* @param passkey Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-"
* @return length of the message in bytes (excluding serial stream start sign)
*/
@@ -127,7 +127,7 @@ static inline uint16_t mavlink_msg_change_operator_control_pack_status(uint8_t s
* @param msg The MAVLink message to compress the data into
* @param target_system System the GCS requests control for
* @param control_request 0: request control of this MAV, 1: Release control of this MAV
- * @param version [rad] 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch.
+ * @param version 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch.
* @param passkey Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-"
* @return length of the message in bytes (excluding serial stream start sign)
*/
@@ -202,7 +202,7 @@ static inline uint16_t mavlink_msg_change_operator_control_encode_status(uint8_t
*
* @param target_system System the GCS requests control for
* @param control_request 0: request control of this MAV, 1: Release control of this MAV
- * @param version [rad] 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch.
+ * @param version 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch.
* @param passkey Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-"
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
@@ -296,7 +296,7 @@ static inline uint8_t mavlink_msg_change_operator_control_get_control_request(co
/**
* @brief Get field version from change_operator_control message
*
- * @return [rad] 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch.
+ * @return 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch.
*/
static inline uint8_t mavlink_msg_change_operator_control_get_version(const mavlink_message_t* msg)
{
diff --git a/lib/main/MAVLink/common/mavlink_msg_data_stream.h b/lib/main/MAVLink/common/mavlink_msg_data_stream.h
index 9436e645cd2..ee6b7a7d9ac 100755
--- a/lib/main/MAVLink/common/mavlink_msg_data_stream.h
+++ b/lib/main/MAVLink/common/mavlink_msg_data_stream.h
@@ -6,7 +6,7 @@
typedef struct __mavlink_data_stream_t {
uint16_t message_rate; /*< [Hz] The message rate*/
- uint8_t stream_id; /*< The ID of the requested data stream*/
+ uint8_t stream_id; /*< The ID of the requested data stream.*/
uint8_t on_off; /*< 1 stream is enabled, 0 stream is stopped.*/
} mavlink_data_stream_t;
@@ -47,7 +47,7 @@ typedef struct __mavlink_data_stream_t {
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
- * @param stream_id The ID of the requested data stream
+ * @param stream_id The ID of the requested data stream.
* @param message_rate [Hz] The message rate
* @param on_off 1 stream is enabled, 0 stream is stopped.
* @return length of the message in bytes (excluding serial stream start sign)
@@ -82,7 +82,7 @@ static inline uint16_t mavlink_msg_data_stream_pack(uint8_t system_id, uint8_t c
* @param status MAVLink status structure
* @param msg The MAVLink message to compress the data into
*
- * @param stream_id The ID of the requested data stream
+ * @param stream_id The ID of the requested data stream.
* @param message_rate [Hz] The message rate
* @param on_off 1 stream is enabled, 0 stream is stopped.
* @return length of the message in bytes (excluding serial stream start sign)
@@ -120,7 +120,7 @@ static inline uint16_t mavlink_msg_data_stream_pack_status(uint8_t system_id, ui
* @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 stream_id The ID of the requested data stream
+ * @param stream_id The ID of the requested data stream.
* @param message_rate [Hz] The message rate
* @param on_off 1 stream is enabled, 0 stream is stopped.
* @return length of the message in bytes (excluding serial stream start sign)
@@ -194,7 +194,7 @@ static inline uint16_t mavlink_msg_data_stream_encode_status(uint8_t system_id,
* @brief Send a data_stream message
* @param chan MAVLink channel to send the message
*
- * @param stream_id The ID of the requested data stream
+ * @param stream_id The ID of the requested data stream.
* @param message_rate [Hz] The message rate
* @param on_off 1 stream is enabled, 0 stream is stopped.
*/
@@ -269,7 +269,7 @@ static inline void mavlink_msg_data_stream_send_buf(mavlink_message_t *msgbuf, m
/**
* @brief Get field stream_id from data_stream message
*
- * @return The ID of the requested data stream
+ * @return The ID of the requested data stream.
*/
static inline uint8_t mavlink_msg_data_stream_get_stream_id(const mavlink_message_t* msg)
{
diff --git a/lib/main/MAVLink/common/mavlink_msg_esc_info.h b/lib/main/MAVLink/common/mavlink_msg_esc_info.h
index 463e46abb4b..cc65e73dbc4 100644
--- a/lib/main/MAVLink/common/mavlink_msg_esc_info.h
+++ b/lib/main/MAVLink/common/mavlink_msg_esc_info.h
@@ -10,7 +10,7 @@ typedef struct __mavlink_esc_info_t {
uint16_t counter; /*< Counter of data packets received.*/
uint16_t failure_flags[4]; /*< Bitmap of ESC failure flags.*/
int16_t temperature[4]; /*< [cdegC] Temperature of each ESC. INT16_MAX: if data not supplied by ESC.*/
- uint8_t index; /*< Index of the first ESC in this message. minValue = 0, maxValue = 60, increment = 4.*/
+ uint8_t index; /*< Index of the first ESC in this message (ESC are indexed in motor order). minValue = 0, maxValue = 60, increment = 4.*/
uint8_t count; /*< Total number of ESCs in all messages of this type. Message fields with an index higher than this should be ignored because they contain invalid data.*/
uint8_t connection_type; /*< Connection type protocol for all ESC.*/
uint8_t info; /*< Information regarding online/offline status of each ESC.*/
@@ -67,7 +67,7 @@ typedef struct __mavlink_esc_info_t {
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
- * @param index Index of the first ESC in this message. minValue = 0, maxValue = 60, increment = 4.
+ * @param index Index of the first ESC in this message (ESC are indexed in motor order). minValue = 0, maxValue = 60, increment = 4.
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude the number.
* @param counter Counter of data packets received.
* @param count Total number of ESCs in all messages of this type. Message fields with an index higher than this should be ignored because they contain invalid data.
@@ -118,7 +118,7 @@ static inline uint16_t mavlink_msg_esc_info_pack(uint8_t system_id, uint8_t comp
* @param status MAVLink status structure
* @param msg The MAVLink message to compress the data into
*
- * @param index Index of the first ESC in this message. minValue = 0, maxValue = 60, increment = 4.
+ * @param index Index of the first ESC in this message (ESC are indexed in motor order). minValue = 0, maxValue = 60, increment = 4.
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude the number.
* @param counter Counter of data packets received.
* @param count Total number of ESCs in all messages of this type. Message fields with an index higher than this should be ignored because they contain invalid data.
@@ -172,7 +172,7 @@ static inline uint16_t mavlink_msg_esc_info_pack_status(uint8_t system_id, uint8
* @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 index Index of the first ESC in this message. minValue = 0, maxValue = 60, increment = 4.
+ * @param index Index of the first ESC in this message (ESC are indexed in motor order). minValue = 0, maxValue = 60, increment = 4.
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude the number.
* @param counter Counter of data packets received.
* @param count Total number of ESCs in all messages of this type. Message fields with an index higher than this should be ignored because they contain invalid data.
@@ -262,7 +262,7 @@ static inline uint16_t mavlink_msg_esc_info_encode_status(uint8_t system_id, uin
* @brief Send a esc_info message
* @param chan MAVLink channel to send the message
*
- * @param index Index of the first ESC in this message. minValue = 0, maxValue = 60, increment = 4.
+ * @param index Index of the first ESC in this message (ESC are indexed in motor order). minValue = 0, maxValue = 60, increment = 4.
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude the number.
* @param counter Counter of data packets received.
* @param count Total number of ESCs in all messages of this type. Message fields with an index higher than this should be ignored because they contain invalid data.
@@ -363,7 +363,7 @@ static inline void mavlink_msg_esc_info_send_buf(mavlink_message_t *msgbuf, mavl
/**
* @brief Get field index from esc_info message
*
- * @return Index of the first ESC in this message. minValue = 0, maxValue = 60, increment = 4.
+ * @return Index of the first ESC in this message (ESC are indexed in motor order). minValue = 0, maxValue = 60, increment = 4.
*/
static inline uint8_t mavlink_msg_esc_info_get_index(const mavlink_message_t* msg)
{
diff --git a/lib/main/MAVLink/common/mavlink_msg_esc_status.h b/lib/main/MAVLink/common/mavlink_msg_esc_status.h
index 1fc33dda0a1..5b4c581e5c7 100644
--- a/lib/main/MAVLink/common/mavlink_msg_esc_status.h
+++ b/lib/main/MAVLink/common/mavlink_msg_esc_status.h
@@ -9,7 +9,7 @@ typedef struct __mavlink_esc_status_t {
int32_t rpm[4]; /*< [rpm] Reported motor RPM from each ESC (negative for reverse rotation).*/
float voltage[4]; /*< [V] Voltage measured from each ESC.*/
float current[4]; /*< [A] Current measured from each ESC.*/
- uint8_t index; /*< Index of the first ESC in this message. minValue = 0, maxValue = 60, increment = 4.*/
+ uint8_t index; /*< Index of the first ESC in this message (ESC are indexed in motor order). minValue = 0, maxValue = 60, increment = 4.*/
} mavlink_esc_status_t;
#define MAVLINK_MSG_ID_ESC_STATUS_LEN 57
@@ -55,7 +55,7 @@ typedef struct __mavlink_esc_status_t {
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
- * @param index Index of the first ESC in this message. minValue = 0, maxValue = 60, increment = 4.
+ * @param index Index of the first ESC in this message (ESC are indexed in motor order). minValue = 0, maxValue = 60, increment = 4.
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude the number.
* @param rpm [rpm] Reported motor RPM from each ESC (negative for reverse rotation).
* @param voltage [V] Voltage measured from each ESC.
@@ -94,7 +94,7 @@ static inline uint16_t mavlink_msg_esc_status_pack(uint8_t system_id, uint8_t co
* @param status MAVLink status structure
* @param msg The MAVLink message to compress the data into
*
- * @param index Index of the first ESC in this message. minValue = 0, maxValue = 60, increment = 4.
+ * @param index Index of the first ESC in this message (ESC are indexed in motor order). minValue = 0, maxValue = 60, increment = 4.
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude the number.
* @param rpm [rpm] Reported motor RPM from each ESC (negative for reverse rotation).
* @param voltage [V] Voltage measured from each ESC.
@@ -136,7 +136,7 @@ static inline uint16_t mavlink_msg_esc_status_pack_status(uint8_t system_id, uin
* @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 index Index of the first ESC in this message. minValue = 0, maxValue = 60, increment = 4.
+ * @param index Index of the first ESC in this message (ESC are indexed in motor order). minValue = 0, maxValue = 60, increment = 4.
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude the number.
* @param rpm [rpm] Reported motor RPM from each ESC (negative for reverse rotation).
* @param voltage [V] Voltage measured from each ESC.
@@ -214,7 +214,7 @@ static inline uint16_t mavlink_msg_esc_status_encode_status(uint8_t system_id, u
* @brief Send a esc_status message
* @param chan MAVLink channel to send the message
*
- * @param index Index of the first ESC in this message. minValue = 0, maxValue = 60, increment = 4.
+ * @param index Index of the first ESC in this message (ESC are indexed in motor order). minValue = 0, maxValue = 60, increment = 4.
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude the number.
* @param rpm [rpm] Reported motor RPM from each ESC (negative for reverse rotation).
* @param voltage [V] Voltage measured from each ESC.
@@ -295,7 +295,7 @@ static inline void mavlink_msg_esc_status_send_buf(mavlink_message_t *msgbuf, ma
/**
* @brief Get field index from esc_status message
*
- * @return Index of the first ESC in this message. minValue = 0, maxValue = 60, increment = 4.
+ * @return Index of the first ESC in this message (ESC are indexed in motor order). minValue = 0, maxValue = 60, increment = 4.
*/
static inline uint8_t mavlink_msg_esc_status_get_index(const mavlink_message_t* msg)
{
diff --git a/lib/main/MAVLink/common/mavlink_msg_figure_eight_execution_status.h b/lib/main/MAVLink/common/mavlink_msg_figure_eight_execution_status.h
new file mode 100644
index 00000000000..96807c5336f
--- /dev/null
+++ b/lib/main/MAVLink/common/mavlink_msg_figure_eight_execution_status.h
@@ -0,0 +1,456 @@
+#pragma once
+// MESSAGE FIGURE_EIGHT_EXECUTION_STATUS PACKING
+
+#define MAVLINK_MSG_ID_FIGURE_EIGHT_EXECUTION_STATUS 361
+
+
+typedef struct __mavlink_figure_eight_execution_status_t {
+ uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/
+ float major_radius; /*< [m] Major axis radius of the figure eight. Positive: orbit the north circle clockwise. Negative: orbit the north circle counter-clockwise.*/
+ float minor_radius; /*< [m] Minor axis radius of the figure eight. Defines the radius of two circles that make up the figure.*/
+ float orientation; /*< [rad] Orientation of the figure eight major axis with respect to true north in [-pi,pi).*/
+ int32_t x; /*< X coordinate of center point. Coordinate system depends on frame field.*/
+ int32_t y; /*< Y coordinate of center point. Coordinate system depends on frame field.*/
+ float z; /*< [m] Altitude of center point. Coordinate system depends on frame field.*/
+ uint8_t frame; /*< The coordinate system of the fields: x, y, z.*/
+} mavlink_figure_eight_execution_status_t;
+
+#define MAVLINK_MSG_ID_FIGURE_EIGHT_EXECUTION_STATUS_LEN 33
+#define MAVLINK_MSG_ID_FIGURE_EIGHT_EXECUTION_STATUS_MIN_LEN 33
+#define MAVLINK_MSG_ID_361_LEN 33
+#define MAVLINK_MSG_ID_361_MIN_LEN 33
+
+#define MAVLINK_MSG_ID_FIGURE_EIGHT_EXECUTION_STATUS_CRC 93
+#define MAVLINK_MSG_ID_361_CRC 93
+
+
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_FIGURE_EIGHT_EXECUTION_STATUS { \
+ 361, \
+ "FIGURE_EIGHT_EXECUTION_STATUS", \
+ 8, \
+ { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_figure_eight_execution_status_t, time_usec) }, \
+ { "major_radius", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_figure_eight_execution_status_t, major_radius) }, \
+ { "minor_radius", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_figure_eight_execution_status_t, minor_radius) }, \
+ { "orientation", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_figure_eight_execution_status_t, orientation) }, \
+ { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_figure_eight_execution_status_t, frame) }, \
+ { "x", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_figure_eight_execution_status_t, x) }, \
+ { "y", NULL, MAVLINK_TYPE_INT32_T, 0, 24, offsetof(mavlink_figure_eight_execution_status_t, y) }, \
+ { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_figure_eight_execution_status_t, z) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_FIGURE_EIGHT_EXECUTION_STATUS { \
+ "FIGURE_EIGHT_EXECUTION_STATUS", \
+ 8, \
+ { { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_figure_eight_execution_status_t, time_usec) }, \
+ { "major_radius", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_figure_eight_execution_status_t, major_radius) }, \
+ { "minor_radius", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_figure_eight_execution_status_t, minor_radius) }, \
+ { "orientation", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_figure_eight_execution_status_t, orientation) }, \
+ { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_figure_eight_execution_status_t, frame) }, \
+ { "x", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_figure_eight_execution_status_t, x) }, \
+ { "y", NULL, MAVLINK_TYPE_INT32_T, 0, 24, offsetof(mavlink_figure_eight_execution_status_t, y) }, \
+ { "z", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_figure_eight_execution_status_t, z) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a figure_eight_execution_status 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 time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
+ * @param major_radius [m] Major axis radius of the figure eight. Positive: orbit the north circle clockwise. Negative: orbit the north circle counter-clockwise.
+ * @param minor_radius [m] Minor axis radius of the figure eight. Defines the radius of two circles that make up the figure.
+ * @param orientation [rad] Orientation of the figure eight major axis with respect to true north in [-pi,pi).
+ * @param frame The coordinate system of the fields: x, y, z.
+ * @param x X coordinate of center point. Coordinate system depends on frame field.
+ * @param y Y coordinate of center point. Coordinate system depends on frame field.
+ * @param z [m] Altitude of center point. Coordinate system depends on frame field.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_figure_eight_execution_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint64_t time_usec, float major_radius, float minor_radius, float orientation, uint8_t frame, int32_t x, int32_t y, float z)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_FIGURE_EIGHT_EXECUTION_STATUS_LEN];
+ _mav_put_uint64_t(buf, 0, time_usec);
+ _mav_put_float(buf, 8, major_radius);
+ _mav_put_float(buf, 12, minor_radius);
+ _mav_put_float(buf, 16, orientation);
+ _mav_put_int32_t(buf, 20, x);
+ _mav_put_int32_t(buf, 24, y);
+ _mav_put_float(buf, 28, z);
+ _mav_put_uint8_t(buf, 32, frame);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FIGURE_EIGHT_EXECUTION_STATUS_LEN);
+#else
+ mavlink_figure_eight_execution_status_t packet;
+ packet.time_usec = time_usec;
+ packet.major_radius = major_radius;
+ packet.minor_radius = minor_radius;
+ packet.orientation = orientation;
+ packet.x = x;
+ packet.y = y;
+ packet.z = z;
+ packet.frame = frame;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FIGURE_EIGHT_EXECUTION_STATUS_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_FIGURE_EIGHT_EXECUTION_STATUS;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FIGURE_EIGHT_EXECUTION_STATUS_MIN_LEN, MAVLINK_MSG_ID_FIGURE_EIGHT_EXECUTION_STATUS_LEN, MAVLINK_MSG_ID_FIGURE_EIGHT_EXECUTION_STATUS_CRC);
+}
+
+/**
+ * @brief Pack a figure_eight_execution_status 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 time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
+ * @param major_radius [m] Major axis radius of the figure eight. Positive: orbit the north circle clockwise. Negative: orbit the north circle counter-clockwise.
+ * @param minor_radius [m] Minor axis radius of the figure eight. Defines the radius of two circles that make up the figure.
+ * @param orientation [rad] Orientation of the figure eight major axis with respect to true north in [-pi,pi).
+ * @param frame The coordinate system of the fields: x, y, z.
+ * @param x X coordinate of center point. Coordinate system depends on frame field.
+ * @param y Y coordinate of center point. Coordinate system depends on frame field.
+ * @param z [m] Altitude of center point. Coordinate system depends on frame field.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_figure_eight_execution_status_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ uint64_t time_usec, float major_radius, float minor_radius, float orientation, uint8_t frame, int32_t x, int32_t y, float z)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_FIGURE_EIGHT_EXECUTION_STATUS_LEN];
+ _mav_put_uint64_t(buf, 0, time_usec);
+ _mav_put_float(buf, 8, major_radius);
+ _mav_put_float(buf, 12, minor_radius);
+ _mav_put_float(buf, 16, orientation);
+ _mav_put_int32_t(buf, 20, x);
+ _mav_put_int32_t(buf, 24, y);
+ _mav_put_float(buf, 28, z);
+ _mav_put_uint8_t(buf, 32, frame);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FIGURE_EIGHT_EXECUTION_STATUS_LEN);
+#else
+ mavlink_figure_eight_execution_status_t packet;
+ packet.time_usec = time_usec;
+ packet.major_radius = major_radius;
+ packet.minor_radius = minor_radius;
+ packet.orientation = orientation;
+ packet.x = x;
+ packet.y = y;
+ packet.z = z;
+ packet.frame = frame;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FIGURE_EIGHT_EXECUTION_STATUS_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_FIGURE_EIGHT_EXECUTION_STATUS;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_FIGURE_EIGHT_EXECUTION_STATUS_MIN_LEN, MAVLINK_MSG_ID_FIGURE_EIGHT_EXECUTION_STATUS_LEN, MAVLINK_MSG_ID_FIGURE_EIGHT_EXECUTION_STATUS_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_FIGURE_EIGHT_EXECUTION_STATUS_MIN_LEN, MAVLINK_MSG_ID_FIGURE_EIGHT_EXECUTION_STATUS_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a figure_eight_execution_status 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 time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
+ * @param major_radius [m] Major axis radius of the figure eight. Positive: orbit the north circle clockwise. Negative: orbit the north circle counter-clockwise.
+ * @param minor_radius [m] Minor axis radius of the figure eight. Defines the radius of two circles that make up the figure.
+ * @param orientation [rad] Orientation of the figure eight major axis with respect to true north in [-pi,pi).
+ * @param frame The coordinate system of the fields: x, y, z.
+ * @param x X coordinate of center point. Coordinate system depends on frame field.
+ * @param y Y coordinate of center point. Coordinate system depends on frame field.
+ * @param z [m] Altitude of center point. Coordinate system depends on frame field.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_figure_eight_execution_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint64_t time_usec,float major_radius,float minor_radius,float orientation,uint8_t frame,int32_t x,int32_t y,float z)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_FIGURE_EIGHT_EXECUTION_STATUS_LEN];
+ _mav_put_uint64_t(buf, 0, time_usec);
+ _mav_put_float(buf, 8, major_radius);
+ _mav_put_float(buf, 12, minor_radius);
+ _mav_put_float(buf, 16, orientation);
+ _mav_put_int32_t(buf, 20, x);
+ _mav_put_int32_t(buf, 24, y);
+ _mav_put_float(buf, 28, z);
+ _mav_put_uint8_t(buf, 32, frame);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FIGURE_EIGHT_EXECUTION_STATUS_LEN);
+#else
+ mavlink_figure_eight_execution_status_t packet;
+ packet.time_usec = time_usec;
+ packet.major_radius = major_radius;
+ packet.minor_radius = minor_radius;
+ packet.orientation = orientation;
+ packet.x = x;
+ packet.y = y;
+ packet.z = z;
+ packet.frame = frame;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FIGURE_EIGHT_EXECUTION_STATUS_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_FIGURE_EIGHT_EXECUTION_STATUS;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FIGURE_EIGHT_EXECUTION_STATUS_MIN_LEN, MAVLINK_MSG_ID_FIGURE_EIGHT_EXECUTION_STATUS_LEN, MAVLINK_MSG_ID_FIGURE_EIGHT_EXECUTION_STATUS_CRC);
+}
+
+/**
+ * @brief Encode a figure_eight_execution_status 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 figure_eight_execution_status C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_figure_eight_execution_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_figure_eight_execution_status_t* figure_eight_execution_status)
+{
+ return mavlink_msg_figure_eight_execution_status_pack(system_id, component_id, msg, figure_eight_execution_status->time_usec, figure_eight_execution_status->major_radius, figure_eight_execution_status->minor_radius, figure_eight_execution_status->orientation, figure_eight_execution_status->frame, figure_eight_execution_status->x, figure_eight_execution_status->y, figure_eight_execution_status->z);
+}
+
+/**
+ * @brief Encode a figure_eight_execution_status 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 figure_eight_execution_status C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_figure_eight_execution_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_figure_eight_execution_status_t* figure_eight_execution_status)
+{
+ return mavlink_msg_figure_eight_execution_status_pack_chan(system_id, component_id, chan, msg, figure_eight_execution_status->time_usec, figure_eight_execution_status->major_radius, figure_eight_execution_status->minor_radius, figure_eight_execution_status->orientation, figure_eight_execution_status->frame, figure_eight_execution_status->x, figure_eight_execution_status->y, figure_eight_execution_status->z);
+}
+
+/**
+ * @brief Encode a figure_eight_execution_status 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 figure_eight_execution_status C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_figure_eight_execution_status_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_figure_eight_execution_status_t* figure_eight_execution_status)
+{
+ return mavlink_msg_figure_eight_execution_status_pack_status(system_id, component_id, _status, msg, figure_eight_execution_status->time_usec, figure_eight_execution_status->major_radius, figure_eight_execution_status->minor_radius, figure_eight_execution_status->orientation, figure_eight_execution_status->frame, figure_eight_execution_status->x, figure_eight_execution_status->y, figure_eight_execution_status->z);
+}
+
+/**
+ * @brief Send a figure_eight_execution_status message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
+ * @param major_radius [m] Major axis radius of the figure eight. Positive: orbit the north circle clockwise. Negative: orbit the north circle counter-clockwise.
+ * @param minor_radius [m] Minor axis radius of the figure eight. Defines the radius of two circles that make up the figure.
+ * @param orientation [rad] Orientation of the figure eight major axis with respect to true north in [-pi,pi).
+ * @param frame The coordinate system of the fields: x, y, z.
+ * @param x X coordinate of center point. Coordinate system depends on frame field.
+ * @param y Y coordinate of center point. Coordinate system depends on frame field.
+ * @param z [m] Altitude of center point. Coordinate system depends on frame field.
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_figure_eight_execution_status_send(mavlink_channel_t chan, uint64_t time_usec, float major_radius, float minor_radius, float orientation, uint8_t frame, int32_t x, int32_t y, float z)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_FIGURE_EIGHT_EXECUTION_STATUS_LEN];
+ _mav_put_uint64_t(buf, 0, time_usec);
+ _mav_put_float(buf, 8, major_radius);
+ _mav_put_float(buf, 12, minor_radius);
+ _mav_put_float(buf, 16, orientation);
+ _mav_put_int32_t(buf, 20, x);
+ _mav_put_int32_t(buf, 24, y);
+ _mav_put_float(buf, 28, z);
+ _mav_put_uint8_t(buf, 32, frame);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FIGURE_EIGHT_EXECUTION_STATUS, buf, MAVLINK_MSG_ID_FIGURE_EIGHT_EXECUTION_STATUS_MIN_LEN, MAVLINK_MSG_ID_FIGURE_EIGHT_EXECUTION_STATUS_LEN, MAVLINK_MSG_ID_FIGURE_EIGHT_EXECUTION_STATUS_CRC);
+#else
+ mavlink_figure_eight_execution_status_t packet;
+ packet.time_usec = time_usec;
+ packet.major_radius = major_radius;
+ packet.minor_radius = minor_radius;
+ packet.orientation = orientation;
+ packet.x = x;
+ packet.y = y;
+ packet.z = z;
+ packet.frame = frame;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FIGURE_EIGHT_EXECUTION_STATUS, (const char *)&packet, MAVLINK_MSG_ID_FIGURE_EIGHT_EXECUTION_STATUS_MIN_LEN, MAVLINK_MSG_ID_FIGURE_EIGHT_EXECUTION_STATUS_LEN, MAVLINK_MSG_ID_FIGURE_EIGHT_EXECUTION_STATUS_CRC);
+#endif
+}
+
+/**
+ * @brief Send a figure_eight_execution_status message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_figure_eight_execution_status_send_struct(mavlink_channel_t chan, const mavlink_figure_eight_execution_status_t* figure_eight_execution_status)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_figure_eight_execution_status_send(chan, figure_eight_execution_status->time_usec, figure_eight_execution_status->major_radius, figure_eight_execution_status->minor_radius, figure_eight_execution_status->orientation, figure_eight_execution_status->frame, figure_eight_execution_status->x, figure_eight_execution_status->y, figure_eight_execution_status->z);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FIGURE_EIGHT_EXECUTION_STATUS, (const char *)figure_eight_execution_status, MAVLINK_MSG_ID_FIGURE_EIGHT_EXECUTION_STATUS_MIN_LEN, MAVLINK_MSG_ID_FIGURE_EIGHT_EXECUTION_STATUS_LEN, MAVLINK_MSG_ID_FIGURE_EIGHT_EXECUTION_STATUS_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_FIGURE_EIGHT_EXECUTION_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_figure_eight_execution_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, float major_radius, float minor_radius, float orientation, uint8_t frame, int32_t x, int32_t y, float z)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint64_t(buf, 0, time_usec);
+ _mav_put_float(buf, 8, major_radius);
+ _mav_put_float(buf, 12, minor_radius);
+ _mav_put_float(buf, 16, orientation);
+ _mav_put_int32_t(buf, 20, x);
+ _mav_put_int32_t(buf, 24, y);
+ _mav_put_float(buf, 28, z);
+ _mav_put_uint8_t(buf, 32, frame);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FIGURE_EIGHT_EXECUTION_STATUS, buf, MAVLINK_MSG_ID_FIGURE_EIGHT_EXECUTION_STATUS_MIN_LEN, MAVLINK_MSG_ID_FIGURE_EIGHT_EXECUTION_STATUS_LEN, MAVLINK_MSG_ID_FIGURE_EIGHT_EXECUTION_STATUS_CRC);
+#else
+ mavlink_figure_eight_execution_status_t *packet = (mavlink_figure_eight_execution_status_t *)msgbuf;
+ packet->time_usec = time_usec;
+ packet->major_radius = major_radius;
+ packet->minor_radius = minor_radius;
+ packet->orientation = orientation;
+ packet->x = x;
+ packet->y = y;
+ packet->z = z;
+ packet->frame = frame;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FIGURE_EIGHT_EXECUTION_STATUS, (const char *)packet, MAVLINK_MSG_ID_FIGURE_EIGHT_EXECUTION_STATUS_MIN_LEN, MAVLINK_MSG_ID_FIGURE_EIGHT_EXECUTION_STATUS_LEN, MAVLINK_MSG_ID_FIGURE_EIGHT_EXECUTION_STATUS_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE FIGURE_EIGHT_EXECUTION_STATUS UNPACKING
+
+
+/**
+ * @brief Get field time_usec from figure_eight_execution_status message
+ *
+ * @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
+ */
+static inline uint64_t mavlink_msg_figure_eight_execution_status_get_time_usec(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint64_t(msg, 0);
+}
+
+/**
+ * @brief Get field major_radius from figure_eight_execution_status message
+ *
+ * @return [m] Major axis radius of the figure eight. Positive: orbit the north circle clockwise. Negative: orbit the north circle counter-clockwise.
+ */
+static inline float mavlink_msg_figure_eight_execution_status_get_major_radius(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 8);
+}
+
+/**
+ * @brief Get field minor_radius from figure_eight_execution_status message
+ *
+ * @return [m] Minor axis radius of the figure eight. Defines the radius of two circles that make up the figure.
+ */
+static inline float mavlink_msg_figure_eight_execution_status_get_minor_radius(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 12);
+}
+
+/**
+ * @brief Get field orientation from figure_eight_execution_status message
+ *
+ * @return [rad] Orientation of the figure eight major axis with respect to true north in [-pi,pi).
+ */
+static inline float mavlink_msg_figure_eight_execution_status_get_orientation(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 16);
+}
+
+/**
+ * @brief Get field frame from figure_eight_execution_status message
+ *
+ * @return The coordinate system of the fields: x, y, z.
+ */
+static inline uint8_t mavlink_msg_figure_eight_execution_status_get_frame(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 32);
+}
+
+/**
+ * @brief Get field x from figure_eight_execution_status message
+ *
+ * @return X coordinate of center point. Coordinate system depends on frame field.
+ */
+static inline int32_t mavlink_msg_figure_eight_execution_status_get_x(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_int32_t(msg, 20);
+}
+
+/**
+ * @brief Get field y from figure_eight_execution_status message
+ *
+ * @return Y coordinate of center point. Coordinate system depends on frame field.
+ */
+static inline int32_t mavlink_msg_figure_eight_execution_status_get_y(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_int32_t(msg, 24);
+}
+
+/**
+ * @brief Get field z from figure_eight_execution_status message
+ *
+ * @return [m] Altitude of center point. Coordinate system depends on frame field.
+ */
+static inline float mavlink_msg_figure_eight_execution_status_get_z(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 28);
+}
+
+/**
+ * @brief Decode a figure_eight_execution_status message into a struct
+ *
+ * @param msg The message to decode
+ * @param figure_eight_execution_status C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_figure_eight_execution_status_decode(const mavlink_message_t* msg, mavlink_figure_eight_execution_status_t* figure_eight_execution_status)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ figure_eight_execution_status->time_usec = mavlink_msg_figure_eight_execution_status_get_time_usec(msg);
+ figure_eight_execution_status->major_radius = mavlink_msg_figure_eight_execution_status_get_major_radius(msg);
+ figure_eight_execution_status->minor_radius = mavlink_msg_figure_eight_execution_status_get_minor_radius(msg);
+ figure_eight_execution_status->orientation = mavlink_msg_figure_eight_execution_status_get_orientation(msg);
+ figure_eight_execution_status->x = mavlink_msg_figure_eight_execution_status_get_x(msg);
+ figure_eight_execution_status->y = mavlink_msg_figure_eight_execution_status_get_y(msg);
+ figure_eight_execution_status->z = mavlink_msg_figure_eight_execution_status_get_z(msg);
+ figure_eight_execution_status->frame = mavlink_msg_figure_eight_execution_status_get_frame(msg);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_FIGURE_EIGHT_EXECUTION_STATUS_LEN? msg->len : MAVLINK_MSG_ID_FIGURE_EIGHT_EXECUTION_STATUS_LEN;
+ memset(figure_eight_execution_status, 0, MAVLINK_MSG_ID_FIGURE_EIGHT_EXECUTION_STATUS_LEN);
+ memcpy(figure_eight_execution_status, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/common/mavlink_msg_file_transfer_protocol.h b/lib/main/MAVLink/common/mavlink_msg_file_transfer_protocol.h
index 091aec65e66..992a16e62a9 100755
--- a/lib/main/MAVLink/common/mavlink_msg_file_transfer_protocol.h
+++ b/lib/main/MAVLink/common/mavlink_msg_file_transfer_protocol.h
@@ -8,7 +8,7 @@ typedef struct __mavlink_file_transfer_protocol_t {
uint8_t target_network; /*< Network ID (0 for broadcast)*/
uint8_t target_system; /*< System ID (0 for broadcast)*/
uint8_t target_component; /*< Component ID (0 for broadcast)*/
- uint8_t payload[251]; /*< Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The content/format of this block is defined in https://mavlink.io/en/services/ftp.html.*/
+ uint8_t payload[251]; /*< Variable length payload. The content/format of this block is defined in https://mavlink.io/en/services/ftp.html. The length is defined by the remaining message length when subtracting the header and other fields. See also MAV_FTP_OPCODE and MAV_FTP_ERR.*/
} mavlink_file_transfer_protocol_t;
#define MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN 254
@@ -53,7 +53,7 @@ typedef struct __mavlink_file_transfer_protocol_t {
* @param target_network Network ID (0 for broadcast)
* @param target_system System ID (0 for broadcast)
* @param target_component Component ID (0 for broadcast)
- * @param payload Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The content/format of this block is defined in https://mavlink.io/en/services/ftp.html.
+ * @param payload Variable length payload. The content/format of this block is defined in https://mavlink.io/en/services/ftp.html. The length is defined by the remaining message length when subtracting the header and other fields. See also MAV_FTP_OPCODE and MAV_FTP_ERR.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_file_transfer_protocol_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
@@ -89,7 +89,7 @@ static inline uint16_t mavlink_msg_file_transfer_protocol_pack(uint8_t system_id
* @param target_network Network ID (0 for broadcast)
* @param target_system System ID (0 for broadcast)
* @param target_component Component ID (0 for broadcast)
- * @param payload Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The content/format of this block is defined in https://mavlink.io/en/services/ftp.html.
+ * @param payload Variable length payload. The content/format of this block is defined in https://mavlink.io/en/services/ftp.html. The length is defined by the remaining message length when subtracting the header and other fields. See also MAV_FTP_OPCODE and MAV_FTP_ERR.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_file_transfer_protocol_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
@@ -128,7 +128,7 @@ static inline uint16_t mavlink_msg_file_transfer_protocol_pack_status(uint8_t sy
* @param target_network Network ID (0 for broadcast)
* @param target_system System ID (0 for broadcast)
* @param target_component Component ID (0 for broadcast)
- * @param payload Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The content/format of this block is defined in https://mavlink.io/en/services/ftp.html.
+ * @param payload Variable length payload. The content/format of this block is defined in https://mavlink.io/en/services/ftp.html. The length is defined by the remaining message length when subtracting the header and other fields. See also MAV_FTP_OPCODE and MAV_FTP_ERR.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_file_transfer_protocol_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
@@ -203,7 +203,7 @@ static inline uint16_t mavlink_msg_file_transfer_protocol_encode_status(uint8_t
* @param target_network Network ID (0 for broadcast)
* @param target_system System ID (0 for broadcast)
* @param target_component Component ID (0 for broadcast)
- * @param payload Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The content/format of this block is defined in https://mavlink.io/en/services/ftp.html.
+ * @param payload Variable length payload. The content/format of this block is defined in https://mavlink.io/en/services/ftp.html. The length is defined by the remaining message length when subtracting the header and other fields. See also MAV_FTP_OPCODE and MAV_FTP_ERR.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
@@ -306,7 +306,7 @@ static inline uint8_t mavlink_msg_file_transfer_protocol_get_target_component(co
/**
* @brief Get field payload from file_transfer_protocol message
*
- * @return Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The content/format of this block is defined in https://mavlink.io/en/services/ftp.html.
+ * @return Variable length payload. The content/format of this block is defined in https://mavlink.io/en/services/ftp.html. The length is defined by the remaining message length when subtracting the header and other fields. See also MAV_FTP_OPCODE and MAV_FTP_ERR.
*/
static inline uint16_t mavlink_msg_file_transfer_protocol_get_payload(const mavlink_message_t* msg, uint8_t *payload)
{
diff --git a/lib/main/MAVLink/common/mavlink_msg_gimbal_device_information.h b/lib/main/MAVLink/common/mavlink_msg_gimbal_device_information.h
index 77c5e901799..937540afc71 100644
--- a/lib/main/MAVLink/common/mavlink_msg_gimbal_device_information.h
+++ b/lib/main/MAVLink/common/mavlink_msg_gimbal_device_information.h
@@ -3,12 +3,12 @@
#define MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION 283
-
+MAVPACKED(
typedef struct __mavlink_gimbal_device_information_t {
uint64_t uid; /*< UID of gimbal hardware (0 if unknown).*/
uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/
- uint32_t firmware_version; /*< Version of the gimbal firmware, encoded as: `(Dev & 0xff) << 24 \| (Patch & 0xff) << 16 \| (Minor & 0xff) << 8 \| (Major & 0xff)`.*/
- uint32_t hardware_version; /*< Version of the gimbal hardware, encoded as: `(Dev & 0xff) << 24 \| (Patch & 0xff) << 16 \| (Minor & 0xff) << 8 \| (Major & 0xff)`.*/
+ uint32_t firmware_version; /*< Version of the gimbal firmware, encoded as: `(Dev & 0xff) << 24 + (Patch & 0xff) << 16 + (Minor & 0xff) << 8 + (Major & 0xff)`.*/
+ uint32_t hardware_version; /*< Version of the gimbal hardware, encoded as: `(Dev & 0xff) << 24 + (Patch & 0xff) << 16 + (Minor & 0xff) << 8 + (Major & 0xff)`.*/
float roll_min; /*< [rad] Minimum hardware roll angle (positive: rolling to the right, negative: rolling to the left). NAN if unknown.*/
float roll_max; /*< [rad] Maximum hardware roll angle (positive: rolling to the right, negative: rolling to the left). NAN if unknown.*/
float pitch_min; /*< [rad] Minimum hardware pitch angle (positive: up, negative: down). NAN if unknown.*/
@@ -21,11 +21,12 @@ typedef struct __mavlink_gimbal_device_information_t {
char model_name[32]; /*< Name of the gimbal model.*/
char custom_name[32]; /*< Custom name of the gimbal given to it by the user.*/
uint8_t gimbal_device_id; /*< This field is to be used if the gimbal manager and the gimbal device are the same component and hence have the same component ID. This field is then set to a number between 1-6. If the component ID is separate, this field is not required and must be set to 0.*/
-} mavlink_gimbal_device_information_t;
+ uint32_t cap_flags2; /*< Extended bitmap of gimbal capability flags (32 bit). For backwards compatibility, the lower 16 bits should also be set in cap_flags. Ground stations should prefer this field if non-zero.*/
+}) mavlink_gimbal_device_information_t;
-#define MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_LEN 145
+#define MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_LEN 149
#define MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_MIN_LEN 144
-#define MAVLINK_MSG_ID_283_LEN 145
+#define MAVLINK_MSG_ID_283_LEN 149
#define MAVLINK_MSG_ID_283_MIN_LEN 144
#define MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_CRC 74
@@ -39,7 +40,7 @@ typedef struct __mavlink_gimbal_device_information_t {
#define MAVLINK_MESSAGE_INFO_GIMBAL_DEVICE_INFORMATION { \
283, \
"GIMBAL_DEVICE_INFORMATION", \
- 16, \
+ 17, \
{ { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_gimbal_device_information_t, time_boot_ms) }, \
{ "vendor_name", NULL, MAVLINK_TYPE_CHAR, 32, 48, offsetof(mavlink_gimbal_device_information_t, vendor_name) }, \
{ "model_name", NULL, MAVLINK_TYPE_CHAR, 32, 80, offsetof(mavlink_gimbal_device_information_t, model_name) }, \
@@ -56,12 +57,13 @@ typedef struct __mavlink_gimbal_device_information_t {
{ "yaw_min", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_gimbal_device_information_t, yaw_min) }, \
{ "yaw_max", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_gimbal_device_information_t, yaw_max) }, \
{ "gimbal_device_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 144, offsetof(mavlink_gimbal_device_information_t, gimbal_device_id) }, \
+ { "cap_flags2", NULL, MAVLINK_TYPE_UINT32_T, 0, 145, offsetof(mavlink_gimbal_device_information_t, cap_flags2) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_GIMBAL_DEVICE_INFORMATION { \
"GIMBAL_DEVICE_INFORMATION", \
- 16, \
+ 17, \
{ { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_gimbal_device_information_t, time_boot_ms) }, \
{ "vendor_name", NULL, MAVLINK_TYPE_CHAR, 32, 48, offsetof(mavlink_gimbal_device_information_t, vendor_name) }, \
{ "model_name", NULL, MAVLINK_TYPE_CHAR, 32, 80, offsetof(mavlink_gimbal_device_information_t, model_name) }, \
@@ -78,6 +80,7 @@ typedef struct __mavlink_gimbal_device_information_t {
{ "yaw_min", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_gimbal_device_information_t, yaw_min) }, \
{ "yaw_max", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_gimbal_device_information_t, yaw_max) }, \
{ "gimbal_device_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 144, offsetof(mavlink_gimbal_device_information_t, gimbal_device_id) }, \
+ { "cap_flags2", NULL, MAVLINK_TYPE_UINT32_T, 0, 145, offsetof(mavlink_gimbal_device_information_t, cap_flags2) }, \
} \
}
#endif
@@ -92,8 +95,8 @@ typedef struct __mavlink_gimbal_device_information_t {
* @param vendor_name Name of the gimbal vendor.
* @param model_name Name of the gimbal model.
* @param custom_name Custom name of the gimbal given to it by the user.
- * @param firmware_version Version of the gimbal firmware, encoded as: `(Dev & 0xff) << 24 \| (Patch & 0xff) << 16 \| (Minor & 0xff) << 8 \| (Major & 0xff)`.
- * @param hardware_version Version of the gimbal hardware, encoded as: `(Dev & 0xff) << 24 \| (Patch & 0xff) << 16 \| (Minor & 0xff) << 8 \| (Major & 0xff)`.
+ * @param firmware_version Version of the gimbal firmware, encoded as: `(Dev & 0xff) << 24 + (Patch & 0xff) << 16 + (Minor & 0xff) << 8 + (Major & 0xff)`.
+ * @param hardware_version Version of the gimbal hardware, encoded as: `(Dev & 0xff) << 24 + (Patch & 0xff) << 16 + (Minor & 0xff) << 8 + (Major & 0xff)`.
* @param uid UID of gimbal hardware (0 if unknown).
* @param cap_flags Bitmap of gimbal capability flags.
* @param custom_cap_flags Bitmap for use for gimbal-specific capability flags.
@@ -104,10 +107,11 @@ typedef struct __mavlink_gimbal_device_information_t {
* @param yaw_min [rad] Minimum hardware yaw angle (positive: to the right, negative: to the left). NAN if unknown.
* @param yaw_max [rad] Maximum hardware yaw angle (positive: to the right, negative: to the left). NAN if unknown.
* @param gimbal_device_id This field is to be used if the gimbal manager and the gimbal device are the same component and hence have the same component ID. This field is then set to a number between 1-6. If the component ID is separate, this field is not required and must be set to 0.
+ * @param cap_flags2 Extended bitmap of gimbal capability flags (32 bit). For backwards compatibility, the lower 16 bits should also be set in cap_flags. Ground stations should prefer this field if non-zero.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_gimbal_device_information_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint32_t time_boot_ms, const char *vendor_name, const char *model_name, const char *custom_name, uint32_t firmware_version, uint32_t hardware_version, uint64_t uid, uint16_t cap_flags, uint16_t custom_cap_flags, float roll_min, float roll_max, float pitch_min, float pitch_max, float yaw_min, float yaw_max, uint8_t gimbal_device_id)
+ uint32_t time_boot_ms, const char *vendor_name, const char *model_name, const char *custom_name, uint32_t firmware_version, uint32_t hardware_version, uint64_t uid, uint16_t cap_flags, uint16_t custom_cap_flags, float roll_min, float roll_max, float pitch_min, float pitch_max, float yaw_min, float yaw_max, uint8_t gimbal_device_id, uint32_t cap_flags2)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_LEN];
@@ -124,6 +128,7 @@ static inline uint16_t mavlink_msg_gimbal_device_information_pack(uint8_t system
_mav_put_uint16_t(buf, 44, cap_flags);
_mav_put_uint16_t(buf, 46, custom_cap_flags);
_mav_put_uint8_t(buf, 144, gimbal_device_id);
+ _mav_put_uint32_t(buf, 145, cap_flags2);
_mav_put_char_array(buf, 48, vendor_name, 32);
_mav_put_char_array(buf, 80, model_name, 32);
_mav_put_char_array(buf, 112, custom_name, 32);
@@ -143,6 +148,7 @@ static inline uint16_t mavlink_msg_gimbal_device_information_pack(uint8_t system
packet.cap_flags = cap_flags;
packet.custom_cap_flags = custom_cap_flags;
packet.gimbal_device_id = gimbal_device_id;
+ packet.cap_flags2 = cap_flags2;
mav_array_assign_char(packet.vendor_name, vendor_name, 32);
mav_array_assign_char(packet.model_name, model_name, 32);
mav_array_assign_char(packet.custom_name, custom_name, 32);
@@ -164,8 +170,8 @@ static inline uint16_t mavlink_msg_gimbal_device_information_pack(uint8_t system
* @param vendor_name Name of the gimbal vendor.
* @param model_name Name of the gimbal model.
* @param custom_name Custom name of the gimbal given to it by the user.
- * @param firmware_version Version of the gimbal firmware, encoded as: `(Dev & 0xff) << 24 \| (Patch & 0xff) << 16 \| (Minor & 0xff) << 8 \| (Major & 0xff)`.
- * @param hardware_version Version of the gimbal hardware, encoded as: `(Dev & 0xff) << 24 \| (Patch & 0xff) << 16 \| (Minor & 0xff) << 8 \| (Major & 0xff)`.
+ * @param firmware_version Version of the gimbal firmware, encoded as: `(Dev & 0xff) << 24 + (Patch & 0xff) << 16 + (Minor & 0xff) << 8 + (Major & 0xff)`.
+ * @param hardware_version Version of the gimbal hardware, encoded as: `(Dev & 0xff) << 24 + (Patch & 0xff) << 16 + (Minor & 0xff) << 8 + (Major & 0xff)`.
* @param uid UID of gimbal hardware (0 if unknown).
* @param cap_flags Bitmap of gimbal capability flags.
* @param custom_cap_flags Bitmap for use for gimbal-specific capability flags.
@@ -176,10 +182,11 @@ static inline uint16_t mavlink_msg_gimbal_device_information_pack(uint8_t system
* @param yaw_min [rad] Minimum hardware yaw angle (positive: to the right, negative: to the left). NAN if unknown.
* @param yaw_max [rad] Maximum hardware yaw angle (positive: to the right, negative: to the left). NAN if unknown.
* @param gimbal_device_id This field is to be used if the gimbal manager and the gimbal device are the same component and hence have the same component ID. This field is then set to a number between 1-6. If the component ID is separate, this field is not required and must be set to 0.
+ * @param cap_flags2 Extended bitmap of gimbal capability flags (32 bit). For backwards compatibility, the lower 16 bits should also be set in cap_flags. Ground stations should prefer this field if non-zero.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_gimbal_device_information_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
- uint32_t time_boot_ms, const char *vendor_name, const char *model_name, const char *custom_name, uint32_t firmware_version, uint32_t hardware_version, uint64_t uid, uint16_t cap_flags, uint16_t custom_cap_flags, float roll_min, float roll_max, float pitch_min, float pitch_max, float yaw_min, float yaw_max, uint8_t gimbal_device_id)
+ uint32_t time_boot_ms, const char *vendor_name, const char *model_name, const char *custom_name, uint32_t firmware_version, uint32_t hardware_version, uint64_t uid, uint16_t cap_flags, uint16_t custom_cap_flags, float roll_min, float roll_max, float pitch_min, float pitch_max, float yaw_min, float yaw_max, uint8_t gimbal_device_id, uint32_t cap_flags2)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_LEN];
@@ -196,6 +203,7 @@ static inline uint16_t mavlink_msg_gimbal_device_information_pack_status(uint8_t
_mav_put_uint16_t(buf, 44, cap_flags);
_mav_put_uint16_t(buf, 46, custom_cap_flags);
_mav_put_uint8_t(buf, 144, gimbal_device_id);
+ _mav_put_uint32_t(buf, 145, cap_flags2);
_mav_put_char_array(buf, 48, vendor_name, 32);
_mav_put_char_array(buf, 80, model_name, 32);
_mav_put_char_array(buf, 112, custom_name, 32);
@@ -215,6 +223,7 @@ static inline uint16_t mavlink_msg_gimbal_device_information_pack_status(uint8_t
packet.cap_flags = cap_flags;
packet.custom_cap_flags = custom_cap_flags;
packet.gimbal_device_id = gimbal_device_id;
+ packet.cap_flags2 = cap_flags2;
mav_array_memcpy(packet.vendor_name, vendor_name, sizeof(char)*32);
mav_array_memcpy(packet.model_name, model_name, sizeof(char)*32);
mav_array_memcpy(packet.custom_name, custom_name, sizeof(char)*32);
@@ -239,8 +248,8 @@ static inline uint16_t mavlink_msg_gimbal_device_information_pack_status(uint8_t
* @param vendor_name Name of the gimbal vendor.
* @param model_name Name of the gimbal model.
* @param custom_name Custom name of the gimbal given to it by the user.
- * @param firmware_version Version of the gimbal firmware, encoded as: `(Dev & 0xff) << 24 \| (Patch & 0xff) << 16 \| (Minor & 0xff) << 8 \| (Major & 0xff)`.
- * @param hardware_version Version of the gimbal hardware, encoded as: `(Dev & 0xff) << 24 \| (Patch & 0xff) << 16 \| (Minor & 0xff) << 8 \| (Major & 0xff)`.
+ * @param firmware_version Version of the gimbal firmware, encoded as: `(Dev & 0xff) << 24 + (Patch & 0xff) << 16 + (Minor & 0xff) << 8 + (Major & 0xff)`.
+ * @param hardware_version Version of the gimbal hardware, encoded as: `(Dev & 0xff) << 24 + (Patch & 0xff) << 16 + (Minor & 0xff) << 8 + (Major & 0xff)`.
* @param uid UID of gimbal hardware (0 if unknown).
* @param cap_flags Bitmap of gimbal capability flags.
* @param custom_cap_flags Bitmap for use for gimbal-specific capability flags.
@@ -251,11 +260,12 @@ static inline uint16_t mavlink_msg_gimbal_device_information_pack_status(uint8_t
* @param yaw_min [rad] Minimum hardware yaw angle (positive: to the right, negative: to the left). NAN if unknown.
* @param yaw_max [rad] Maximum hardware yaw angle (positive: to the right, negative: to the left). NAN if unknown.
* @param gimbal_device_id This field is to be used if the gimbal manager and the gimbal device are the same component and hence have the same component ID. This field is then set to a number between 1-6. If the component ID is separate, this field is not required and must be set to 0.
+ * @param cap_flags2 Extended bitmap of gimbal capability flags (32 bit). For backwards compatibility, the lower 16 bits should also be set in cap_flags. Ground stations should prefer this field if non-zero.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_gimbal_device_information_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
- uint32_t time_boot_ms,const char *vendor_name,const char *model_name,const char *custom_name,uint32_t firmware_version,uint32_t hardware_version,uint64_t uid,uint16_t cap_flags,uint16_t custom_cap_flags,float roll_min,float roll_max,float pitch_min,float pitch_max,float yaw_min,float yaw_max,uint8_t gimbal_device_id)
+ uint32_t time_boot_ms,const char *vendor_name,const char *model_name,const char *custom_name,uint32_t firmware_version,uint32_t hardware_version,uint64_t uid,uint16_t cap_flags,uint16_t custom_cap_flags,float roll_min,float roll_max,float pitch_min,float pitch_max,float yaw_min,float yaw_max,uint8_t gimbal_device_id,uint32_t cap_flags2)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_LEN];
@@ -272,6 +282,7 @@ static inline uint16_t mavlink_msg_gimbal_device_information_pack_chan(uint8_t s
_mav_put_uint16_t(buf, 44, cap_flags);
_mav_put_uint16_t(buf, 46, custom_cap_flags);
_mav_put_uint8_t(buf, 144, gimbal_device_id);
+ _mav_put_uint32_t(buf, 145, cap_flags2);
_mav_put_char_array(buf, 48, vendor_name, 32);
_mav_put_char_array(buf, 80, model_name, 32);
_mav_put_char_array(buf, 112, custom_name, 32);
@@ -291,6 +302,7 @@ static inline uint16_t mavlink_msg_gimbal_device_information_pack_chan(uint8_t s
packet.cap_flags = cap_flags;
packet.custom_cap_flags = custom_cap_flags;
packet.gimbal_device_id = gimbal_device_id;
+ packet.cap_flags2 = cap_flags2;
mav_array_assign_char(packet.vendor_name, vendor_name, 32);
mav_array_assign_char(packet.model_name, model_name, 32);
mav_array_assign_char(packet.custom_name, custom_name, 32);
@@ -311,7 +323,7 @@ static inline uint16_t mavlink_msg_gimbal_device_information_pack_chan(uint8_t s
*/
static inline uint16_t mavlink_msg_gimbal_device_information_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gimbal_device_information_t* gimbal_device_information)
{
- return mavlink_msg_gimbal_device_information_pack(system_id, component_id, msg, gimbal_device_information->time_boot_ms, gimbal_device_information->vendor_name, gimbal_device_information->model_name, gimbal_device_information->custom_name, gimbal_device_information->firmware_version, gimbal_device_information->hardware_version, gimbal_device_information->uid, gimbal_device_information->cap_flags, gimbal_device_information->custom_cap_flags, gimbal_device_information->roll_min, gimbal_device_information->roll_max, gimbal_device_information->pitch_min, gimbal_device_information->pitch_max, gimbal_device_information->yaw_min, gimbal_device_information->yaw_max, gimbal_device_information->gimbal_device_id);
+ return mavlink_msg_gimbal_device_information_pack(system_id, component_id, msg, gimbal_device_information->time_boot_ms, gimbal_device_information->vendor_name, gimbal_device_information->model_name, gimbal_device_information->custom_name, gimbal_device_information->firmware_version, gimbal_device_information->hardware_version, gimbal_device_information->uid, gimbal_device_information->cap_flags, gimbal_device_information->custom_cap_flags, gimbal_device_information->roll_min, gimbal_device_information->roll_max, gimbal_device_information->pitch_min, gimbal_device_information->pitch_max, gimbal_device_information->yaw_min, gimbal_device_information->yaw_max, gimbal_device_information->gimbal_device_id, gimbal_device_information->cap_flags2);
}
/**
@@ -325,7 +337,7 @@ static inline uint16_t mavlink_msg_gimbal_device_information_encode(uint8_t syst
*/
static inline uint16_t mavlink_msg_gimbal_device_information_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gimbal_device_information_t* gimbal_device_information)
{
- return mavlink_msg_gimbal_device_information_pack_chan(system_id, component_id, chan, msg, gimbal_device_information->time_boot_ms, gimbal_device_information->vendor_name, gimbal_device_information->model_name, gimbal_device_information->custom_name, gimbal_device_information->firmware_version, gimbal_device_information->hardware_version, gimbal_device_information->uid, gimbal_device_information->cap_flags, gimbal_device_information->custom_cap_flags, gimbal_device_information->roll_min, gimbal_device_information->roll_max, gimbal_device_information->pitch_min, gimbal_device_information->pitch_max, gimbal_device_information->yaw_min, gimbal_device_information->yaw_max, gimbal_device_information->gimbal_device_id);
+ return mavlink_msg_gimbal_device_information_pack_chan(system_id, component_id, chan, msg, gimbal_device_information->time_boot_ms, gimbal_device_information->vendor_name, gimbal_device_information->model_name, gimbal_device_information->custom_name, gimbal_device_information->firmware_version, gimbal_device_information->hardware_version, gimbal_device_information->uid, gimbal_device_information->cap_flags, gimbal_device_information->custom_cap_flags, gimbal_device_information->roll_min, gimbal_device_information->roll_max, gimbal_device_information->pitch_min, gimbal_device_information->pitch_max, gimbal_device_information->yaw_min, gimbal_device_information->yaw_max, gimbal_device_information->gimbal_device_id, gimbal_device_information->cap_flags2);
}
/**
@@ -339,7 +351,7 @@ static inline uint16_t mavlink_msg_gimbal_device_information_encode_chan(uint8_t
*/
static inline uint16_t mavlink_msg_gimbal_device_information_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_gimbal_device_information_t* gimbal_device_information)
{
- return mavlink_msg_gimbal_device_information_pack_status(system_id, component_id, _status, msg, gimbal_device_information->time_boot_ms, gimbal_device_information->vendor_name, gimbal_device_information->model_name, gimbal_device_information->custom_name, gimbal_device_information->firmware_version, gimbal_device_information->hardware_version, gimbal_device_information->uid, gimbal_device_information->cap_flags, gimbal_device_information->custom_cap_flags, gimbal_device_information->roll_min, gimbal_device_information->roll_max, gimbal_device_information->pitch_min, gimbal_device_information->pitch_max, gimbal_device_information->yaw_min, gimbal_device_information->yaw_max, gimbal_device_information->gimbal_device_id);
+ return mavlink_msg_gimbal_device_information_pack_status(system_id, component_id, _status, msg, gimbal_device_information->time_boot_ms, gimbal_device_information->vendor_name, gimbal_device_information->model_name, gimbal_device_information->custom_name, gimbal_device_information->firmware_version, gimbal_device_information->hardware_version, gimbal_device_information->uid, gimbal_device_information->cap_flags, gimbal_device_information->custom_cap_flags, gimbal_device_information->roll_min, gimbal_device_information->roll_max, gimbal_device_information->pitch_min, gimbal_device_information->pitch_max, gimbal_device_information->yaw_min, gimbal_device_information->yaw_max, gimbal_device_information->gimbal_device_id, gimbal_device_information->cap_flags2);
}
/**
@@ -350,8 +362,8 @@ static inline uint16_t mavlink_msg_gimbal_device_information_encode_status(uint8
* @param vendor_name Name of the gimbal vendor.
* @param model_name Name of the gimbal model.
* @param custom_name Custom name of the gimbal given to it by the user.
- * @param firmware_version Version of the gimbal firmware, encoded as: `(Dev & 0xff) << 24 \| (Patch & 0xff) << 16 \| (Minor & 0xff) << 8 \| (Major & 0xff)`.
- * @param hardware_version Version of the gimbal hardware, encoded as: `(Dev & 0xff) << 24 \| (Patch & 0xff) << 16 \| (Minor & 0xff) << 8 \| (Major & 0xff)`.
+ * @param firmware_version Version of the gimbal firmware, encoded as: `(Dev & 0xff) << 24 + (Patch & 0xff) << 16 + (Minor & 0xff) << 8 + (Major & 0xff)`.
+ * @param hardware_version Version of the gimbal hardware, encoded as: `(Dev & 0xff) << 24 + (Patch & 0xff) << 16 + (Minor & 0xff) << 8 + (Major & 0xff)`.
* @param uid UID of gimbal hardware (0 if unknown).
* @param cap_flags Bitmap of gimbal capability flags.
* @param custom_cap_flags Bitmap for use for gimbal-specific capability flags.
@@ -362,10 +374,11 @@ static inline uint16_t mavlink_msg_gimbal_device_information_encode_status(uint8
* @param yaw_min [rad] Minimum hardware yaw angle (positive: to the right, negative: to the left). NAN if unknown.
* @param yaw_max [rad] Maximum hardware yaw angle (positive: to the right, negative: to the left). NAN if unknown.
* @param gimbal_device_id This field is to be used if the gimbal manager and the gimbal device are the same component and hence have the same component ID. This field is then set to a number between 1-6. If the component ID is separate, this field is not required and must be set to 0.
+ * @param cap_flags2 Extended bitmap of gimbal capability flags (32 bit). For backwards compatibility, the lower 16 bits should also be set in cap_flags. Ground stations should prefer this field if non-zero.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-static inline void mavlink_msg_gimbal_device_information_send(mavlink_channel_t chan, uint32_t time_boot_ms, const char *vendor_name, const char *model_name, const char *custom_name, uint32_t firmware_version, uint32_t hardware_version, uint64_t uid, uint16_t cap_flags, uint16_t custom_cap_flags, float roll_min, float roll_max, float pitch_min, float pitch_max, float yaw_min, float yaw_max, uint8_t gimbal_device_id)
+static inline void mavlink_msg_gimbal_device_information_send(mavlink_channel_t chan, uint32_t time_boot_ms, const char *vendor_name, const char *model_name, const char *custom_name, uint32_t firmware_version, uint32_t hardware_version, uint64_t uid, uint16_t cap_flags, uint16_t custom_cap_flags, float roll_min, float roll_max, float pitch_min, float pitch_max, float yaw_min, float yaw_max, uint8_t gimbal_device_id, uint32_t cap_flags2)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_LEN];
@@ -382,6 +395,7 @@ static inline void mavlink_msg_gimbal_device_information_send(mavlink_channel_t
_mav_put_uint16_t(buf, 44, cap_flags);
_mav_put_uint16_t(buf, 46, custom_cap_flags);
_mav_put_uint8_t(buf, 144, gimbal_device_id);
+ _mav_put_uint32_t(buf, 145, cap_flags2);
_mav_put_char_array(buf, 48, vendor_name, 32);
_mav_put_char_array(buf, 80, model_name, 32);
_mav_put_char_array(buf, 112, custom_name, 32);
@@ -401,6 +415,7 @@ static inline void mavlink_msg_gimbal_device_information_send(mavlink_channel_t
packet.cap_flags = cap_flags;
packet.custom_cap_flags = custom_cap_flags;
packet.gimbal_device_id = gimbal_device_id;
+ packet.cap_flags2 = cap_flags2;
mav_array_assign_char(packet.vendor_name, vendor_name, 32);
mav_array_assign_char(packet.model_name, model_name, 32);
mav_array_assign_char(packet.custom_name, custom_name, 32);
@@ -416,7 +431,7 @@ static inline void mavlink_msg_gimbal_device_information_send(mavlink_channel_t
static inline void mavlink_msg_gimbal_device_information_send_struct(mavlink_channel_t chan, const mavlink_gimbal_device_information_t* gimbal_device_information)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_gimbal_device_information_send(chan, gimbal_device_information->time_boot_ms, gimbal_device_information->vendor_name, gimbal_device_information->model_name, gimbal_device_information->custom_name, gimbal_device_information->firmware_version, gimbal_device_information->hardware_version, gimbal_device_information->uid, gimbal_device_information->cap_flags, gimbal_device_information->custom_cap_flags, gimbal_device_information->roll_min, gimbal_device_information->roll_max, gimbal_device_information->pitch_min, gimbal_device_information->pitch_max, gimbal_device_information->yaw_min, gimbal_device_information->yaw_max, gimbal_device_information->gimbal_device_id);
+ mavlink_msg_gimbal_device_information_send(chan, gimbal_device_information->time_boot_ms, gimbal_device_information->vendor_name, gimbal_device_information->model_name, gimbal_device_information->custom_name, gimbal_device_information->firmware_version, gimbal_device_information->hardware_version, gimbal_device_information->uid, gimbal_device_information->cap_flags, gimbal_device_information->custom_cap_flags, gimbal_device_information->roll_min, gimbal_device_information->roll_max, gimbal_device_information->pitch_min, gimbal_device_information->pitch_max, gimbal_device_information->yaw_min, gimbal_device_information->yaw_max, gimbal_device_information->gimbal_device_id, gimbal_device_information->cap_flags2);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION, (const char *)gimbal_device_information, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_CRC);
#endif
@@ -430,7 +445,7 @@ static inline void mavlink_msg_gimbal_device_information_send_struct(mavlink_cha
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_gimbal_device_information_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, const char *vendor_name, const char *model_name, const char *custom_name, uint32_t firmware_version, uint32_t hardware_version, uint64_t uid, uint16_t cap_flags, uint16_t custom_cap_flags, float roll_min, float roll_max, float pitch_min, float pitch_max, float yaw_min, float yaw_max, uint8_t gimbal_device_id)
+static inline void mavlink_msg_gimbal_device_information_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, const char *vendor_name, const char *model_name, const char *custom_name, uint32_t firmware_version, uint32_t hardware_version, uint64_t uid, uint16_t cap_flags, uint16_t custom_cap_flags, float roll_min, float roll_max, float pitch_min, float pitch_max, float yaw_min, float yaw_max, uint8_t gimbal_device_id, uint32_t cap_flags2)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
@@ -447,6 +462,7 @@ static inline void mavlink_msg_gimbal_device_information_send_buf(mavlink_messag
_mav_put_uint16_t(buf, 44, cap_flags);
_mav_put_uint16_t(buf, 46, custom_cap_flags);
_mav_put_uint8_t(buf, 144, gimbal_device_id);
+ _mav_put_uint32_t(buf, 145, cap_flags2);
_mav_put_char_array(buf, 48, vendor_name, 32);
_mav_put_char_array(buf, 80, model_name, 32);
_mav_put_char_array(buf, 112, custom_name, 32);
@@ -466,6 +482,7 @@ static inline void mavlink_msg_gimbal_device_information_send_buf(mavlink_messag
packet->cap_flags = cap_flags;
packet->custom_cap_flags = custom_cap_flags;
packet->gimbal_device_id = gimbal_device_id;
+ packet->cap_flags2 = cap_flags2;
mav_array_assign_char(packet->vendor_name, vendor_name, 32);
mav_array_assign_char(packet->model_name, model_name, 32);
mav_array_assign_char(packet->custom_name, custom_name, 32);
@@ -522,7 +539,7 @@ static inline uint16_t mavlink_msg_gimbal_device_information_get_custom_name(con
/**
* @brief Get field firmware_version from gimbal_device_information message
*
- * @return Version of the gimbal firmware, encoded as: `(Dev & 0xff) << 24 \| (Patch & 0xff) << 16 \| (Minor & 0xff) << 8 \| (Major & 0xff)`.
+ * @return Version of the gimbal firmware, encoded as: `(Dev & 0xff) << 24 + (Patch & 0xff) << 16 + (Minor & 0xff) << 8 + (Major & 0xff)`.
*/
static inline uint32_t mavlink_msg_gimbal_device_information_get_firmware_version(const mavlink_message_t* msg)
{
@@ -532,7 +549,7 @@ static inline uint32_t mavlink_msg_gimbal_device_information_get_firmware_versio
/**
* @brief Get field hardware_version from gimbal_device_information message
*
- * @return Version of the gimbal hardware, encoded as: `(Dev & 0xff) << 24 \| (Patch & 0xff) << 16 \| (Minor & 0xff) << 8 \| (Major & 0xff)`.
+ * @return Version of the gimbal hardware, encoded as: `(Dev & 0xff) << 24 + (Patch & 0xff) << 16 + (Minor & 0xff) << 8 + (Major & 0xff)`.
*/
static inline uint32_t mavlink_msg_gimbal_device_information_get_hardware_version(const mavlink_message_t* msg)
{
@@ -639,6 +656,16 @@ static inline uint8_t mavlink_msg_gimbal_device_information_get_gimbal_device_id
return _MAV_RETURN_uint8_t(msg, 144);
}
+/**
+ * @brief Get field cap_flags2 from gimbal_device_information message
+ *
+ * @return Extended bitmap of gimbal capability flags (32 bit). For backwards compatibility, the lower 16 bits should also be set in cap_flags. Ground stations should prefer this field if non-zero.
+ */
+static inline uint32_t mavlink_msg_gimbal_device_information_get_cap_flags2(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint32_t(msg, 145);
+}
+
/**
* @brief Decode a gimbal_device_information message into a struct
*
@@ -664,6 +691,7 @@ static inline void mavlink_msg_gimbal_device_information_decode(const mavlink_me
mavlink_msg_gimbal_device_information_get_model_name(msg, gimbal_device_information->model_name);
mavlink_msg_gimbal_device_information_get_custom_name(msg, gimbal_device_information->custom_name);
gimbal_device_information->gimbal_device_id = mavlink_msg_gimbal_device_information_get_gimbal_device_id(msg);
+ gimbal_device_information->cap_flags2 = mavlink_msg_gimbal_device_information_get_cap_flags2(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_LEN? msg->len : MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_LEN;
memset(gimbal_device_information, 0, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_LEN);
diff --git a/lib/main/MAVLink/common/mavlink_msg_global_position_sensor.h b/lib/main/MAVLink/common/mavlink_msg_global_position_sensor.h
new file mode 100644
index 00000000000..3c6f8340d61
--- /dev/null
+++ b/lib/main/MAVLink/common/mavlink_msg_global_position_sensor.h
@@ -0,0 +1,596 @@
+#pragma once
+// MESSAGE GLOBAL_POSITION_SENSOR PACKING
+
+#define MAVLINK_MSG_ID_GLOBAL_POSITION_SENSOR 296
+
+
+typedef struct __mavlink_global_position_sensor_t {
+ uint64_t time_usec; /*< [us] Timestamp of message transmission (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/
+ uint32_t processing_time; /*< [us] The time spent in processing the sensor data that is the basis for this position. The recipient can use this to improve time alignment of the data. This is the time between measurement (e.g. camera exposure time) and transmission of this message. Set to NaN if not known.*/
+ int32_t lat; /*< [degE7] Latitude (WGS84)*/
+ int32_t lon; /*< [degE7] Longitude (WGS84)*/
+ float alt_ellipsoid; /*< [m] Altitude (WGS84 elipsoid), preferred if available*/
+ float alt; /*< [m] Altitude (MSL - position-system specific value) use if no alt_ellipsoid available*/
+ float eph; /*< [m] Standard deviation of horizontal position error*/
+ float epv; /*< [m] Standard deviation of vertical position error*/
+ uint8_t target_system; /*< System ID (ID of target system, normally autopilot and ground station).*/
+ uint8_t target_component; /*< Component ID (normally 0 for broadcast).*/
+ uint8_t id; /*< Sensor ID*/
+ uint8_t source; /*< Source of position/estimate (such as GNSS, estimator, etc.)*/
+ uint8_t flags; /*< Status flags*/
+} mavlink_global_position_sensor_t;
+
+#define MAVLINK_MSG_ID_GLOBAL_POSITION_SENSOR_LEN 41
+#define MAVLINK_MSG_ID_GLOBAL_POSITION_SENSOR_MIN_LEN 41
+#define MAVLINK_MSG_ID_296_LEN 41
+#define MAVLINK_MSG_ID_296_MIN_LEN 41
+
+#define MAVLINK_MSG_ID_GLOBAL_POSITION_SENSOR_CRC 158
+#define MAVLINK_MSG_ID_296_CRC 158
+
+
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_SENSOR { \
+ 296, \
+ "GLOBAL_POSITION_SENSOR", \
+ 13, \
+ { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_global_position_sensor_t, target_system) }, \
+ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 37, offsetof(mavlink_global_position_sensor_t, target_component) }, \
+ { "id", NULL, MAVLINK_TYPE_UINT8_T, 0, 38, offsetof(mavlink_global_position_sensor_t, id) }, \
+ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_global_position_sensor_t, time_usec) }, \
+ { "processing_time", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_global_position_sensor_t, processing_time) }, \
+ { "source", NULL, MAVLINK_TYPE_UINT8_T, 0, 39, offsetof(mavlink_global_position_sensor_t, source) }, \
+ { "flags", NULL, MAVLINK_TYPE_UINT8_T, 0, 40, offsetof(mavlink_global_position_sensor_t, flags) }, \
+ { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_global_position_sensor_t, lat) }, \
+ { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_global_position_sensor_t, lon) }, \
+ { "alt_ellipsoid", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_global_position_sensor_t, alt_ellipsoid) }, \
+ { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_global_position_sensor_t, alt) }, \
+ { "eph", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_global_position_sensor_t, eph) }, \
+ { "epv", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_global_position_sensor_t, epv) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_SENSOR { \
+ "GLOBAL_POSITION_SENSOR", \
+ 13, \
+ { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_global_position_sensor_t, target_system) }, \
+ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 37, offsetof(mavlink_global_position_sensor_t, target_component) }, \
+ { "id", NULL, MAVLINK_TYPE_UINT8_T, 0, 38, offsetof(mavlink_global_position_sensor_t, id) }, \
+ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_global_position_sensor_t, time_usec) }, \
+ { "processing_time", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_global_position_sensor_t, processing_time) }, \
+ { "source", NULL, MAVLINK_TYPE_UINT8_T, 0, 39, offsetof(mavlink_global_position_sensor_t, source) }, \
+ { "flags", NULL, MAVLINK_TYPE_UINT8_T, 0, 40, offsetof(mavlink_global_position_sensor_t, flags) }, \
+ { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_global_position_sensor_t, lat) }, \
+ { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_global_position_sensor_t, lon) }, \
+ { "alt_ellipsoid", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_global_position_sensor_t, alt_ellipsoid) }, \
+ { "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_global_position_sensor_t, alt) }, \
+ { "eph", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_global_position_sensor_t, eph) }, \
+ { "epv", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_global_position_sensor_t, epv) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a global_position_sensor 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 target_system System ID (ID of target system, normally autopilot and ground station).
+ * @param target_component Component ID (normally 0 for broadcast).
+ * @param id Sensor ID
+ * @param time_usec [us] Timestamp of message transmission (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
+ * @param processing_time [us] The time spent in processing the sensor data that is the basis for this position. The recipient can use this to improve time alignment of the data. This is the time between measurement (e.g. camera exposure time) and transmission of this message. Set to NaN if not known.
+ * @param source Source of position/estimate (such as GNSS, estimator, etc.)
+ * @param flags Status flags
+ * @param lat [degE7] Latitude (WGS84)
+ * @param lon [degE7] Longitude (WGS84)
+ * @param alt_ellipsoid [m] Altitude (WGS84 elipsoid), preferred if available
+ * @param alt [m] Altitude (MSL - position-system specific value) use if no alt_ellipsoid available
+ * @param eph [m] Standard deviation of horizontal position error
+ * @param epv [m] Standard deviation of vertical position error
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_global_position_sensor_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint8_t target_system, uint8_t target_component, uint8_t id, uint64_t time_usec, uint32_t processing_time, uint8_t source, uint8_t flags, int32_t lat, int32_t lon, float alt_ellipsoid, float alt, float eph, float epv)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_GLOBAL_POSITION_SENSOR_LEN];
+ _mav_put_uint64_t(buf, 0, time_usec);
+ _mav_put_uint32_t(buf, 8, processing_time);
+ _mav_put_int32_t(buf, 12, lat);
+ _mav_put_int32_t(buf, 16, lon);
+ _mav_put_float(buf, 20, alt_ellipsoid);
+ _mav_put_float(buf, 24, alt);
+ _mav_put_float(buf, 28, eph);
+ _mav_put_float(buf, 32, epv);
+ _mav_put_uint8_t(buf, 36, target_system);
+ _mav_put_uint8_t(buf, 37, target_component);
+ _mav_put_uint8_t(buf, 38, id);
+ _mav_put_uint8_t(buf, 39, source);
+ _mav_put_uint8_t(buf, 40, flags);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GLOBAL_POSITION_SENSOR_LEN);
+#else
+ mavlink_global_position_sensor_t packet;
+ packet.time_usec = time_usec;
+ packet.processing_time = processing_time;
+ packet.lat = lat;
+ packet.lon = lon;
+ packet.alt_ellipsoid = alt_ellipsoid;
+ packet.alt = alt;
+ packet.eph = eph;
+ packet.epv = epv;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.id = id;
+ packet.source = source;
+ packet.flags = flags;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GLOBAL_POSITION_SENSOR_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION_SENSOR;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GLOBAL_POSITION_SENSOR_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_SENSOR_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_SENSOR_CRC);
+}
+
+/**
+ * @brief Pack a global_position_sensor 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 target_system System ID (ID of target system, normally autopilot and ground station).
+ * @param target_component Component ID (normally 0 for broadcast).
+ * @param id Sensor ID
+ * @param time_usec [us] Timestamp of message transmission (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
+ * @param processing_time [us] The time spent in processing the sensor data that is the basis for this position. The recipient can use this to improve time alignment of the data. This is the time between measurement (e.g. camera exposure time) and transmission of this message. Set to NaN if not known.
+ * @param source Source of position/estimate (such as GNSS, estimator, etc.)
+ * @param flags Status flags
+ * @param lat [degE7] Latitude (WGS84)
+ * @param lon [degE7] Longitude (WGS84)
+ * @param alt_ellipsoid [m] Altitude (WGS84 elipsoid), preferred if available
+ * @param alt [m] Altitude (MSL - position-system specific value) use if no alt_ellipsoid available
+ * @param eph [m] Standard deviation of horizontal position error
+ * @param epv [m] Standard deviation of vertical position error
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_global_position_sensor_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ uint8_t target_system, uint8_t target_component, uint8_t id, uint64_t time_usec, uint32_t processing_time, uint8_t source, uint8_t flags, int32_t lat, int32_t lon, float alt_ellipsoid, float alt, float eph, float epv)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_GLOBAL_POSITION_SENSOR_LEN];
+ _mav_put_uint64_t(buf, 0, time_usec);
+ _mav_put_uint32_t(buf, 8, processing_time);
+ _mav_put_int32_t(buf, 12, lat);
+ _mav_put_int32_t(buf, 16, lon);
+ _mav_put_float(buf, 20, alt_ellipsoid);
+ _mav_put_float(buf, 24, alt);
+ _mav_put_float(buf, 28, eph);
+ _mav_put_float(buf, 32, epv);
+ _mav_put_uint8_t(buf, 36, target_system);
+ _mav_put_uint8_t(buf, 37, target_component);
+ _mav_put_uint8_t(buf, 38, id);
+ _mav_put_uint8_t(buf, 39, source);
+ _mav_put_uint8_t(buf, 40, flags);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GLOBAL_POSITION_SENSOR_LEN);
+#else
+ mavlink_global_position_sensor_t packet;
+ packet.time_usec = time_usec;
+ packet.processing_time = processing_time;
+ packet.lat = lat;
+ packet.lon = lon;
+ packet.alt_ellipsoid = alt_ellipsoid;
+ packet.alt = alt;
+ packet.eph = eph;
+ packet.epv = epv;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.id = id;
+ packet.source = source;
+ packet.flags = flags;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GLOBAL_POSITION_SENSOR_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION_SENSOR;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_GLOBAL_POSITION_SENSOR_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_SENSOR_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_SENSOR_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_GLOBAL_POSITION_SENSOR_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_SENSOR_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a global_position_sensor 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 target_system System ID (ID of target system, normally autopilot and ground station).
+ * @param target_component Component ID (normally 0 for broadcast).
+ * @param id Sensor ID
+ * @param time_usec [us] Timestamp of message transmission (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
+ * @param processing_time [us] The time spent in processing the sensor data that is the basis for this position. The recipient can use this to improve time alignment of the data. This is the time between measurement (e.g. camera exposure time) and transmission of this message. Set to NaN if not known.
+ * @param source Source of position/estimate (such as GNSS, estimator, etc.)
+ * @param flags Status flags
+ * @param lat [degE7] Latitude (WGS84)
+ * @param lon [degE7] Longitude (WGS84)
+ * @param alt_ellipsoid [m] Altitude (WGS84 elipsoid), preferred if available
+ * @param alt [m] Altitude (MSL - position-system specific value) use if no alt_ellipsoid available
+ * @param eph [m] Standard deviation of horizontal position error
+ * @param epv [m] Standard deviation of vertical position error
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_global_position_sensor_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint8_t target_system,uint8_t target_component,uint8_t id,uint64_t time_usec,uint32_t processing_time,uint8_t source,uint8_t flags,int32_t lat,int32_t lon,float alt_ellipsoid,float alt,float eph,float epv)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_GLOBAL_POSITION_SENSOR_LEN];
+ _mav_put_uint64_t(buf, 0, time_usec);
+ _mav_put_uint32_t(buf, 8, processing_time);
+ _mav_put_int32_t(buf, 12, lat);
+ _mav_put_int32_t(buf, 16, lon);
+ _mav_put_float(buf, 20, alt_ellipsoid);
+ _mav_put_float(buf, 24, alt);
+ _mav_put_float(buf, 28, eph);
+ _mav_put_float(buf, 32, epv);
+ _mav_put_uint8_t(buf, 36, target_system);
+ _mav_put_uint8_t(buf, 37, target_component);
+ _mav_put_uint8_t(buf, 38, id);
+ _mav_put_uint8_t(buf, 39, source);
+ _mav_put_uint8_t(buf, 40, flags);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GLOBAL_POSITION_SENSOR_LEN);
+#else
+ mavlink_global_position_sensor_t packet;
+ packet.time_usec = time_usec;
+ packet.processing_time = processing_time;
+ packet.lat = lat;
+ packet.lon = lon;
+ packet.alt_ellipsoid = alt_ellipsoid;
+ packet.alt = alt;
+ packet.eph = eph;
+ packet.epv = epv;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.id = id;
+ packet.source = source;
+ packet.flags = flags;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GLOBAL_POSITION_SENSOR_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION_SENSOR;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GLOBAL_POSITION_SENSOR_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_SENSOR_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_SENSOR_CRC);
+}
+
+/**
+ * @brief Encode a global_position_sensor 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 global_position_sensor C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_global_position_sensor_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_global_position_sensor_t* global_position_sensor)
+{
+ return mavlink_msg_global_position_sensor_pack(system_id, component_id, msg, global_position_sensor->target_system, global_position_sensor->target_component, global_position_sensor->id, global_position_sensor->time_usec, global_position_sensor->processing_time, global_position_sensor->source, global_position_sensor->flags, global_position_sensor->lat, global_position_sensor->lon, global_position_sensor->alt_ellipsoid, global_position_sensor->alt, global_position_sensor->eph, global_position_sensor->epv);
+}
+
+/**
+ * @brief Encode a global_position_sensor 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 global_position_sensor C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_global_position_sensor_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_global_position_sensor_t* global_position_sensor)
+{
+ return mavlink_msg_global_position_sensor_pack_chan(system_id, component_id, chan, msg, global_position_sensor->target_system, global_position_sensor->target_component, global_position_sensor->id, global_position_sensor->time_usec, global_position_sensor->processing_time, global_position_sensor->source, global_position_sensor->flags, global_position_sensor->lat, global_position_sensor->lon, global_position_sensor->alt_ellipsoid, global_position_sensor->alt, global_position_sensor->eph, global_position_sensor->epv);
+}
+
+/**
+ * @brief Encode a global_position_sensor 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 global_position_sensor C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_global_position_sensor_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_global_position_sensor_t* global_position_sensor)
+{
+ return mavlink_msg_global_position_sensor_pack_status(system_id, component_id, _status, msg, global_position_sensor->target_system, global_position_sensor->target_component, global_position_sensor->id, global_position_sensor->time_usec, global_position_sensor->processing_time, global_position_sensor->source, global_position_sensor->flags, global_position_sensor->lat, global_position_sensor->lon, global_position_sensor->alt_ellipsoid, global_position_sensor->alt, global_position_sensor->eph, global_position_sensor->epv);
+}
+
+/**
+ * @brief Send a global_position_sensor message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param target_system System ID (ID of target system, normally autopilot and ground station).
+ * @param target_component Component ID (normally 0 for broadcast).
+ * @param id Sensor ID
+ * @param time_usec [us] Timestamp of message transmission (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
+ * @param processing_time [us] The time spent in processing the sensor data that is the basis for this position. The recipient can use this to improve time alignment of the data. This is the time between measurement (e.g. camera exposure time) and transmission of this message. Set to NaN if not known.
+ * @param source Source of position/estimate (such as GNSS, estimator, etc.)
+ * @param flags Status flags
+ * @param lat [degE7] Latitude (WGS84)
+ * @param lon [degE7] Longitude (WGS84)
+ * @param alt_ellipsoid [m] Altitude (WGS84 elipsoid), preferred if available
+ * @param alt [m] Altitude (MSL - position-system specific value) use if no alt_ellipsoid available
+ * @param eph [m] Standard deviation of horizontal position error
+ * @param epv [m] Standard deviation of vertical position error
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_global_position_sensor_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t id, uint64_t time_usec, uint32_t processing_time, uint8_t source, uint8_t flags, int32_t lat, int32_t lon, float alt_ellipsoid, float alt, float eph, float epv)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_GLOBAL_POSITION_SENSOR_LEN];
+ _mav_put_uint64_t(buf, 0, time_usec);
+ _mav_put_uint32_t(buf, 8, processing_time);
+ _mav_put_int32_t(buf, 12, lat);
+ _mav_put_int32_t(buf, 16, lon);
+ _mav_put_float(buf, 20, alt_ellipsoid);
+ _mav_put_float(buf, 24, alt);
+ _mav_put_float(buf, 28, eph);
+ _mav_put_float(buf, 32, epv);
+ _mav_put_uint8_t(buf, 36, target_system);
+ _mav_put_uint8_t(buf, 37, target_component);
+ _mav_put_uint8_t(buf, 38, id);
+ _mav_put_uint8_t(buf, 39, source);
+ _mav_put_uint8_t(buf, 40, flags);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_SENSOR, buf, MAVLINK_MSG_ID_GLOBAL_POSITION_SENSOR_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_SENSOR_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_SENSOR_CRC);
+#else
+ mavlink_global_position_sensor_t packet;
+ packet.time_usec = time_usec;
+ packet.processing_time = processing_time;
+ packet.lat = lat;
+ packet.lon = lon;
+ packet.alt_ellipsoid = alt_ellipsoid;
+ packet.alt = alt;
+ packet.eph = eph;
+ packet.epv = epv;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.id = id;
+ packet.source = source;
+ packet.flags = flags;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_SENSOR, (const char *)&packet, MAVLINK_MSG_ID_GLOBAL_POSITION_SENSOR_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_SENSOR_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_SENSOR_CRC);
+#endif
+}
+
+/**
+ * @brief Send a global_position_sensor message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_global_position_sensor_send_struct(mavlink_channel_t chan, const mavlink_global_position_sensor_t* global_position_sensor)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_global_position_sensor_send(chan, global_position_sensor->target_system, global_position_sensor->target_component, global_position_sensor->id, global_position_sensor->time_usec, global_position_sensor->processing_time, global_position_sensor->source, global_position_sensor->flags, global_position_sensor->lat, global_position_sensor->lon, global_position_sensor->alt_ellipsoid, global_position_sensor->alt, global_position_sensor->eph, global_position_sensor->epv);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_SENSOR, (const char *)global_position_sensor, MAVLINK_MSG_ID_GLOBAL_POSITION_SENSOR_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_SENSOR_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_SENSOR_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_GLOBAL_POSITION_SENSOR_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_global_position_sensor_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t id, uint64_t time_usec, uint32_t processing_time, uint8_t source, uint8_t flags, int32_t lat, int32_t lon, float alt_ellipsoid, float alt, float eph, float epv)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint64_t(buf, 0, time_usec);
+ _mav_put_uint32_t(buf, 8, processing_time);
+ _mav_put_int32_t(buf, 12, lat);
+ _mav_put_int32_t(buf, 16, lon);
+ _mav_put_float(buf, 20, alt_ellipsoid);
+ _mav_put_float(buf, 24, alt);
+ _mav_put_float(buf, 28, eph);
+ _mav_put_float(buf, 32, epv);
+ _mav_put_uint8_t(buf, 36, target_system);
+ _mav_put_uint8_t(buf, 37, target_component);
+ _mav_put_uint8_t(buf, 38, id);
+ _mav_put_uint8_t(buf, 39, source);
+ _mav_put_uint8_t(buf, 40, flags);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_SENSOR, buf, MAVLINK_MSG_ID_GLOBAL_POSITION_SENSOR_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_SENSOR_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_SENSOR_CRC);
+#else
+ mavlink_global_position_sensor_t *packet = (mavlink_global_position_sensor_t *)msgbuf;
+ packet->time_usec = time_usec;
+ packet->processing_time = processing_time;
+ packet->lat = lat;
+ packet->lon = lon;
+ packet->alt_ellipsoid = alt_ellipsoid;
+ packet->alt = alt;
+ packet->eph = eph;
+ packet->epv = epv;
+ packet->target_system = target_system;
+ packet->target_component = target_component;
+ packet->id = id;
+ packet->source = source;
+ packet->flags = flags;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_SENSOR, (const char *)packet, MAVLINK_MSG_ID_GLOBAL_POSITION_SENSOR_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_SENSOR_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_SENSOR_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE GLOBAL_POSITION_SENSOR UNPACKING
+
+
+/**
+ * @brief Get field target_system from global_position_sensor message
+ *
+ * @return System ID (ID of target system, normally autopilot and ground station).
+ */
+static inline uint8_t mavlink_msg_global_position_sensor_get_target_system(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 36);
+}
+
+/**
+ * @brief Get field target_component from global_position_sensor message
+ *
+ * @return Component ID (normally 0 for broadcast).
+ */
+static inline uint8_t mavlink_msg_global_position_sensor_get_target_component(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 37);
+}
+
+/**
+ * @brief Get field id from global_position_sensor message
+ *
+ * @return Sensor ID
+ */
+static inline uint8_t mavlink_msg_global_position_sensor_get_id(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 38);
+}
+
+/**
+ * @brief Get field time_usec from global_position_sensor message
+ *
+ * @return [us] Timestamp of message transmission (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
+ */
+static inline uint64_t mavlink_msg_global_position_sensor_get_time_usec(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint64_t(msg, 0);
+}
+
+/**
+ * @brief Get field processing_time from global_position_sensor message
+ *
+ * @return [us] The time spent in processing the sensor data that is the basis for this position. The recipient can use this to improve time alignment of the data. This is the time between measurement (e.g. camera exposure time) and transmission of this message. Set to NaN if not known.
+ */
+static inline uint32_t mavlink_msg_global_position_sensor_get_processing_time(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint32_t(msg, 8);
+}
+
+/**
+ * @brief Get field source from global_position_sensor message
+ *
+ * @return Source of position/estimate (such as GNSS, estimator, etc.)
+ */
+static inline uint8_t mavlink_msg_global_position_sensor_get_source(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 39);
+}
+
+/**
+ * @brief Get field flags from global_position_sensor message
+ *
+ * @return Status flags
+ */
+static inline uint8_t mavlink_msg_global_position_sensor_get_flags(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 40);
+}
+
+/**
+ * @brief Get field lat from global_position_sensor message
+ *
+ * @return [degE7] Latitude (WGS84)
+ */
+static inline int32_t mavlink_msg_global_position_sensor_get_lat(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_int32_t(msg, 12);
+}
+
+/**
+ * @brief Get field lon from global_position_sensor message
+ *
+ * @return [degE7] Longitude (WGS84)
+ */
+static inline int32_t mavlink_msg_global_position_sensor_get_lon(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_int32_t(msg, 16);
+}
+
+/**
+ * @brief Get field alt_ellipsoid from global_position_sensor message
+ *
+ * @return [m] Altitude (WGS84 elipsoid), preferred if available
+ */
+static inline float mavlink_msg_global_position_sensor_get_alt_ellipsoid(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 20);
+}
+
+/**
+ * @brief Get field alt from global_position_sensor message
+ *
+ * @return [m] Altitude (MSL - position-system specific value) use if no alt_ellipsoid available
+ */
+static inline float mavlink_msg_global_position_sensor_get_alt(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 24);
+}
+
+/**
+ * @brief Get field eph from global_position_sensor message
+ *
+ * @return [m] Standard deviation of horizontal position error
+ */
+static inline float mavlink_msg_global_position_sensor_get_eph(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 28);
+}
+
+/**
+ * @brief Get field epv from global_position_sensor message
+ *
+ * @return [m] Standard deviation of vertical position error
+ */
+static inline float mavlink_msg_global_position_sensor_get_epv(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 32);
+}
+
+/**
+ * @brief Decode a global_position_sensor message into a struct
+ *
+ * @param msg The message to decode
+ * @param global_position_sensor C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_global_position_sensor_decode(const mavlink_message_t* msg, mavlink_global_position_sensor_t* global_position_sensor)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ global_position_sensor->time_usec = mavlink_msg_global_position_sensor_get_time_usec(msg);
+ global_position_sensor->processing_time = mavlink_msg_global_position_sensor_get_processing_time(msg);
+ global_position_sensor->lat = mavlink_msg_global_position_sensor_get_lat(msg);
+ global_position_sensor->lon = mavlink_msg_global_position_sensor_get_lon(msg);
+ global_position_sensor->alt_ellipsoid = mavlink_msg_global_position_sensor_get_alt_ellipsoid(msg);
+ global_position_sensor->alt = mavlink_msg_global_position_sensor_get_alt(msg);
+ global_position_sensor->eph = mavlink_msg_global_position_sensor_get_eph(msg);
+ global_position_sensor->epv = mavlink_msg_global_position_sensor_get_epv(msg);
+ global_position_sensor->target_system = mavlink_msg_global_position_sensor_get_target_system(msg);
+ global_position_sensor->target_component = mavlink_msg_global_position_sensor_get_target_component(msg);
+ global_position_sensor->id = mavlink_msg_global_position_sensor_get_id(msg);
+ global_position_sensor->source = mavlink_msg_global_position_sensor_get_source(msg);
+ global_position_sensor->flags = mavlink_msg_global_position_sensor_get_flags(msg);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_GLOBAL_POSITION_SENSOR_LEN? msg->len : MAVLINK_MSG_ID_GLOBAL_POSITION_SENSOR_LEN;
+ memset(global_position_sensor, 0, MAVLINK_MSG_ID_GLOBAL_POSITION_SENSOR_LEN);
+ memcpy(global_position_sensor, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/common/mavlink_msg_manual_control.h b/lib/main/MAVLink/common/mavlink_msg_manual_control.h
index 69c1139d01a..40bc5a10492 100755
--- a/lib/main/MAVLink/common/mavlink_msg_manual_control.h
+++ b/lib/main/MAVLink/common/mavlink_msg_manual_control.h
@@ -8,7 +8,7 @@ typedef struct __mavlink_manual_control_t {
int16_t x; /*< X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle.*/
int16_t y; /*< Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle.*/
int16_t z; /*< Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. Positive values are positive thrust, negative values are negative thrust.*/
- int16_t r; /*< R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle.*/
+ int16_t r; /*< R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with clockwise being 1000 and counter-clockwise being -1000, and the yaw of a vehicle.*/
uint16_t buttons; /*< A bitfield corresponding to the joystick buttons' 0-15 current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1.*/
uint8_t target; /*< The system to be controlled.*/
uint16_t buttons2; /*< A bitfield corresponding to the joystick buttons' 16-31 current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 16.*/
@@ -90,7 +90,7 @@ typedef struct __mavlink_manual_control_t {
* @param x X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle.
* @param y Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle.
* @param z Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. Positive values are positive thrust, negative values are negative thrust.
- * @param r R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle.
+ * @param r R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with clockwise being 1000 and counter-clockwise being -1000, and the yaw of a vehicle.
* @param buttons A bitfield corresponding to the joystick buttons' 0-15 current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1.
* @param buttons2 A bitfield corresponding to the joystick buttons' 16-31 current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 16.
* @param enabled_extensions Set bits to 1 to indicate which of the following extension fields contain valid data: bit 0: pitch, bit 1: roll, bit 2: aux1, bit 3: aux2, bit 4: aux3, bit 5: aux4, bit 6: aux5, bit 7: aux6
@@ -164,7 +164,7 @@ static inline uint16_t mavlink_msg_manual_control_pack(uint8_t system_id, uint8_
* @param x X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle.
* @param y Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle.
* @param z Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. Positive values are positive thrust, negative values are negative thrust.
- * @param r R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle.
+ * @param r R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with clockwise being 1000 and counter-clockwise being -1000, and the yaw of a vehicle.
* @param buttons A bitfield corresponding to the joystick buttons' 0-15 current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1.
* @param buttons2 A bitfield corresponding to the joystick buttons' 16-31 current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 16.
* @param enabled_extensions Set bits to 1 to indicate which of the following extension fields contain valid data: bit 0: pitch, bit 1: roll, bit 2: aux1, bit 3: aux2, bit 4: aux3, bit 5: aux4, bit 6: aux5, bit 7: aux6
@@ -241,7 +241,7 @@ static inline uint16_t mavlink_msg_manual_control_pack_status(uint8_t system_id,
* @param x X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle.
* @param y Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle.
* @param z Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. Positive values are positive thrust, negative values are negative thrust.
- * @param r R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle.
+ * @param r R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with clockwise being 1000 and counter-clockwise being -1000, and the yaw of a vehicle.
* @param buttons A bitfield corresponding to the joystick buttons' 0-15 current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1.
* @param buttons2 A bitfield corresponding to the joystick buttons' 16-31 current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 16.
* @param enabled_extensions Set bits to 1 to indicate which of the following extension fields contain valid data: bit 0: pitch, bit 1: roll, bit 2: aux1, bit 3: aux2, bit 4: aux3, bit 5: aux4, bit 6: aux5, bit 7: aux6
@@ -354,7 +354,7 @@ static inline uint16_t mavlink_msg_manual_control_encode_status(uint8_t system_i
* @param x X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle.
* @param y Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle.
* @param z Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. Positive values are positive thrust, negative values are negative thrust.
- * @param r R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle.
+ * @param r R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with clockwise being 1000 and counter-clockwise being -1000, and the yaw of a vehicle.
* @param buttons A bitfield corresponding to the joystick buttons' 0-15 current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1.
* @param buttons2 A bitfield corresponding to the joystick buttons' 16-31 current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 16.
* @param enabled_extensions Set bits to 1 to indicate which of the following extension fields contain valid data: bit 0: pitch, bit 1: roll, bit 2: aux1, bit 3: aux2, bit 4: aux3, bit 5: aux4, bit 6: aux5, bit 7: aux6
@@ -530,7 +530,7 @@ static inline int16_t mavlink_msg_manual_control_get_z(const mavlink_message_t*
/**
* @brief Get field r from manual_control message
*
- * @return R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle.
+ * @return R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with clockwise being 1000 and counter-clockwise being -1000, and the yaw of a vehicle.
*/
static inline int16_t mavlink_msg_manual_control_get_r(const mavlink_message_t* msg)
{
diff --git a/lib/main/MAVLink/common/mavlink_msg_onboard_computer_status.h b/lib/main/MAVLink/common/mavlink_msg_onboard_computer_status.h
index bb191e5a356..008aac31448 100644
--- a/lib/main/MAVLink/common/mavlink_msg_onboard_computer_status.h
+++ b/lib/main/MAVLink/common/mavlink_msg_onboard_computer_status.h
@@ -25,11 +25,12 @@ typedef struct __mavlink_onboard_computer_status_t {
uint8_t gpu_combined[10]; /*< Combined GPU usage as the last 10 slices of 100 MS (a histogram). This allows to identify spikes in load that max out the system, but only for a short amount of time. A value of UINT8_MAX implies the field is unused.*/
int8_t temperature_board; /*< [degC] Temperature of the board. A value of INT8_MAX implies the field is unused.*/
int8_t temperature_core[8]; /*< [degC] Temperature of the CPU core. A value of INT8_MAX implies the field is unused.*/
+ uint16_t status_flags; /*< Bitmap of status flags.*/
} mavlink_onboard_computer_status_t;
-#define MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS_LEN 238
+#define MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS_LEN 240
#define MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS_MIN_LEN 238
-#define MAVLINK_MSG_ID_390_LEN 238
+#define MAVLINK_MSG_ID_390_LEN 240
#define MAVLINK_MSG_ID_390_MIN_LEN 238
#define MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS_CRC 156
@@ -54,7 +55,7 @@ typedef struct __mavlink_onboard_computer_status_t {
#define MAVLINK_MESSAGE_INFO_ONBOARD_COMPUTER_STATUS { \
390, \
"ONBOARD_COMPUTER_STATUS", \
- 20, \
+ 21, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_onboard_computer_status_t, time_usec) }, \
{ "uptime", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_onboard_computer_status_t, uptime) }, \
{ "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 196, offsetof(mavlink_onboard_computer_status_t, type) }, \
@@ -75,12 +76,13 @@ typedef struct __mavlink_onboard_computer_status_t {
{ "link_rx_rate", NULL, MAVLINK_TYPE_UINT32_T, 6, 116, offsetof(mavlink_onboard_computer_status_t, link_rx_rate) }, \
{ "link_tx_max", NULL, MAVLINK_TYPE_UINT32_T, 6, 140, offsetof(mavlink_onboard_computer_status_t, link_tx_max) }, \
{ "link_rx_max", NULL, MAVLINK_TYPE_UINT32_T, 6, 164, offsetof(mavlink_onboard_computer_status_t, link_rx_max) }, \
+ { "status_flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 238, offsetof(mavlink_onboard_computer_status_t, status_flags) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_ONBOARD_COMPUTER_STATUS { \
"ONBOARD_COMPUTER_STATUS", \
- 20, \
+ 21, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_onboard_computer_status_t, time_usec) }, \
{ "uptime", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_onboard_computer_status_t, uptime) }, \
{ "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 196, offsetof(mavlink_onboard_computer_status_t, type) }, \
@@ -101,6 +103,7 @@ typedef struct __mavlink_onboard_computer_status_t {
{ "link_rx_rate", NULL, MAVLINK_TYPE_UINT32_T, 6, 116, offsetof(mavlink_onboard_computer_status_t, link_rx_rate) }, \
{ "link_tx_max", NULL, MAVLINK_TYPE_UINT32_T, 6, 140, offsetof(mavlink_onboard_computer_status_t, link_tx_max) }, \
{ "link_rx_max", NULL, MAVLINK_TYPE_UINT32_T, 6, 164, offsetof(mavlink_onboard_computer_status_t, link_rx_max) }, \
+ { "status_flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 238, offsetof(mavlink_onboard_computer_status_t, status_flags) }, \
} \
}
#endif
@@ -131,10 +134,11 @@ typedef struct __mavlink_onboard_computer_status_t {
* @param link_rx_rate [KiB/s] Network traffic to the component system. A value of UINT32_MAX implies the field is unused.
* @param link_tx_max [KiB/s] Network capacity from the component system. A value of UINT32_MAX implies the field is unused.
* @param link_rx_max [KiB/s] Network capacity to the component system. A value of UINT32_MAX implies the field is unused.
+ * @param status_flags Bitmap of status flags.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_onboard_computer_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint64_t time_usec, uint32_t uptime, uint8_t type, const uint8_t *cpu_cores, const uint8_t *cpu_combined, const uint8_t *gpu_cores, const uint8_t *gpu_combined, int8_t temperature_board, const int8_t *temperature_core, const int16_t *fan_speed, uint32_t ram_usage, uint32_t ram_total, const uint32_t *storage_type, const uint32_t *storage_usage, const uint32_t *storage_total, const uint32_t *link_type, const uint32_t *link_tx_rate, const uint32_t *link_rx_rate, const uint32_t *link_tx_max, const uint32_t *link_rx_max)
+ uint64_t time_usec, uint32_t uptime, uint8_t type, const uint8_t *cpu_cores, const uint8_t *cpu_combined, const uint8_t *gpu_cores, const uint8_t *gpu_combined, int8_t temperature_board, const int8_t *temperature_core, const int16_t *fan_speed, uint32_t ram_usage, uint32_t ram_total, const uint32_t *storage_type, const uint32_t *storage_usage, const uint32_t *storage_total, const uint32_t *link_type, const uint32_t *link_tx_rate, const uint32_t *link_rx_rate, const uint32_t *link_tx_max, const uint32_t *link_rx_max, uint16_t status_flags)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS_LEN];
@@ -144,6 +148,7 @@ static inline uint16_t mavlink_msg_onboard_computer_status_pack(uint8_t system_i
_mav_put_uint32_t(buf, 16, ram_total);
_mav_put_uint8_t(buf, 196, type);
_mav_put_int8_t(buf, 229, temperature_board);
+ _mav_put_uint16_t(buf, 238, status_flags);
_mav_put_uint32_t_array(buf, 20, storage_type, 4);
_mav_put_uint32_t_array(buf, 36, storage_usage, 4);
_mav_put_uint32_t_array(buf, 52, storage_total, 4);
@@ -167,6 +172,7 @@ static inline uint16_t mavlink_msg_onboard_computer_status_pack(uint8_t system_i
packet.ram_total = ram_total;
packet.type = type;
packet.temperature_board = temperature_board;
+ packet.status_flags = status_flags;
mav_array_assign_uint32_t(packet.storage_type, storage_type, 4);
mav_array_assign_uint32_t(packet.storage_usage, storage_usage, 4);
mav_array_assign_uint32_t(packet.storage_total, storage_total, 4);
@@ -215,10 +221,11 @@ static inline uint16_t mavlink_msg_onboard_computer_status_pack(uint8_t system_i
* @param link_rx_rate [KiB/s] Network traffic to the component system. A value of UINT32_MAX implies the field is unused.
* @param link_tx_max [KiB/s] Network capacity from the component system. A value of UINT32_MAX implies the field is unused.
* @param link_rx_max [KiB/s] Network capacity to the component system. A value of UINT32_MAX implies the field is unused.
+ * @param status_flags Bitmap of status flags.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_onboard_computer_status_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
- uint64_t time_usec, uint32_t uptime, uint8_t type, const uint8_t *cpu_cores, const uint8_t *cpu_combined, const uint8_t *gpu_cores, const uint8_t *gpu_combined, int8_t temperature_board, const int8_t *temperature_core, const int16_t *fan_speed, uint32_t ram_usage, uint32_t ram_total, const uint32_t *storage_type, const uint32_t *storage_usage, const uint32_t *storage_total, const uint32_t *link_type, const uint32_t *link_tx_rate, const uint32_t *link_rx_rate, const uint32_t *link_tx_max, const uint32_t *link_rx_max)
+ uint64_t time_usec, uint32_t uptime, uint8_t type, const uint8_t *cpu_cores, const uint8_t *cpu_combined, const uint8_t *gpu_cores, const uint8_t *gpu_combined, int8_t temperature_board, const int8_t *temperature_core, const int16_t *fan_speed, uint32_t ram_usage, uint32_t ram_total, const uint32_t *storage_type, const uint32_t *storage_usage, const uint32_t *storage_total, const uint32_t *link_type, const uint32_t *link_tx_rate, const uint32_t *link_rx_rate, const uint32_t *link_tx_max, const uint32_t *link_rx_max, uint16_t status_flags)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS_LEN];
@@ -228,6 +235,7 @@ static inline uint16_t mavlink_msg_onboard_computer_status_pack_status(uint8_t s
_mav_put_uint32_t(buf, 16, ram_total);
_mav_put_uint8_t(buf, 196, type);
_mav_put_int8_t(buf, 229, temperature_board);
+ _mav_put_uint16_t(buf, 238, status_flags);
_mav_put_uint32_t_array(buf, 20, storage_type, 4);
_mav_put_uint32_t_array(buf, 36, storage_usage, 4);
_mav_put_uint32_t_array(buf, 52, storage_total, 4);
@@ -251,6 +259,7 @@ static inline uint16_t mavlink_msg_onboard_computer_status_pack_status(uint8_t s
packet.ram_total = ram_total;
packet.type = type;
packet.temperature_board = temperature_board;
+ packet.status_flags = status_flags;
mav_array_memcpy(packet.storage_type, storage_type, sizeof(uint32_t)*4);
mav_array_memcpy(packet.storage_usage, storage_usage, sizeof(uint32_t)*4);
mav_array_memcpy(packet.storage_total, storage_total, sizeof(uint32_t)*4);
@@ -302,11 +311,12 @@ static inline uint16_t mavlink_msg_onboard_computer_status_pack_status(uint8_t s
* @param link_rx_rate [KiB/s] Network traffic to the component system. A value of UINT32_MAX implies the field is unused.
* @param link_tx_max [KiB/s] Network capacity from the component system. A value of UINT32_MAX implies the field is unused.
* @param link_rx_max [KiB/s] Network capacity to the component system. A value of UINT32_MAX implies the field is unused.
+ * @param status_flags Bitmap of status flags.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_onboard_computer_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
- uint64_t time_usec,uint32_t uptime,uint8_t type,const uint8_t *cpu_cores,const uint8_t *cpu_combined,const uint8_t *gpu_cores,const uint8_t *gpu_combined,int8_t temperature_board,const int8_t *temperature_core,const int16_t *fan_speed,uint32_t ram_usage,uint32_t ram_total,const uint32_t *storage_type,const uint32_t *storage_usage,const uint32_t *storage_total,const uint32_t *link_type,const uint32_t *link_tx_rate,const uint32_t *link_rx_rate,const uint32_t *link_tx_max,const uint32_t *link_rx_max)
+ uint64_t time_usec,uint32_t uptime,uint8_t type,const uint8_t *cpu_cores,const uint8_t *cpu_combined,const uint8_t *gpu_cores,const uint8_t *gpu_combined,int8_t temperature_board,const int8_t *temperature_core,const int16_t *fan_speed,uint32_t ram_usage,uint32_t ram_total,const uint32_t *storage_type,const uint32_t *storage_usage,const uint32_t *storage_total,const uint32_t *link_type,const uint32_t *link_tx_rate,const uint32_t *link_rx_rate,const uint32_t *link_tx_max,const uint32_t *link_rx_max,uint16_t status_flags)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS_LEN];
@@ -316,6 +326,7 @@ static inline uint16_t mavlink_msg_onboard_computer_status_pack_chan(uint8_t sys
_mav_put_uint32_t(buf, 16, ram_total);
_mav_put_uint8_t(buf, 196, type);
_mav_put_int8_t(buf, 229, temperature_board);
+ _mav_put_uint16_t(buf, 238, status_flags);
_mav_put_uint32_t_array(buf, 20, storage_type, 4);
_mav_put_uint32_t_array(buf, 36, storage_usage, 4);
_mav_put_uint32_t_array(buf, 52, storage_total, 4);
@@ -339,6 +350,7 @@ static inline uint16_t mavlink_msg_onboard_computer_status_pack_chan(uint8_t sys
packet.ram_total = ram_total;
packet.type = type;
packet.temperature_board = temperature_board;
+ packet.status_flags = status_flags;
mav_array_assign_uint32_t(packet.storage_type, storage_type, 4);
mav_array_assign_uint32_t(packet.storage_usage, storage_usage, 4);
mav_array_assign_uint32_t(packet.storage_total, storage_total, 4);
@@ -370,7 +382,7 @@ static inline uint16_t mavlink_msg_onboard_computer_status_pack_chan(uint8_t sys
*/
static inline uint16_t mavlink_msg_onboard_computer_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_onboard_computer_status_t* onboard_computer_status)
{
- return mavlink_msg_onboard_computer_status_pack(system_id, component_id, msg, onboard_computer_status->time_usec, onboard_computer_status->uptime, onboard_computer_status->type, onboard_computer_status->cpu_cores, onboard_computer_status->cpu_combined, onboard_computer_status->gpu_cores, onboard_computer_status->gpu_combined, onboard_computer_status->temperature_board, onboard_computer_status->temperature_core, onboard_computer_status->fan_speed, onboard_computer_status->ram_usage, onboard_computer_status->ram_total, onboard_computer_status->storage_type, onboard_computer_status->storage_usage, onboard_computer_status->storage_total, onboard_computer_status->link_type, onboard_computer_status->link_tx_rate, onboard_computer_status->link_rx_rate, onboard_computer_status->link_tx_max, onboard_computer_status->link_rx_max);
+ return mavlink_msg_onboard_computer_status_pack(system_id, component_id, msg, onboard_computer_status->time_usec, onboard_computer_status->uptime, onboard_computer_status->type, onboard_computer_status->cpu_cores, onboard_computer_status->cpu_combined, onboard_computer_status->gpu_cores, onboard_computer_status->gpu_combined, onboard_computer_status->temperature_board, onboard_computer_status->temperature_core, onboard_computer_status->fan_speed, onboard_computer_status->ram_usage, onboard_computer_status->ram_total, onboard_computer_status->storage_type, onboard_computer_status->storage_usage, onboard_computer_status->storage_total, onboard_computer_status->link_type, onboard_computer_status->link_tx_rate, onboard_computer_status->link_rx_rate, onboard_computer_status->link_tx_max, onboard_computer_status->link_rx_max, onboard_computer_status->status_flags);
}
/**
@@ -384,7 +396,7 @@ static inline uint16_t mavlink_msg_onboard_computer_status_encode(uint8_t system
*/
static inline uint16_t mavlink_msg_onboard_computer_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_onboard_computer_status_t* onboard_computer_status)
{
- return mavlink_msg_onboard_computer_status_pack_chan(system_id, component_id, chan, msg, onboard_computer_status->time_usec, onboard_computer_status->uptime, onboard_computer_status->type, onboard_computer_status->cpu_cores, onboard_computer_status->cpu_combined, onboard_computer_status->gpu_cores, onboard_computer_status->gpu_combined, onboard_computer_status->temperature_board, onboard_computer_status->temperature_core, onboard_computer_status->fan_speed, onboard_computer_status->ram_usage, onboard_computer_status->ram_total, onboard_computer_status->storage_type, onboard_computer_status->storage_usage, onboard_computer_status->storage_total, onboard_computer_status->link_type, onboard_computer_status->link_tx_rate, onboard_computer_status->link_rx_rate, onboard_computer_status->link_tx_max, onboard_computer_status->link_rx_max);
+ return mavlink_msg_onboard_computer_status_pack_chan(system_id, component_id, chan, msg, onboard_computer_status->time_usec, onboard_computer_status->uptime, onboard_computer_status->type, onboard_computer_status->cpu_cores, onboard_computer_status->cpu_combined, onboard_computer_status->gpu_cores, onboard_computer_status->gpu_combined, onboard_computer_status->temperature_board, onboard_computer_status->temperature_core, onboard_computer_status->fan_speed, onboard_computer_status->ram_usage, onboard_computer_status->ram_total, onboard_computer_status->storage_type, onboard_computer_status->storage_usage, onboard_computer_status->storage_total, onboard_computer_status->link_type, onboard_computer_status->link_tx_rate, onboard_computer_status->link_rx_rate, onboard_computer_status->link_tx_max, onboard_computer_status->link_rx_max, onboard_computer_status->status_flags);
}
/**
@@ -398,7 +410,7 @@ static inline uint16_t mavlink_msg_onboard_computer_status_encode_chan(uint8_t s
*/
static inline uint16_t mavlink_msg_onboard_computer_status_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_onboard_computer_status_t* onboard_computer_status)
{
- return mavlink_msg_onboard_computer_status_pack_status(system_id, component_id, _status, msg, onboard_computer_status->time_usec, onboard_computer_status->uptime, onboard_computer_status->type, onboard_computer_status->cpu_cores, onboard_computer_status->cpu_combined, onboard_computer_status->gpu_cores, onboard_computer_status->gpu_combined, onboard_computer_status->temperature_board, onboard_computer_status->temperature_core, onboard_computer_status->fan_speed, onboard_computer_status->ram_usage, onboard_computer_status->ram_total, onboard_computer_status->storage_type, onboard_computer_status->storage_usage, onboard_computer_status->storage_total, onboard_computer_status->link_type, onboard_computer_status->link_tx_rate, onboard_computer_status->link_rx_rate, onboard_computer_status->link_tx_max, onboard_computer_status->link_rx_max);
+ return mavlink_msg_onboard_computer_status_pack_status(system_id, component_id, _status, msg, onboard_computer_status->time_usec, onboard_computer_status->uptime, onboard_computer_status->type, onboard_computer_status->cpu_cores, onboard_computer_status->cpu_combined, onboard_computer_status->gpu_cores, onboard_computer_status->gpu_combined, onboard_computer_status->temperature_board, onboard_computer_status->temperature_core, onboard_computer_status->fan_speed, onboard_computer_status->ram_usage, onboard_computer_status->ram_total, onboard_computer_status->storage_type, onboard_computer_status->storage_usage, onboard_computer_status->storage_total, onboard_computer_status->link_type, onboard_computer_status->link_tx_rate, onboard_computer_status->link_rx_rate, onboard_computer_status->link_tx_max, onboard_computer_status->link_rx_max, onboard_computer_status->status_flags);
}
/**
@@ -425,10 +437,11 @@ static inline uint16_t mavlink_msg_onboard_computer_status_encode_status(uint8_t
* @param link_rx_rate [KiB/s] Network traffic to the component system. A value of UINT32_MAX implies the field is unused.
* @param link_tx_max [KiB/s] Network capacity from the component system. A value of UINT32_MAX implies the field is unused.
* @param link_rx_max [KiB/s] Network capacity to the component system. A value of UINT32_MAX implies the field is unused.
+ * @param status_flags Bitmap of status flags.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
-static inline void mavlink_msg_onboard_computer_status_send(mavlink_channel_t chan, uint64_t time_usec, uint32_t uptime, uint8_t type, const uint8_t *cpu_cores, const uint8_t *cpu_combined, const uint8_t *gpu_cores, const uint8_t *gpu_combined, int8_t temperature_board, const int8_t *temperature_core, const int16_t *fan_speed, uint32_t ram_usage, uint32_t ram_total, const uint32_t *storage_type, const uint32_t *storage_usage, const uint32_t *storage_total, const uint32_t *link_type, const uint32_t *link_tx_rate, const uint32_t *link_rx_rate, const uint32_t *link_tx_max, const uint32_t *link_rx_max)
+static inline void mavlink_msg_onboard_computer_status_send(mavlink_channel_t chan, uint64_t time_usec, uint32_t uptime, uint8_t type, const uint8_t *cpu_cores, const uint8_t *cpu_combined, const uint8_t *gpu_cores, const uint8_t *gpu_combined, int8_t temperature_board, const int8_t *temperature_core, const int16_t *fan_speed, uint32_t ram_usage, uint32_t ram_total, const uint32_t *storage_type, const uint32_t *storage_usage, const uint32_t *storage_total, const uint32_t *link_type, const uint32_t *link_tx_rate, const uint32_t *link_rx_rate, const uint32_t *link_tx_max, const uint32_t *link_rx_max, uint16_t status_flags)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS_LEN];
@@ -438,6 +451,7 @@ static inline void mavlink_msg_onboard_computer_status_send(mavlink_channel_t ch
_mav_put_uint32_t(buf, 16, ram_total);
_mav_put_uint8_t(buf, 196, type);
_mav_put_int8_t(buf, 229, temperature_board);
+ _mav_put_uint16_t(buf, 238, status_flags);
_mav_put_uint32_t_array(buf, 20, storage_type, 4);
_mav_put_uint32_t_array(buf, 36, storage_usage, 4);
_mav_put_uint32_t_array(buf, 52, storage_total, 4);
@@ -461,6 +475,7 @@ static inline void mavlink_msg_onboard_computer_status_send(mavlink_channel_t ch
packet.ram_total = ram_total;
packet.type = type;
packet.temperature_board = temperature_board;
+ packet.status_flags = status_flags;
mav_array_assign_uint32_t(packet.storage_type, storage_type, 4);
mav_array_assign_uint32_t(packet.storage_usage, storage_usage, 4);
mav_array_assign_uint32_t(packet.storage_total, storage_total, 4);
@@ -487,7 +502,7 @@ static inline void mavlink_msg_onboard_computer_status_send(mavlink_channel_t ch
static inline void mavlink_msg_onboard_computer_status_send_struct(mavlink_channel_t chan, const mavlink_onboard_computer_status_t* onboard_computer_status)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_onboard_computer_status_send(chan, onboard_computer_status->time_usec, onboard_computer_status->uptime, onboard_computer_status->type, onboard_computer_status->cpu_cores, onboard_computer_status->cpu_combined, onboard_computer_status->gpu_cores, onboard_computer_status->gpu_combined, onboard_computer_status->temperature_board, onboard_computer_status->temperature_core, onboard_computer_status->fan_speed, onboard_computer_status->ram_usage, onboard_computer_status->ram_total, onboard_computer_status->storage_type, onboard_computer_status->storage_usage, onboard_computer_status->storage_total, onboard_computer_status->link_type, onboard_computer_status->link_tx_rate, onboard_computer_status->link_rx_rate, onboard_computer_status->link_tx_max, onboard_computer_status->link_rx_max);
+ mavlink_msg_onboard_computer_status_send(chan, onboard_computer_status->time_usec, onboard_computer_status->uptime, onboard_computer_status->type, onboard_computer_status->cpu_cores, onboard_computer_status->cpu_combined, onboard_computer_status->gpu_cores, onboard_computer_status->gpu_combined, onboard_computer_status->temperature_board, onboard_computer_status->temperature_core, onboard_computer_status->fan_speed, onboard_computer_status->ram_usage, onboard_computer_status->ram_total, onboard_computer_status->storage_type, onboard_computer_status->storage_usage, onboard_computer_status->storage_total, onboard_computer_status->link_type, onboard_computer_status->link_tx_rate, onboard_computer_status->link_rx_rate, onboard_computer_status->link_tx_max, onboard_computer_status->link_rx_max, onboard_computer_status->status_flags);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS, (const char *)onboard_computer_status, MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS_MIN_LEN, MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS_LEN, MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS_CRC);
#endif
@@ -501,7 +516,7 @@ static inline void mavlink_msg_onboard_computer_status_send_struct(mavlink_chann
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_onboard_computer_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint32_t uptime, uint8_t type, const uint8_t *cpu_cores, const uint8_t *cpu_combined, const uint8_t *gpu_cores, const uint8_t *gpu_combined, int8_t temperature_board, const int8_t *temperature_core, const int16_t *fan_speed, uint32_t ram_usage, uint32_t ram_total, const uint32_t *storage_type, const uint32_t *storage_usage, const uint32_t *storage_total, const uint32_t *link_type, const uint32_t *link_tx_rate, const uint32_t *link_rx_rate, const uint32_t *link_tx_max, const uint32_t *link_rx_max)
+static inline void mavlink_msg_onboard_computer_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint32_t uptime, uint8_t type, const uint8_t *cpu_cores, const uint8_t *cpu_combined, const uint8_t *gpu_cores, const uint8_t *gpu_combined, int8_t temperature_board, const int8_t *temperature_core, const int16_t *fan_speed, uint32_t ram_usage, uint32_t ram_total, const uint32_t *storage_type, const uint32_t *storage_usage, const uint32_t *storage_total, const uint32_t *link_type, const uint32_t *link_tx_rate, const uint32_t *link_rx_rate, const uint32_t *link_tx_max, const uint32_t *link_rx_max, uint16_t status_flags)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
@@ -511,6 +526,7 @@ static inline void mavlink_msg_onboard_computer_status_send_buf(mavlink_message_
_mav_put_uint32_t(buf, 16, ram_total);
_mav_put_uint8_t(buf, 196, type);
_mav_put_int8_t(buf, 229, temperature_board);
+ _mav_put_uint16_t(buf, 238, status_flags);
_mav_put_uint32_t_array(buf, 20, storage_type, 4);
_mav_put_uint32_t_array(buf, 36, storage_usage, 4);
_mav_put_uint32_t_array(buf, 52, storage_total, 4);
@@ -534,6 +550,7 @@ static inline void mavlink_msg_onboard_computer_status_send_buf(mavlink_message_
packet->ram_total = ram_total;
packet->type = type;
packet->temperature_board = temperature_board;
+ packet->status_flags = status_flags;
mav_array_assign_uint32_t(packet->storage_type, storage_type, 4);
mav_array_assign_uint32_t(packet->storage_usage, storage_usage, 4);
mav_array_assign_uint32_t(packet->storage_total, storage_total, 4);
@@ -758,6 +775,16 @@ static inline uint16_t mavlink_msg_onboard_computer_status_get_link_rx_max(const
return _MAV_RETURN_uint32_t_array(msg, link_rx_max, 6, 164);
}
+/**
+ * @brief Get field status_flags from onboard_computer_status message
+ *
+ * @return Bitmap of status flags.
+ */
+static inline uint16_t mavlink_msg_onboard_computer_status_get_status_flags(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 238);
+}
+
/**
* @brief Decode a onboard_computer_status message into a struct
*
@@ -787,6 +814,7 @@ static inline void mavlink_msg_onboard_computer_status_decode(const mavlink_mess
mavlink_msg_onboard_computer_status_get_gpu_combined(msg, onboard_computer_status->gpu_combined);
onboard_computer_status->temperature_board = mavlink_msg_onboard_computer_status_get_temperature_board(msg);
mavlink_msg_onboard_computer_status_get_temperature_core(msg, onboard_computer_status->temperature_core);
+ onboard_computer_status->status_flags = mavlink_msg_onboard_computer_status_get_status_flags(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS_LEN? msg->len : MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS_LEN;
memset(onboard_computer_status, 0, MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS_LEN);
diff --git a/lib/main/MAVLink/common/mavlink_msg_param_error.h b/lib/main/MAVLink/common/mavlink_msg_param_error.h
new file mode 100644
index 00000000000..bc8266ca2d1
--- /dev/null
+++ b/lib/main/MAVLink/common/mavlink_msg_param_error.h
@@ -0,0 +1,362 @@
+#pragma once
+// MESSAGE PARAM_ERROR PACKING
+
+#define MAVLINK_MSG_ID_PARAM_ERROR 345
+
+
+typedef struct __mavlink_param_error_t {
+ int16_t param_index; /*< Parameter index. Will be -1 if the param ID field should be used as an identifier (else the param id will be ignored)*/
+ uint8_t target_system; /*< System ID*/
+ uint8_t target_component; /*< Component ID*/
+ char param_id[16]; /*< Parameter id. Terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string*/
+ uint8_t error; /*< Error being returned to client.*/
+} mavlink_param_error_t;
+
+#define MAVLINK_MSG_ID_PARAM_ERROR_LEN 21
+#define MAVLINK_MSG_ID_PARAM_ERROR_MIN_LEN 21
+#define MAVLINK_MSG_ID_345_LEN 21
+#define MAVLINK_MSG_ID_345_MIN_LEN 21
+
+#define MAVLINK_MSG_ID_PARAM_ERROR_CRC 209
+#define MAVLINK_MSG_ID_345_CRC 209
+
+#define MAVLINK_MSG_PARAM_ERROR_FIELD_PARAM_ID_LEN 16
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_PARAM_ERROR { \
+ 345, \
+ "PARAM_ERROR", \
+ 5, \
+ { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_param_error_t, target_system) }, \
+ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_param_error_t, target_component) }, \
+ { "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 4, offsetof(mavlink_param_error_t, param_id) }, \
+ { "param_index", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_param_error_t, param_index) }, \
+ { "error", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_param_error_t, error) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_PARAM_ERROR { \
+ "PARAM_ERROR", \
+ 5, \
+ { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_param_error_t, target_system) }, \
+ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_param_error_t, target_component) }, \
+ { "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 4, offsetof(mavlink_param_error_t, param_id) }, \
+ { "param_index", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_param_error_t, param_index) }, \
+ { "error", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_param_error_t, error) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a param_error 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 target_system System ID
+ * @param target_component Component ID
+ * @param param_id Parameter id. Terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
+ * @param param_index Parameter index. Will be -1 if the param ID field should be used as an identifier (else the param id will be ignored)
+ * @param error Error being returned to client.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_param_error_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint8_t target_system, uint8_t target_component, const char *param_id, int16_t param_index, uint8_t error)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_PARAM_ERROR_LEN];
+ _mav_put_int16_t(buf, 0, param_index);
+ _mav_put_uint8_t(buf, 2, target_system);
+ _mav_put_uint8_t(buf, 3, target_component);
+ _mav_put_uint8_t(buf, 20, error);
+ _mav_put_char_array(buf, 4, param_id, 16);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PARAM_ERROR_LEN);
+#else
+ mavlink_param_error_t packet;
+ packet.param_index = param_index;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.error = error;
+ mav_array_assign_char(packet.param_id, param_id, 16);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PARAM_ERROR_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_PARAM_ERROR;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PARAM_ERROR_MIN_LEN, MAVLINK_MSG_ID_PARAM_ERROR_LEN, MAVLINK_MSG_ID_PARAM_ERROR_CRC);
+}
+
+/**
+ * @brief Pack a param_error 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 target_system System ID
+ * @param target_component Component ID
+ * @param param_id Parameter id. Terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
+ * @param param_index Parameter index. Will be -1 if the param ID field should be used as an identifier (else the param id will be ignored)
+ * @param error Error being returned to client.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_param_error_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ uint8_t target_system, uint8_t target_component, const char *param_id, int16_t param_index, uint8_t error)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_PARAM_ERROR_LEN];
+ _mav_put_int16_t(buf, 0, param_index);
+ _mav_put_uint8_t(buf, 2, target_system);
+ _mav_put_uint8_t(buf, 3, target_component);
+ _mav_put_uint8_t(buf, 20, error);
+ _mav_put_char_array(buf, 4, param_id, 16);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PARAM_ERROR_LEN);
+#else
+ mavlink_param_error_t packet;
+ packet.param_index = param_index;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.error = error;
+ mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PARAM_ERROR_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_PARAM_ERROR;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_PARAM_ERROR_MIN_LEN, MAVLINK_MSG_ID_PARAM_ERROR_LEN, MAVLINK_MSG_ID_PARAM_ERROR_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_PARAM_ERROR_MIN_LEN, MAVLINK_MSG_ID_PARAM_ERROR_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a param_error 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 target_system System ID
+ * @param target_component Component ID
+ * @param param_id Parameter id. Terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
+ * @param param_index Parameter index. Will be -1 if the param ID field should be used as an identifier (else the param id will be ignored)
+ * @param error Error being returned to client.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_param_error_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint8_t target_system,uint8_t target_component,const char *param_id,int16_t param_index,uint8_t error)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_PARAM_ERROR_LEN];
+ _mav_put_int16_t(buf, 0, param_index);
+ _mav_put_uint8_t(buf, 2, target_system);
+ _mav_put_uint8_t(buf, 3, target_component);
+ _mav_put_uint8_t(buf, 20, error);
+ _mav_put_char_array(buf, 4, param_id, 16);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PARAM_ERROR_LEN);
+#else
+ mavlink_param_error_t packet;
+ packet.param_index = param_index;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.error = error;
+ mav_array_assign_char(packet.param_id, param_id, 16);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PARAM_ERROR_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_PARAM_ERROR;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PARAM_ERROR_MIN_LEN, MAVLINK_MSG_ID_PARAM_ERROR_LEN, MAVLINK_MSG_ID_PARAM_ERROR_CRC);
+}
+
+/**
+ * @brief Encode a param_error 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 param_error C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_param_error_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_param_error_t* param_error)
+{
+ return mavlink_msg_param_error_pack(system_id, component_id, msg, param_error->target_system, param_error->target_component, param_error->param_id, param_error->param_index, param_error->error);
+}
+
+/**
+ * @brief Encode a param_error 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 param_error C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_param_error_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_param_error_t* param_error)
+{
+ return mavlink_msg_param_error_pack_chan(system_id, component_id, chan, msg, param_error->target_system, param_error->target_component, param_error->param_id, param_error->param_index, param_error->error);
+}
+
+/**
+ * @brief Encode a param_error 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 param_error C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_param_error_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_param_error_t* param_error)
+{
+ return mavlink_msg_param_error_pack_status(system_id, component_id, _status, msg, param_error->target_system, param_error->target_component, param_error->param_id, param_error->param_index, param_error->error);
+}
+
+/**
+ * @brief Send a param_error message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param target_system System ID
+ * @param target_component Component ID
+ * @param param_id Parameter id. Terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
+ * @param param_index Parameter index. Will be -1 if the param ID field should be used as an identifier (else the param id will be ignored)
+ * @param error Error being returned to client.
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_param_error_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const char *param_id, int16_t param_index, uint8_t error)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_PARAM_ERROR_LEN];
+ _mav_put_int16_t(buf, 0, param_index);
+ _mav_put_uint8_t(buf, 2, target_system);
+ _mav_put_uint8_t(buf, 3, target_component);
+ _mav_put_uint8_t(buf, 20, error);
+ _mav_put_char_array(buf, 4, param_id, 16);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_ERROR, buf, MAVLINK_MSG_ID_PARAM_ERROR_MIN_LEN, MAVLINK_MSG_ID_PARAM_ERROR_LEN, MAVLINK_MSG_ID_PARAM_ERROR_CRC);
+#else
+ mavlink_param_error_t packet;
+ packet.param_index = param_index;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.error = error;
+ mav_array_assign_char(packet.param_id, param_id, 16);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_ERROR, (const char *)&packet, MAVLINK_MSG_ID_PARAM_ERROR_MIN_LEN, MAVLINK_MSG_ID_PARAM_ERROR_LEN, MAVLINK_MSG_ID_PARAM_ERROR_CRC);
+#endif
+}
+
+/**
+ * @brief Send a param_error message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_param_error_send_struct(mavlink_channel_t chan, const mavlink_param_error_t* param_error)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_param_error_send(chan, param_error->target_system, param_error->target_component, param_error->param_id, param_error->param_index, param_error->error);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_ERROR, (const char *)param_error, MAVLINK_MSG_ID_PARAM_ERROR_MIN_LEN, MAVLINK_MSG_ID_PARAM_ERROR_LEN, MAVLINK_MSG_ID_PARAM_ERROR_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_PARAM_ERROR_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_param_error_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const char *param_id, int16_t param_index, uint8_t error)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_int16_t(buf, 0, param_index);
+ _mav_put_uint8_t(buf, 2, target_system);
+ _mav_put_uint8_t(buf, 3, target_component);
+ _mav_put_uint8_t(buf, 20, error);
+ _mav_put_char_array(buf, 4, param_id, 16);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_ERROR, buf, MAVLINK_MSG_ID_PARAM_ERROR_MIN_LEN, MAVLINK_MSG_ID_PARAM_ERROR_LEN, MAVLINK_MSG_ID_PARAM_ERROR_CRC);
+#else
+ mavlink_param_error_t *packet = (mavlink_param_error_t *)msgbuf;
+ packet->param_index = param_index;
+ packet->target_system = target_system;
+ packet->target_component = target_component;
+ packet->error = error;
+ mav_array_assign_char(packet->param_id, param_id, 16);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_ERROR, (const char *)packet, MAVLINK_MSG_ID_PARAM_ERROR_MIN_LEN, MAVLINK_MSG_ID_PARAM_ERROR_LEN, MAVLINK_MSG_ID_PARAM_ERROR_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE PARAM_ERROR UNPACKING
+
+
+/**
+ * @brief Get field target_system from param_error message
+ *
+ * @return System ID
+ */
+static inline uint8_t mavlink_msg_param_error_get_target_system(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 2);
+}
+
+/**
+ * @brief Get field target_component from param_error message
+ *
+ * @return Component ID
+ */
+static inline uint8_t mavlink_msg_param_error_get_target_component(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 3);
+}
+
+/**
+ * @brief Get field param_id from param_error message
+ *
+ * @return Parameter id. Terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
+ */
+static inline uint16_t mavlink_msg_param_error_get_param_id(const mavlink_message_t* msg, char *param_id)
+{
+ return _MAV_RETURN_char_array(msg, param_id, 16, 4);
+}
+
+/**
+ * @brief Get field param_index from param_error message
+ *
+ * @return Parameter index. Will be -1 if the param ID field should be used as an identifier (else the param id will be ignored)
+ */
+static inline int16_t mavlink_msg_param_error_get_param_index(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_int16_t(msg, 0);
+}
+
+/**
+ * @brief Get field error from param_error message
+ *
+ * @return Error being returned to client.
+ */
+static inline uint8_t mavlink_msg_param_error_get_error(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 20);
+}
+
+/**
+ * @brief Decode a param_error message into a struct
+ *
+ * @param msg The message to decode
+ * @param param_error C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_param_error_decode(const mavlink_message_t* msg, mavlink_param_error_t* param_error)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ param_error->param_index = mavlink_msg_param_error_get_param_index(msg);
+ param_error->target_system = mavlink_msg_param_error_get_target_system(msg);
+ param_error->target_component = mavlink_msg_param_error_get_target_component(msg);
+ mavlink_msg_param_error_get_param_id(msg, param_error->param_id);
+ param_error->error = mavlink_msg_param_error_get_error(msg);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_PARAM_ERROR_LEN? msg->len : MAVLINK_MSG_ID_PARAM_ERROR_LEN;
+ memset(param_error, 0, MAVLINK_MSG_ID_PARAM_ERROR_LEN);
+ memcpy(param_error, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/minimal/mavlink_msg_protocol_version.h b/lib/main/MAVLink/common/mavlink_msg_protocol_version.h
similarity index 100%
rename from lib/main/MAVLink/minimal/mavlink_msg_protocol_version.h
rename to lib/main/MAVLink/common/mavlink_msg_protocol_version.h
diff --git a/lib/main/MAVLink/common/mavlink_msg_relay_status.h b/lib/main/MAVLink/common/mavlink_msg_relay_status.h
new file mode 100644
index 00000000000..f1ae0c3a04a
--- /dev/null
+++ b/lib/main/MAVLink/common/mavlink_msg_relay_status.h
@@ -0,0 +1,316 @@
+#pragma once
+// MESSAGE RELAY_STATUS PACKING
+
+#define MAVLINK_MSG_ID_RELAY_STATUS 376
+
+
+typedef struct __mavlink_relay_status_t {
+ uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/
+ uint16_t on; /*< Relay states. Relay instance numbers are represented as individual bits in this mask by offset.*/
+ uint16_t present; /*< Relay present. Relay instance numbers are represented as individual bits in this mask by offset. Bits will be true if a relay instance is configured.*/
+} mavlink_relay_status_t;
+
+#define MAVLINK_MSG_ID_RELAY_STATUS_LEN 8
+#define MAVLINK_MSG_ID_RELAY_STATUS_MIN_LEN 8
+#define MAVLINK_MSG_ID_376_LEN 8
+#define MAVLINK_MSG_ID_376_MIN_LEN 8
+
+#define MAVLINK_MSG_ID_RELAY_STATUS_CRC 199
+#define MAVLINK_MSG_ID_376_CRC 199
+
+
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_RELAY_STATUS { \
+ 376, \
+ "RELAY_STATUS", \
+ 3, \
+ { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_relay_status_t, time_boot_ms) }, \
+ { "on", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_relay_status_t, on) }, \
+ { "present", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_relay_status_t, present) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_RELAY_STATUS { \
+ "RELAY_STATUS", \
+ 3, \
+ { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_relay_status_t, time_boot_ms) }, \
+ { "on", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_relay_status_t, on) }, \
+ { "present", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_relay_status_t, present) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a relay_status 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 time_boot_ms [ms] Timestamp (time since system boot).
+ * @param on Relay states. Relay instance numbers are represented as individual bits in this mask by offset.
+ * @param present Relay present. Relay instance numbers are represented as individual bits in this mask by offset. Bits will be true if a relay instance is configured.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_relay_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint32_t time_boot_ms, uint16_t on, uint16_t present)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_RELAY_STATUS_LEN];
+ _mav_put_uint32_t(buf, 0, time_boot_ms);
+ _mav_put_uint16_t(buf, 4, on);
+ _mav_put_uint16_t(buf, 6, present);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RELAY_STATUS_LEN);
+#else
+ mavlink_relay_status_t packet;
+ packet.time_boot_ms = time_boot_ms;
+ packet.on = on;
+ packet.present = present;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RELAY_STATUS_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_RELAY_STATUS;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RELAY_STATUS_MIN_LEN, MAVLINK_MSG_ID_RELAY_STATUS_LEN, MAVLINK_MSG_ID_RELAY_STATUS_CRC);
+}
+
+/**
+ * @brief Pack a relay_status 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 time_boot_ms [ms] Timestamp (time since system boot).
+ * @param on Relay states. Relay instance numbers are represented as individual bits in this mask by offset.
+ * @param present Relay present. Relay instance numbers are represented as individual bits in this mask by offset. Bits will be true if a relay instance is configured.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_relay_status_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ uint32_t time_boot_ms, uint16_t on, uint16_t present)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_RELAY_STATUS_LEN];
+ _mav_put_uint32_t(buf, 0, time_boot_ms);
+ _mav_put_uint16_t(buf, 4, on);
+ _mav_put_uint16_t(buf, 6, present);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RELAY_STATUS_LEN);
+#else
+ mavlink_relay_status_t packet;
+ packet.time_boot_ms = time_boot_ms;
+ packet.on = on;
+ packet.present = present;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RELAY_STATUS_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_RELAY_STATUS;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_RELAY_STATUS_MIN_LEN, MAVLINK_MSG_ID_RELAY_STATUS_LEN, MAVLINK_MSG_ID_RELAY_STATUS_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_RELAY_STATUS_MIN_LEN, MAVLINK_MSG_ID_RELAY_STATUS_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a relay_status 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 time_boot_ms [ms] Timestamp (time since system boot).
+ * @param on Relay states. Relay instance numbers are represented as individual bits in this mask by offset.
+ * @param present Relay present. Relay instance numbers are represented as individual bits in this mask by offset. Bits will be true if a relay instance is configured.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_relay_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint32_t time_boot_ms,uint16_t on,uint16_t present)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_RELAY_STATUS_LEN];
+ _mav_put_uint32_t(buf, 0, time_boot_ms);
+ _mav_put_uint16_t(buf, 4, on);
+ _mav_put_uint16_t(buf, 6, present);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RELAY_STATUS_LEN);
+#else
+ mavlink_relay_status_t packet;
+ packet.time_boot_ms = time_boot_ms;
+ packet.on = on;
+ packet.present = present;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RELAY_STATUS_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_RELAY_STATUS;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RELAY_STATUS_MIN_LEN, MAVLINK_MSG_ID_RELAY_STATUS_LEN, MAVLINK_MSG_ID_RELAY_STATUS_CRC);
+}
+
+/**
+ * @brief Encode a relay_status 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 relay_status C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_relay_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_relay_status_t* relay_status)
+{
+ return mavlink_msg_relay_status_pack(system_id, component_id, msg, relay_status->time_boot_ms, relay_status->on, relay_status->present);
+}
+
+/**
+ * @brief Encode a relay_status 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 relay_status C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_relay_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_relay_status_t* relay_status)
+{
+ return mavlink_msg_relay_status_pack_chan(system_id, component_id, chan, msg, relay_status->time_boot_ms, relay_status->on, relay_status->present);
+}
+
+/**
+ * @brief Encode a relay_status 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 relay_status C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_relay_status_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_relay_status_t* relay_status)
+{
+ return mavlink_msg_relay_status_pack_status(system_id, component_id, _status, msg, relay_status->time_boot_ms, relay_status->on, relay_status->present);
+}
+
+/**
+ * @brief Send a relay_status message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param time_boot_ms [ms] Timestamp (time since system boot).
+ * @param on Relay states. Relay instance numbers are represented as individual bits in this mask by offset.
+ * @param present Relay present. Relay instance numbers are represented as individual bits in this mask by offset. Bits will be true if a relay instance is configured.
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_relay_status_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint16_t on, uint16_t present)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_RELAY_STATUS_LEN];
+ _mav_put_uint32_t(buf, 0, time_boot_ms);
+ _mav_put_uint16_t(buf, 4, on);
+ _mav_put_uint16_t(buf, 6, present);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RELAY_STATUS, buf, MAVLINK_MSG_ID_RELAY_STATUS_MIN_LEN, MAVLINK_MSG_ID_RELAY_STATUS_LEN, MAVLINK_MSG_ID_RELAY_STATUS_CRC);
+#else
+ mavlink_relay_status_t packet;
+ packet.time_boot_ms = time_boot_ms;
+ packet.on = on;
+ packet.present = present;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RELAY_STATUS, (const char *)&packet, MAVLINK_MSG_ID_RELAY_STATUS_MIN_LEN, MAVLINK_MSG_ID_RELAY_STATUS_LEN, MAVLINK_MSG_ID_RELAY_STATUS_CRC);
+#endif
+}
+
+/**
+ * @brief Send a relay_status message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_relay_status_send_struct(mavlink_channel_t chan, const mavlink_relay_status_t* relay_status)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_relay_status_send(chan, relay_status->time_boot_ms, relay_status->on, relay_status->present);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RELAY_STATUS, (const char *)relay_status, MAVLINK_MSG_ID_RELAY_STATUS_MIN_LEN, MAVLINK_MSG_ID_RELAY_STATUS_LEN, MAVLINK_MSG_ID_RELAY_STATUS_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_RELAY_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_relay_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint16_t on, uint16_t present)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint32_t(buf, 0, time_boot_ms);
+ _mav_put_uint16_t(buf, 4, on);
+ _mav_put_uint16_t(buf, 6, present);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RELAY_STATUS, buf, MAVLINK_MSG_ID_RELAY_STATUS_MIN_LEN, MAVLINK_MSG_ID_RELAY_STATUS_LEN, MAVLINK_MSG_ID_RELAY_STATUS_CRC);
+#else
+ mavlink_relay_status_t *packet = (mavlink_relay_status_t *)msgbuf;
+ packet->time_boot_ms = time_boot_ms;
+ packet->on = on;
+ packet->present = present;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RELAY_STATUS, (const char *)packet, MAVLINK_MSG_ID_RELAY_STATUS_MIN_LEN, MAVLINK_MSG_ID_RELAY_STATUS_LEN, MAVLINK_MSG_ID_RELAY_STATUS_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE RELAY_STATUS UNPACKING
+
+
+/**
+ * @brief Get field time_boot_ms from relay_status message
+ *
+ * @return [ms] Timestamp (time since system boot).
+ */
+static inline uint32_t mavlink_msg_relay_status_get_time_boot_ms(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint32_t(msg, 0);
+}
+
+/**
+ * @brief Get field on from relay_status message
+ *
+ * @return Relay states. Relay instance numbers are represented as individual bits in this mask by offset.
+ */
+static inline uint16_t mavlink_msg_relay_status_get_on(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 4);
+}
+
+/**
+ * @brief Get field present from relay_status message
+ *
+ * @return Relay present. Relay instance numbers are represented as individual bits in this mask by offset. Bits will be true if a relay instance is configured.
+ */
+static inline uint16_t mavlink_msg_relay_status_get_present(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 6);
+}
+
+/**
+ * @brief Decode a relay_status message into a struct
+ *
+ * @param msg The message to decode
+ * @param relay_status C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_relay_status_decode(const mavlink_message_t* msg, mavlink_relay_status_t* relay_status)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ relay_status->time_boot_ms = mavlink_msg_relay_status_get_time_boot_ms(msg);
+ relay_status->on = mavlink_msg_relay_status_get_on(msg);
+ relay_status->present = mavlink_msg_relay_status_get_present(msg);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_RELAY_STATUS_LEN? msg->len : MAVLINK_MSG_ID_RELAY_STATUS_LEN;
+ memset(relay_status, 0, MAVLINK_MSG_ID_RELAY_STATUS_LEN);
+ memcpy(relay_status, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/common/mavlink_msg_request_data_stream.h b/lib/main/MAVLink/common/mavlink_msg_request_data_stream.h
index f3a81d5cfe1..aadfea149d8 100755
--- a/lib/main/MAVLink/common/mavlink_msg_request_data_stream.h
+++ b/lib/main/MAVLink/common/mavlink_msg_request_data_stream.h
@@ -8,7 +8,7 @@ typedef struct __mavlink_request_data_stream_t {
uint16_t req_message_rate; /*< [Hz] The requested message rate*/
uint8_t target_system; /*< The target requested to send the message stream.*/
uint8_t target_component; /*< The target requested to send the message stream.*/
- uint8_t req_stream_id; /*< The ID of the requested data stream*/
+ uint8_t req_stream_id; /*< The ID of the requested data stream.*/
uint8_t start_stop; /*< 1 to start sending, 0 to stop sending.*/
} mavlink_request_data_stream_t;
@@ -55,7 +55,7 @@ typedef struct __mavlink_request_data_stream_t {
*
* @param target_system The target requested to send the message stream.
* @param target_component The target requested to send the message stream.
- * @param req_stream_id The ID of the requested data stream
+ * @param req_stream_id The ID of the requested data stream.
* @param req_message_rate [Hz] The requested message rate
* @param start_stop 1 to start sending, 0 to stop sending.
* @return length of the message in bytes (excluding serial stream start sign)
@@ -96,7 +96,7 @@ static inline uint16_t mavlink_msg_request_data_stream_pack(uint8_t system_id, u
*
* @param target_system The target requested to send the message stream.
* @param target_component The target requested to send the message stream.
- * @param req_stream_id The ID of the requested data stream
+ * @param req_stream_id The ID of the requested data stream.
* @param req_message_rate [Hz] The requested message rate
* @param start_stop 1 to start sending, 0 to stop sending.
* @return length of the message in bytes (excluding serial stream start sign)
@@ -140,7 +140,7 @@ static inline uint16_t mavlink_msg_request_data_stream_pack_status(uint8_t syste
* @param msg The MAVLink message to compress the data into
* @param target_system The target requested to send the message stream.
* @param target_component The target requested to send the message stream.
- * @param req_stream_id The ID of the requested data stream
+ * @param req_stream_id The ID of the requested data stream.
* @param req_message_rate [Hz] The requested message rate
* @param start_stop 1 to start sending, 0 to stop sending.
* @return length of the message in bytes (excluding serial stream start sign)
@@ -220,7 +220,7 @@ static inline uint16_t mavlink_msg_request_data_stream_encode_status(uint8_t sys
*
* @param target_system The target requested to send the message stream.
* @param target_component The target requested to send the message stream.
- * @param req_stream_id The ID of the requested data stream
+ * @param req_stream_id The ID of the requested data stream.
* @param req_message_rate [Hz] The requested message rate
* @param start_stop 1 to start sending, 0 to stop sending.
*/
@@ -323,7 +323,7 @@ static inline uint8_t mavlink_msg_request_data_stream_get_target_component(const
/**
* @brief Get field req_stream_id from request_data_stream message
*
- * @return The ID of the requested data stream
+ * @return The ID of the requested data stream.
*/
static inline uint8_t mavlink_msg_request_data_stream_get_req_stream_id(const mavlink_message_t* msg)
{
diff --git a/lib/main/MAVLink/common/mavlink_msg_set_attitude_target.h b/lib/main/MAVLink/common/mavlink_msg_set_attitude_target.h
index e9ed2e044bd..57495342a57 100755
--- a/lib/main/MAVLink/common/mavlink_msg_set_attitude_target.h
+++ b/lib/main/MAVLink/common/mavlink_msg_set_attitude_target.h
@@ -10,7 +10,7 @@ typedef struct __mavlink_set_attitude_target_t {
float body_roll_rate; /*< [rad/s] Body roll rate*/
float body_pitch_rate; /*< [rad/s] Body pitch rate*/
float body_yaw_rate; /*< [rad/s] Body yaw rate*/
- float thrust; /*< Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust)*/
+ float thrust; /*< Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse thrust)*/
uint8_t target_system; /*< System ID*/
uint8_t target_component; /*< Component ID*/
uint8_t type_mask; /*< Bitmap to indicate which dimensions should be ignored by the vehicle.*/
@@ -77,7 +77,7 @@ typedef struct __mavlink_set_attitude_target_t {
* @param body_roll_rate [rad/s] Body roll rate
* @param body_pitch_rate [rad/s] Body pitch rate
* @param body_yaw_rate [rad/s] Body yaw rate
- * @param thrust Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust)
+ * @param thrust Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse thrust)
* @param thrust_body 3D thrust setpoint in the body NED frame, normalized to -1 .. 1
* @return length of the message in bytes (excluding serial stream start sign)
*/
@@ -131,7 +131,7 @@ static inline uint16_t mavlink_msg_set_attitude_target_pack(uint8_t system_id, u
* @param body_roll_rate [rad/s] Body roll rate
* @param body_pitch_rate [rad/s] Body pitch rate
* @param body_yaw_rate [rad/s] Body yaw rate
- * @param thrust Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust)
+ * @param thrust Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse thrust)
* @param thrust_body 3D thrust setpoint in the body NED frame, normalized to -1 .. 1
* @return length of the message in bytes (excluding serial stream start sign)
*/
@@ -188,7 +188,7 @@ static inline uint16_t mavlink_msg_set_attitude_target_pack_status(uint8_t syste
* @param body_roll_rate [rad/s] Body roll rate
* @param body_pitch_rate [rad/s] Body pitch rate
* @param body_yaw_rate [rad/s] Body yaw rate
- * @param thrust Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust)
+ * @param thrust Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse thrust)
* @param thrust_body 3D thrust setpoint in the body NED frame, normalized to -1 .. 1
* @return length of the message in bytes (excluding serial stream start sign)
*/
@@ -281,7 +281,7 @@ static inline uint16_t mavlink_msg_set_attitude_target_encode_status(uint8_t sys
* @param body_roll_rate [rad/s] Body roll rate
* @param body_pitch_rate [rad/s] Body pitch rate
* @param body_yaw_rate [rad/s] Body yaw rate
- * @param thrust Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust)
+ * @param thrust Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse thrust)
* @param thrust_body 3D thrust setpoint in the body NED frame, normalized to -1 .. 1
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
@@ -459,7 +459,7 @@ static inline float mavlink_msg_set_attitude_target_get_body_yaw_rate(const mavl
/**
* @brief Get field thrust from set_attitude_target message
*
- * @return Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust)
+ * @return Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse thrust)
*/
static inline float mavlink_msg_set_attitude_target_get_thrust(const mavlink_message_t* msg)
{
diff --git a/lib/main/MAVLink/common/mavlink_msg_statustext.h b/lib/main/MAVLink/common/mavlink_msg_statustext.h
index 57facb8a5d2..14d98f2b9fe 100755
--- a/lib/main/MAVLink/common/mavlink_msg_statustext.h
+++ b/lib/main/MAVLink/common/mavlink_msg_statustext.h
@@ -6,7 +6,7 @@
MAVPACKED(
typedef struct __mavlink_statustext_t {
uint8_t severity; /*< Severity of status. Relies on the definitions within RFC-5424.*/
- char text[50]; /*< Status text message, without null termination character*/
+ char text[50]; /*< Status text message, without null termination character. UTF-8 encoded.*/
uint16_t id; /*< Unique (opaque) identifier for this statustext message. May be used to reassemble a logical long-statustext message from a sequence of chunks. A value of zero indicates this is the only chunk in the sequence and the message can be emitted immediately.*/
uint8_t chunk_seq; /*< This chunk's sequence number; indexing is from zero. Any null character in the text field is taken to mean this was the last chunk.*/
}) mavlink_statustext_t;
@@ -51,7 +51,7 @@ typedef struct __mavlink_statustext_t {
* @param msg The MAVLink message to compress the data into
*
* @param severity Severity of status. Relies on the definitions within RFC-5424.
- * @param text Status text message, without null termination character
+ * @param text Status text message, without null termination character. UTF-8 encoded.
* @param id Unique (opaque) identifier for this statustext message. May be used to reassemble a logical long-statustext message from a sequence of chunks. A value of zero indicates this is the only chunk in the sequence and the message can be emitted immediately.
* @param chunk_seq This chunk's sequence number; indexing is from zero. Any null character in the text field is taken to mean this was the last chunk.
* @return length of the message in bytes (excluding serial stream start sign)
@@ -87,7 +87,7 @@ static inline uint16_t mavlink_msg_statustext_pack(uint8_t system_id, uint8_t co
* @param msg The MAVLink message to compress the data into
*
* @param severity Severity of status. Relies on the definitions within RFC-5424.
- * @param text Status text message, without null termination character
+ * @param text Status text message, without null termination character. UTF-8 encoded.
* @param id Unique (opaque) identifier for this statustext message. May be used to reassemble a logical long-statustext message from a sequence of chunks. A value of zero indicates this is the only chunk in the sequence and the message can be emitted immediately.
* @param chunk_seq This chunk's sequence number; indexing is from zero. Any null character in the text field is taken to mean this was the last chunk.
* @return length of the message in bytes (excluding serial stream start sign)
@@ -126,7 +126,7 @@ static inline uint16_t mavlink_msg_statustext_pack_status(uint8_t system_id, uin
* @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param severity Severity of status. Relies on the definitions within RFC-5424.
- * @param text Status text message, without null termination character
+ * @param text Status text message, without null termination character. UTF-8 encoded.
* @param id Unique (opaque) identifier for this statustext message. May be used to reassemble a logical long-statustext message from a sequence of chunks. A value of zero indicates this is the only chunk in the sequence and the message can be emitted immediately.
* @param chunk_seq This chunk's sequence number; indexing is from zero. Any null character in the text field is taken to mean this was the last chunk.
* @return length of the message in bytes (excluding serial stream start sign)
@@ -201,7 +201,7 @@ static inline uint16_t mavlink_msg_statustext_encode_status(uint8_t system_id, u
* @param chan MAVLink channel to send the message
*
* @param severity Severity of status. Relies on the definitions within RFC-5424.
- * @param text Status text message, without null termination character
+ * @param text Status text message, without null termination character. UTF-8 encoded.
* @param id Unique (opaque) identifier for this statustext message. May be used to reassemble a logical long-statustext message from a sequence of chunks. A value of zero indicates this is the only chunk in the sequence and the message can be emitted immediately.
* @param chunk_seq This chunk's sequence number; indexing is from zero. Any null character in the text field is taken to mean this was the last chunk.
*/
@@ -286,7 +286,7 @@ static inline uint8_t mavlink_msg_statustext_get_severity(const mavlink_message_
/**
* @brief Get field text from statustext message
*
- * @return Status text message, without null termination character
+ * @return Status text message, without null termination character. UTF-8 encoded.
*/
static inline uint16_t mavlink_msg_statustext_get_text(const mavlink_message_t* msg, char *text)
{
diff --git a/lib/main/MAVLink/common/testsuite.h b/lib/main/MAVLink/common/testsuite.h
index 69e255d6432..acd27b9a9eb 100755
--- a/lib/main/MAVLink/common/testsuite.h
+++ b/lib/main/MAVLink/common/testsuite.h
@@ -1381,73 +1381,6 @@ static void mavlink_test_local_position_ned(uint8_t system_id, uint8_t component
#endif
}
-static void mavlink_test_global_position_int(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_GLOBAL_POSITION_INT >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_global_position_int_t packet_in = {
- 963497464,963497672,963497880,963498088,963498296,18275,18379,18483,18587
- };
- mavlink_global_position_int_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.time_boot_ms = packet_in.time_boot_ms;
- packet1.lat = packet_in.lat;
- packet1.lon = packet_in.lon;
- packet1.alt = packet_in.alt;
- packet1.relative_alt = packet_in.relative_alt;
- packet1.vx = packet_in.vx;
- packet1.vy = packet_in.vy;
- packet1.vz = packet_in.vz;
- packet1.hdg = packet_in.hdg;
-
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_GLOBAL_POSITION_INT_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_GLOBAL_POSITION_INT_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_global_position_int_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_global_position_int_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_global_position_int_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.lat , packet1.lon , packet1.alt , packet1.relative_alt , packet1.vx , packet1.vy , packet1.vz , packet1.hdg );
- mavlink_msg_global_position_int_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_global_position_int_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.lat , packet1.lon , packet1.alt , packet1.relative_alt , packet1.vx , packet1.vy , packet1.vz , packet1.hdg );
- mavlink_msg_global_position_int_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_AIRSPEED >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_airspeed_t packet_in = {
+ 17.0,45.0,17651,163,230
+ };
+ mavlink_airspeed_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.airspeed = packet_in.airspeed;
+ packet1.raw_press = packet_in.raw_press;
+ packet1.temperature = packet_in.temperature;
+ packet1.id = packet_in.id;
+ packet1.flags = packet_in.flags;
+
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_AIRSPEED_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_AIRSPEED_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_airspeed_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_airspeed_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_airspeed_pack(system_id, component_id, &msg , packet1.id , packet1.airspeed , packet1.temperature , packet1.raw_press , packet1.flags );
+ mavlink_msg_airspeed_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_airspeed_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.id , packet1.airspeed , packet1.temperature , packet1.raw_press , packet1.flags );
+ mavlink_msg_airspeed_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_GLOBAL_POSITION_SENSOR >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_global_position_sensor_t packet_in = {
+ 93372036854775807ULL,963497880,963498088,963498296,157.0,185.0,213.0,241.0,113,180,247,58,125
+ };
+ mavlink_global_position_sensor_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.time_usec = packet_in.time_usec;
+ packet1.processing_time = packet_in.processing_time;
+ packet1.lat = packet_in.lat;
+ packet1.lon = packet_in.lon;
+ packet1.alt_ellipsoid = packet_in.alt_ellipsoid;
+ packet1.alt = packet_in.alt;
+ packet1.eph = packet_in.eph;
+ packet1.epv = packet_in.epv;
+ packet1.target_system = packet_in.target_system;
+ packet1.target_component = packet_in.target_component;
+ packet1.id = packet_in.id;
+ packet1.source = packet_in.source;
+ packet1.flags = packet_in.flags;
+
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_GLOBAL_POSITION_SENSOR_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_GLOBAL_POSITION_SENSOR_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_global_position_sensor_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_global_position_sensor_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_global_position_sensor_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.id , packet1.time_usec , packet1.processing_time , packet1.source , packet1.flags , packet1.lat , packet1.lon , packet1.alt_ellipsoid , packet1.alt , packet1.eph , packet1.epv );
+ mavlink_msg_global_position_sensor_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_global_position_sensor_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.id , packet1.time_usec , packet1.processing_time , packet1.source , packet1.flags , packet1.lat , packet1.lon , packet1.alt_ellipsoid , packet1.alt , packet1.eph , packet1.epv );
+ mavlink_msg_global_position_sensor_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_PROTOCOL_VERSION >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_protocol_version_t packet_in = {
+ 17235,17339,17443,{ 151, 152, 153, 154, 155, 156, 157, 158 },{ 175, 176, 177, 178, 179, 180, 181, 182 }
+ };
+ mavlink_protocol_version_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.version = packet_in.version;
+ packet1.min_version = packet_in.min_version;
+ packet1.max_version = packet_in.max_version;
+
+ mav_array_memcpy(packet1.spec_version_hash, packet_in.spec_version_hash, sizeof(uint8_t)*8);
+ mav_array_memcpy(packet1.library_version_hash, packet_in.library_version_hash, sizeof(uint8_t)*8);
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_PROTOCOL_VERSION_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_PROTOCOL_VERSION_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_protocol_version_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_protocol_version_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_protocol_version_pack(system_id, component_id, &msg , packet1.version , packet1.min_version , packet1.max_version , packet1.spec_version_hash , packet1.library_version_hash );
+ mavlink_msg_protocol_version_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_protocol_version_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.version , packet1.min_version , packet1.max_version , packet1.spec_version_hash , packet1.library_version_hash );
+ mavlink_msg_protocol_version_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_PARAM_ERROR >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_param_error_t packet_in = {
+ 17235,139,206,"EFGHIJKLMNOPQRS",65
+ };
+ mavlink_param_error_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.param_index = packet_in.param_index;
+ packet1.target_system = packet_in.target_system;
+ packet1.target_component = packet_in.target_component;
+ packet1.error = packet_in.error;
+
+ mav_array_memcpy(packet1.param_id, packet_in.param_id, sizeof(char)*16);
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_PARAM_ERROR_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_PARAM_ERROR_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_param_error_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_param_error_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_param_error_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.param_id , packet1.param_index , packet1.error );
+ mavlink_msg_param_error_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_param_error_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.param_id , packet1.param_index , packet1.error );
+ mavlink_msg_param_error_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_FIGURE_EIGHT_EXECUTION_STATUS >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_figure_eight_execution_status_t packet_in = {
+ 93372036854775807ULL,73.0,101.0,129.0,963498504,963498712,213.0,101
+ };
+ mavlink_figure_eight_execution_status_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.time_usec = packet_in.time_usec;
+ packet1.major_radius = packet_in.major_radius;
+ packet1.minor_radius = packet_in.minor_radius;
+ packet1.orientation = packet_in.orientation;
+ packet1.x = packet_in.x;
+ packet1.y = packet_in.y;
+ packet1.z = packet_in.z;
+ packet1.frame = packet_in.frame;
+
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_FIGURE_EIGHT_EXECUTION_STATUS_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_FIGURE_EIGHT_EXECUTION_STATUS_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_figure_eight_execution_status_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_figure_eight_execution_status_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_figure_eight_execution_status_pack(system_id, component_id, &msg , packet1.time_usec , packet1.major_radius , packet1.minor_radius , packet1.orientation , packet1.frame , packet1.x , packet1.y , packet1.z );
+ mavlink_msg_figure_eight_execution_status_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_figure_eight_execution_status_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.major_radius , packet1.minor_radius , packet1.orientation , packet1.frame , packet1.x , packet1.y , packet1.z );
+ mavlink_msg_figure_eight_execution_status_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_RELAY_STATUS >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_relay_status_t packet_in = {
+ 963497464,17443,17547
+ };
+ mavlink_relay_status_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.time_boot_ms = packet_in.time_boot_ms;
+ packet1.on = packet_in.on;
+ packet1.present = packet_in.present;
+
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_RELAY_STATUS_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_RELAY_STATUS_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_relay_status_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_relay_status_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_relay_status_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.on , packet1.present );
+ mavlink_msg_relay_status_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_relay_status_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.on , packet1.present );
+ mavlink_msg_relay_status_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; imsgid = MAVLINK_MSG_ID_AIRLINK_AUTH;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_AIRLINK_AUTH_MIN_LEN, MAVLINK_MSG_ID_AIRLINK_AUTH_LEN, MAVLINK_MSG_ID_AIRLINK_AUTH_CRC);
+}
+
+/**
+ * @brief Pack a airlink_auth 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 login Login
+ * @param password Password
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_airlink_auth_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ const char *login, const char *password)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_AIRLINK_AUTH_LEN];
+
+ _mav_put_char_array(buf, 0, login, 50);
+ _mav_put_char_array(buf, 50, password, 50);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AIRLINK_AUTH_LEN);
+#else
+ mavlink_airlink_auth_t packet;
+
+ mav_array_memcpy(packet.login, login, sizeof(char)*50);
+ mav_array_memcpy(packet.password, password, sizeof(char)*50);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AIRLINK_AUTH_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_AIRLINK_AUTH;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_AIRLINK_AUTH_MIN_LEN, MAVLINK_MSG_ID_AIRLINK_AUTH_LEN, MAVLINK_MSG_ID_AIRLINK_AUTH_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_AIRLINK_AUTH_MIN_LEN, MAVLINK_MSG_ID_AIRLINK_AUTH_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a airlink_auth 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 login Login
+ * @param password Password
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_airlink_auth_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ const char *login,const char *password)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_AIRLINK_AUTH_LEN];
+
+ _mav_put_char_array(buf, 0, login, 50);
+ _mav_put_char_array(buf, 50, password, 50);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AIRLINK_AUTH_LEN);
+#else
+ mavlink_airlink_auth_t packet;
+
+ mav_array_assign_char(packet.login, login, 50);
+ mav_array_assign_char(packet.password, password, 50);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AIRLINK_AUTH_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_AIRLINK_AUTH;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_AIRLINK_AUTH_MIN_LEN, MAVLINK_MSG_ID_AIRLINK_AUTH_LEN, MAVLINK_MSG_ID_AIRLINK_AUTH_CRC);
+}
+
+/**
+ * @brief Encode a airlink_auth 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 airlink_auth C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_airlink_auth_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_airlink_auth_t* airlink_auth)
+{
+ return mavlink_msg_airlink_auth_pack(system_id, component_id, msg, airlink_auth->login, airlink_auth->password);
+}
+
+/**
+ * @brief Encode a airlink_auth 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 airlink_auth C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_airlink_auth_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_airlink_auth_t* airlink_auth)
+{
+ return mavlink_msg_airlink_auth_pack_chan(system_id, component_id, chan, msg, airlink_auth->login, airlink_auth->password);
+}
+
+/**
+ * @brief Encode a airlink_auth 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 airlink_auth C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_airlink_auth_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_airlink_auth_t* airlink_auth)
+{
+ return mavlink_msg_airlink_auth_pack_status(system_id, component_id, _status, msg, airlink_auth->login, airlink_auth->password);
+}
+
+/**
+ * @brief Send a airlink_auth message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param login Login
+ * @param password Password
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_airlink_auth_send(mavlink_channel_t chan, const char *login, const char *password)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_AIRLINK_AUTH_LEN];
+
+ _mav_put_char_array(buf, 0, login, 50);
+ _mav_put_char_array(buf, 50, password, 50);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AIRLINK_AUTH, buf, MAVLINK_MSG_ID_AIRLINK_AUTH_MIN_LEN, MAVLINK_MSG_ID_AIRLINK_AUTH_LEN, MAVLINK_MSG_ID_AIRLINK_AUTH_CRC);
+#else
+ mavlink_airlink_auth_t packet;
+
+ mav_array_assign_char(packet.login, login, 50);
+ mav_array_assign_char(packet.password, password, 50);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AIRLINK_AUTH, (const char *)&packet, MAVLINK_MSG_ID_AIRLINK_AUTH_MIN_LEN, MAVLINK_MSG_ID_AIRLINK_AUTH_LEN, MAVLINK_MSG_ID_AIRLINK_AUTH_CRC);
+#endif
+}
+
+/**
+ * @brief Send a airlink_auth message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_airlink_auth_send_struct(mavlink_channel_t chan, const mavlink_airlink_auth_t* airlink_auth)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_airlink_auth_send(chan, airlink_auth->login, airlink_auth->password);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AIRLINK_AUTH, (const char *)airlink_auth, MAVLINK_MSG_ID_AIRLINK_AUTH_MIN_LEN, MAVLINK_MSG_ID_AIRLINK_AUTH_LEN, MAVLINK_MSG_ID_AIRLINK_AUTH_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_AIRLINK_AUTH_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_airlink_auth_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, const char *login, const char *password)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+
+ _mav_put_char_array(buf, 0, login, 50);
+ _mav_put_char_array(buf, 50, password, 50);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AIRLINK_AUTH, buf, MAVLINK_MSG_ID_AIRLINK_AUTH_MIN_LEN, MAVLINK_MSG_ID_AIRLINK_AUTH_LEN, MAVLINK_MSG_ID_AIRLINK_AUTH_CRC);
+#else
+ mavlink_airlink_auth_t *packet = (mavlink_airlink_auth_t *)msgbuf;
+
+ mav_array_assign_char(packet->login, login, 50);
+ mav_array_assign_char(packet->password, password, 50);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AIRLINK_AUTH, (const char *)packet, MAVLINK_MSG_ID_AIRLINK_AUTH_MIN_LEN, MAVLINK_MSG_ID_AIRLINK_AUTH_LEN, MAVLINK_MSG_ID_AIRLINK_AUTH_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE AIRLINK_AUTH UNPACKING
+
+
+/**
+ * @brief Get field login from airlink_auth message
+ *
+ * @return Login
+ */
+static inline uint16_t mavlink_msg_airlink_auth_get_login(const mavlink_message_t* msg, char *login)
+{
+ return _MAV_RETURN_char_array(msg, login, 50, 0);
+}
+
+/**
+ * @brief Get field password from airlink_auth message
+ *
+ * @return Password
+ */
+static inline uint16_t mavlink_msg_airlink_auth_get_password(const mavlink_message_t* msg, char *password)
+{
+ return _MAV_RETURN_char_array(msg, password, 50, 50);
+}
+
+/**
+ * @brief Decode a airlink_auth message into a struct
+ *
+ * @param msg The message to decode
+ * @param airlink_auth C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_airlink_auth_decode(const mavlink_message_t* msg, mavlink_airlink_auth_t* airlink_auth)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_airlink_auth_get_login(msg, airlink_auth->login);
+ mavlink_msg_airlink_auth_get_password(msg, airlink_auth->password);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_AIRLINK_AUTH_LEN? msg->len : MAVLINK_MSG_ID_AIRLINK_AUTH_LEN;
+ memset(airlink_auth, 0, MAVLINK_MSG_ID_AIRLINK_AUTH_LEN);
+ memcpy(airlink_auth, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/csAirLink/mavlink_msg_airlink_auth_response.h b/lib/main/MAVLink/csAirLink/mavlink_msg_airlink_auth_response.h
new file mode 100644
index 00000000000..ba35a3307bf
--- /dev/null
+++ b/lib/main/MAVLink/csAirLink/mavlink_msg_airlink_auth_response.h
@@ -0,0 +1,260 @@
+#pragma once
+// MESSAGE AIRLINK_AUTH_RESPONSE PACKING
+
+#define MAVLINK_MSG_ID_AIRLINK_AUTH_RESPONSE 52001
+
+
+typedef struct __mavlink_airlink_auth_response_t {
+ uint8_t resp_type; /*< Response type*/
+} mavlink_airlink_auth_response_t;
+
+#define MAVLINK_MSG_ID_AIRLINK_AUTH_RESPONSE_LEN 1
+#define MAVLINK_MSG_ID_AIRLINK_AUTH_RESPONSE_MIN_LEN 1
+#define MAVLINK_MSG_ID_52001_LEN 1
+#define MAVLINK_MSG_ID_52001_MIN_LEN 1
+
+#define MAVLINK_MSG_ID_AIRLINK_AUTH_RESPONSE_CRC 239
+#define MAVLINK_MSG_ID_52001_CRC 239
+
+
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_AIRLINK_AUTH_RESPONSE { \
+ 52001, \
+ "AIRLINK_AUTH_RESPONSE", \
+ 1, \
+ { { "resp_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_airlink_auth_response_t, resp_type) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_AIRLINK_AUTH_RESPONSE { \
+ "AIRLINK_AUTH_RESPONSE", \
+ 1, \
+ { { "resp_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_airlink_auth_response_t, resp_type) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a airlink_auth_response 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 resp_type Response type
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_airlink_auth_response_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint8_t resp_type)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_AIRLINK_AUTH_RESPONSE_LEN];
+ _mav_put_uint8_t(buf, 0, resp_type);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AIRLINK_AUTH_RESPONSE_LEN);
+#else
+ mavlink_airlink_auth_response_t packet;
+ packet.resp_type = resp_type;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AIRLINK_AUTH_RESPONSE_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_AIRLINK_AUTH_RESPONSE;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_AIRLINK_AUTH_RESPONSE_MIN_LEN, MAVLINK_MSG_ID_AIRLINK_AUTH_RESPONSE_LEN, MAVLINK_MSG_ID_AIRLINK_AUTH_RESPONSE_CRC);
+}
+
+/**
+ * @brief Pack a airlink_auth_response 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 resp_type Response type
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_airlink_auth_response_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ uint8_t resp_type)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_AIRLINK_AUTH_RESPONSE_LEN];
+ _mav_put_uint8_t(buf, 0, resp_type);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AIRLINK_AUTH_RESPONSE_LEN);
+#else
+ mavlink_airlink_auth_response_t packet;
+ packet.resp_type = resp_type;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AIRLINK_AUTH_RESPONSE_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_AIRLINK_AUTH_RESPONSE;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_AIRLINK_AUTH_RESPONSE_MIN_LEN, MAVLINK_MSG_ID_AIRLINK_AUTH_RESPONSE_LEN, MAVLINK_MSG_ID_AIRLINK_AUTH_RESPONSE_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_AIRLINK_AUTH_RESPONSE_MIN_LEN, MAVLINK_MSG_ID_AIRLINK_AUTH_RESPONSE_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a airlink_auth_response 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 resp_type Response type
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_airlink_auth_response_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint8_t resp_type)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_AIRLINK_AUTH_RESPONSE_LEN];
+ _mav_put_uint8_t(buf, 0, resp_type);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AIRLINK_AUTH_RESPONSE_LEN);
+#else
+ mavlink_airlink_auth_response_t packet;
+ packet.resp_type = resp_type;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AIRLINK_AUTH_RESPONSE_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_AIRLINK_AUTH_RESPONSE;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_AIRLINK_AUTH_RESPONSE_MIN_LEN, MAVLINK_MSG_ID_AIRLINK_AUTH_RESPONSE_LEN, MAVLINK_MSG_ID_AIRLINK_AUTH_RESPONSE_CRC);
+}
+
+/**
+ * @brief Encode a airlink_auth_response 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 airlink_auth_response C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_airlink_auth_response_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_airlink_auth_response_t* airlink_auth_response)
+{
+ return mavlink_msg_airlink_auth_response_pack(system_id, component_id, msg, airlink_auth_response->resp_type);
+}
+
+/**
+ * @brief Encode a airlink_auth_response 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 airlink_auth_response C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_airlink_auth_response_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_airlink_auth_response_t* airlink_auth_response)
+{
+ return mavlink_msg_airlink_auth_response_pack_chan(system_id, component_id, chan, msg, airlink_auth_response->resp_type);
+}
+
+/**
+ * @brief Encode a airlink_auth_response 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 airlink_auth_response C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_airlink_auth_response_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_airlink_auth_response_t* airlink_auth_response)
+{
+ return mavlink_msg_airlink_auth_response_pack_status(system_id, component_id, _status, msg, airlink_auth_response->resp_type);
+}
+
+/**
+ * @brief Send a airlink_auth_response message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param resp_type Response type
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_airlink_auth_response_send(mavlink_channel_t chan, uint8_t resp_type)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_AIRLINK_AUTH_RESPONSE_LEN];
+ _mav_put_uint8_t(buf, 0, resp_type);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AIRLINK_AUTH_RESPONSE, buf, MAVLINK_MSG_ID_AIRLINK_AUTH_RESPONSE_MIN_LEN, MAVLINK_MSG_ID_AIRLINK_AUTH_RESPONSE_LEN, MAVLINK_MSG_ID_AIRLINK_AUTH_RESPONSE_CRC);
+#else
+ mavlink_airlink_auth_response_t packet;
+ packet.resp_type = resp_type;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AIRLINK_AUTH_RESPONSE, (const char *)&packet, MAVLINK_MSG_ID_AIRLINK_AUTH_RESPONSE_MIN_LEN, MAVLINK_MSG_ID_AIRLINK_AUTH_RESPONSE_LEN, MAVLINK_MSG_ID_AIRLINK_AUTH_RESPONSE_CRC);
+#endif
+}
+
+/**
+ * @brief Send a airlink_auth_response message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_airlink_auth_response_send_struct(mavlink_channel_t chan, const mavlink_airlink_auth_response_t* airlink_auth_response)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_airlink_auth_response_send(chan, airlink_auth_response->resp_type);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AIRLINK_AUTH_RESPONSE, (const char *)airlink_auth_response, MAVLINK_MSG_ID_AIRLINK_AUTH_RESPONSE_MIN_LEN, MAVLINK_MSG_ID_AIRLINK_AUTH_RESPONSE_LEN, MAVLINK_MSG_ID_AIRLINK_AUTH_RESPONSE_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_AIRLINK_AUTH_RESPONSE_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_airlink_auth_response_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t resp_type)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint8_t(buf, 0, resp_type);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AIRLINK_AUTH_RESPONSE, buf, MAVLINK_MSG_ID_AIRLINK_AUTH_RESPONSE_MIN_LEN, MAVLINK_MSG_ID_AIRLINK_AUTH_RESPONSE_LEN, MAVLINK_MSG_ID_AIRLINK_AUTH_RESPONSE_CRC);
+#else
+ mavlink_airlink_auth_response_t *packet = (mavlink_airlink_auth_response_t *)msgbuf;
+ packet->resp_type = resp_type;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AIRLINK_AUTH_RESPONSE, (const char *)packet, MAVLINK_MSG_ID_AIRLINK_AUTH_RESPONSE_MIN_LEN, MAVLINK_MSG_ID_AIRLINK_AUTH_RESPONSE_LEN, MAVLINK_MSG_ID_AIRLINK_AUTH_RESPONSE_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE AIRLINK_AUTH_RESPONSE UNPACKING
+
+
+/**
+ * @brief Get field resp_type from airlink_auth_response message
+ *
+ * @return Response type
+ */
+static inline uint8_t mavlink_msg_airlink_auth_response_get_resp_type(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 0);
+}
+
+/**
+ * @brief Decode a airlink_auth_response message into a struct
+ *
+ * @param msg The message to decode
+ * @param airlink_auth_response C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_airlink_auth_response_decode(const mavlink_message_t* msg, mavlink_airlink_auth_response_t* airlink_auth_response)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ airlink_auth_response->resp_type = mavlink_msg_airlink_auth_response_get_resp_type(msg);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_AIRLINK_AUTH_RESPONSE_LEN? msg->len : MAVLINK_MSG_ID_AIRLINK_AUTH_RESPONSE_LEN;
+ memset(airlink_auth_response, 0, MAVLINK_MSG_ID_AIRLINK_AUTH_RESPONSE_LEN);
+ memcpy(airlink_auth_response, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/csAirLink/testsuite.h b/lib/main/MAVLink/csAirLink/testsuite.h
new file mode 100644
index 00000000000..17aaa534e67
--- /dev/null
+++ b/lib/main/MAVLink/csAirLink/testsuite.h
@@ -0,0 +1,156 @@
+/** @file
+ * @brief MAVLink comm protocol testsuite generated from csAirLink.xml
+ * @see https://mavlink.io/en/
+ */
+#pragma once
+#ifndef CSAIRLINK_TESTSUITE_H
+#define CSAIRLINK_TESTSUITE_H
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+#ifndef MAVLINK_TEST_ALL
+#define MAVLINK_TEST_ALL
+
+static void mavlink_test_csAirLink(uint8_t, uint8_t, mavlink_message_t *last_msg);
+
+static void mavlink_test_all(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
+{
+
+ mavlink_test_csAirLink(system_id, component_id, last_msg);
+}
+#endif
+
+
+
+
+static void mavlink_test_airlink_auth(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_AIRLINK_AUTH >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_airlink_auth_t packet_in = {
+ "ABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVW","YZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTU"
+ };
+ mavlink_airlink_auth_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+
+ mav_array_memcpy(packet1.login, packet_in.login, sizeof(char)*50);
+ mav_array_memcpy(packet1.password, packet_in.password, sizeof(char)*50);
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_AIRLINK_AUTH_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_AIRLINK_AUTH_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_airlink_auth_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_airlink_auth_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_airlink_auth_pack(system_id, component_id, &msg , packet1.login , packet1.password );
+ mavlink_msg_airlink_auth_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_airlink_auth_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.login , packet1.password );
+ mavlink_msg_airlink_auth_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_AIRLINK_AUTH_RESPONSE >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_airlink_auth_response_t packet_in = {
+ 5
+ };
+ mavlink_airlink_auth_response_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.resp_type = packet_in.resp_type;
+
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_AIRLINK_AUTH_RESPONSE_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_AIRLINK_AUTH_RESPONSE_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_airlink_auth_response_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_airlink_auth_response_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_airlink_auth_response_pack(system_id, component_id, &msg , packet1.resp_type );
+ mavlink_msg_airlink_auth_response_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_airlink_auth_response_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.resp_type );
+ mavlink_msg_airlink_auth_response_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; imsgid = MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_RESP;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_RESP_MIN_LEN, MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_RESP_LEN, MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_RESP_CRC);
+}
+
+/**
+ * @brief Pack a cubepilot_firmware_update_resp 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 target_system System ID.
+ * @param target_component Component ID.
+ * @param offset [bytes] FW Offset.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_cubepilot_firmware_update_resp_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ uint8_t target_system, uint8_t target_component, uint32_t offset)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_RESP_LEN];
+ _mav_put_uint32_t(buf, 0, offset);
+ _mav_put_uint8_t(buf, 4, target_system);
+ _mav_put_uint8_t(buf, 5, target_component);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_RESP_LEN);
+#else
+ mavlink_cubepilot_firmware_update_resp_t packet;
+ packet.offset = offset;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_RESP_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_RESP;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_RESP_MIN_LEN, MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_RESP_LEN, MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_RESP_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_RESP_MIN_LEN, MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_RESP_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a cubepilot_firmware_update_resp 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 target_system System ID.
+ * @param target_component Component ID.
+ * @param offset [bytes] FW Offset.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_cubepilot_firmware_update_resp_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint8_t target_system,uint8_t target_component,uint32_t offset)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_RESP_LEN];
+ _mav_put_uint32_t(buf, 0, offset);
+ _mav_put_uint8_t(buf, 4, target_system);
+ _mav_put_uint8_t(buf, 5, target_component);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_RESP_LEN);
+#else
+ mavlink_cubepilot_firmware_update_resp_t packet;
+ packet.offset = offset;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_RESP_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_RESP;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_RESP_MIN_LEN, MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_RESP_LEN, MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_RESP_CRC);
+}
+
+/**
+ * @brief Encode a cubepilot_firmware_update_resp 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 cubepilot_firmware_update_resp C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_cubepilot_firmware_update_resp_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_cubepilot_firmware_update_resp_t* cubepilot_firmware_update_resp)
+{
+ return mavlink_msg_cubepilot_firmware_update_resp_pack(system_id, component_id, msg, cubepilot_firmware_update_resp->target_system, cubepilot_firmware_update_resp->target_component, cubepilot_firmware_update_resp->offset);
+}
+
+/**
+ * @brief Encode a cubepilot_firmware_update_resp 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 cubepilot_firmware_update_resp C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_cubepilot_firmware_update_resp_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_cubepilot_firmware_update_resp_t* cubepilot_firmware_update_resp)
+{
+ return mavlink_msg_cubepilot_firmware_update_resp_pack_chan(system_id, component_id, chan, msg, cubepilot_firmware_update_resp->target_system, cubepilot_firmware_update_resp->target_component, cubepilot_firmware_update_resp->offset);
+}
+
+/**
+ * @brief Encode a cubepilot_firmware_update_resp 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 cubepilot_firmware_update_resp C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_cubepilot_firmware_update_resp_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_cubepilot_firmware_update_resp_t* cubepilot_firmware_update_resp)
+{
+ return mavlink_msg_cubepilot_firmware_update_resp_pack_status(system_id, component_id, _status, msg, cubepilot_firmware_update_resp->target_system, cubepilot_firmware_update_resp->target_component, cubepilot_firmware_update_resp->offset);
+}
+
+/**
+ * @brief Send a cubepilot_firmware_update_resp message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param target_system System ID.
+ * @param target_component Component ID.
+ * @param offset [bytes] FW Offset.
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_cubepilot_firmware_update_resp_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint32_t offset)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_RESP_LEN];
+ _mav_put_uint32_t(buf, 0, offset);
+ _mav_put_uint8_t(buf, 4, target_system);
+ _mav_put_uint8_t(buf, 5, target_component);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_RESP, buf, MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_RESP_MIN_LEN, MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_RESP_LEN, MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_RESP_CRC);
+#else
+ mavlink_cubepilot_firmware_update_resp_t packet;
+ packet.offset = offset;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_RESP, (const char *)&packet, MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_RESP_MIN_LEN, MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_RESP_LEN, MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_RESP_CRC);
+#endif
+}
+
+/**
+ * @brief Send a cubepilot_firmware_update_resp message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_cubepilot_firmware_update_resp_send_struct(mavlink_channel_t chan, const mavlink_cubepilot_firmware_update_resp_t* cubepilot_firmware_update_resp)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_cubepilot_firmware_update_resp_send(chan, cubepilot_firmware_update_resp->target_system, cubepilot_firmware_update_resp->target_component, cubepilot_firmware_update_resp->offset);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_RESP, (const char *)cubepilot_firmware_update_resp, MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_RESP_MIN_LEN, MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_RESP_LEN, MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_RESP_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_RESP_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_cubepilot_firmware_update_resp_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint32_t offset)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint32_t(buf, 0, offset);
+ _mav_put_uint8_t(buf, 4, target_system);
+ _mav_put_uint8_t(buf, 5, target_component);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_RESP, buf, MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_RESP_MIN_LEN, MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_RESP_LEN, MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_RESP_CRC);
+#else
+ mavlink_cubepilot_firmware_update_resp_t *packet = (mavlink_cubepilot_firmware_update_resp_t *)msgbuf;
+ packet->offset = offset;
+ packet->target_system = target_system;
+ packet->target_component = target_component;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_RESP, (const char *)packet, MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_RESP_MIN_LEN, MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_RESP_LEN, MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_RESP_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE CUBEPILOT_FIRMWARE_UPDATE_RESP UNPACKING
+
+
+/**
+ * @brief Get field target_system from cubepilot_firmware_update_resp message
+ *
+ * @return System ID.
+ */
+static inline uint8_t mavlink_msg_cubepilot_firmware_update_resp_get_target_system(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 4);
+}
+
+/**
+ * @brief Get field target_component from cubepilot_firmware_update_resp message
+ *
+ * @return Component ID.
+ */
+static inline uint8_t mavlink_msg_cubepilot_firmware_update_resp_get_target_component(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 5);
+}
+
+/**
+ * @brief Get field offset from cubepilot_firmware_update_resp message
+ *
+ * @return [bytes] FW Offset.
+ */
+static inline uint32_t mavlink_msg_cubepilot_firmware_update_resp_get_offset(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint32_t(msg, 0);
+}
+
+/**
+ * @brief Decode a cubepilot_firmware_update_resp message into a struct
+ *
+ * @param msg The message to decode
+ * @param cubepilot_firmware_update_resp C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_cubepilot_firmware_update_resp_decode(const mavlink_message_t* msg, mavlink_cubepilot_firmware_update_resp_t* cubepilot_firmware_update_resp)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ cubepilot_firmware_update_resp->offset = mavlink_msg_cubepilot_firmware_update_resp_get_offset(msg);
+ cubepilot_firmware_update_resp->target_system = mavlink_msg_cubepilot_firmware_update_resp_get_target_system(msg);
+ cubepilot_firmware_update_resp->target_component = mavlink_msg_cubepilot_firmware_update_resp_get_target_component(msg);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_RESP_LEN? msg->len : MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_RESP_LEN;
+ memset(cubepilot_firmware_update_resp, 0, MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_RESP_LEN);
+ memcpy(cubepilot_firmware_update_resp, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/cubepilot/mavlink_msg_cubepilot_firmware_update_start.h b/lib/main/MAVLink/cubepilot/mavlink_msg_cubepilot_firmware_update_start.h
new file mode 100644
index 00000000000..8f0e6557b47
--- /dev/null
+++ b/lib/main/MAVLink/cubepilot/mavlink_msg_cubepilot_firmware_update_start.h
@@ -0,0 +1,344 @@
+#pragma once
+// MESSAGE CUBEPILOT_FIRMWARE_UPDATE_START PACKING
+
+#define MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_START 50004
+
+
+typedef struct __mavlink_cubepilot_firmware_update_start_t {
+ uint32_t size; /*< [bytes] FW Size.*/
+ uint32_t crc; /*< FW CRC.*/
+ uint8_t target_system; /*< System ID.*/
+ uint8_t target_component; /*< Component ID.*/
+} mavlink_cubepilot_firmware_update_start_t;
+
+#define MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_START_LEN 10
+#define MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_START_MIN_LEN 10
+#define MAVLINK_MSG_ID_50004_LEN 10
+#define MAVLINK_MSG_ID_50004_MIN_LEN 10
+
+#define MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_START_CRC 240
+#define MAVLINK_MSG_ID_50004_CRC 240
+
+
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_CUBEPILOT_FIRMWARE_UPDATE_START { \
+ 50004, \
+ "CUBEPILOT_FIRMWARE_UPDATE_START", \
+ 4, \
+ { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_cubepilot_firmware_update_start_t, target_system) }, \
+ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_cubepilot_firmware_update_start_t, target_component) }, \
+ { "size", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_cubepilot_firmware_update_start_t, size) }, \
+ { "crc", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_cubepilot_firmware_update_start_t, crc) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_CUBEPILOT_FIRMWARE_UPDATE_START { \
+ "CUBEPILOT_FIRMWARE_UPDATE_START", \
+ 4, \
+ { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_cubepilot_firmware_update_start_t, target_system) }, \
+ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_cubepilot_firmware_update_start_t, target_component) }, \
+ { "size", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_cubepilot_firmware_update_start_t, size) }, \
+ { "crc", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_cubepilot_firmware_update_start_t, crc) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a cubepilot_firmware_update_start 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 target_system System ID.
+ * @param target_component Component ID.
+ * @param size [bytes] FW Size.
+ * @param crc FW CRC.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_cubepilot_firmware_update_start_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint8_t target_system, uint8_t target_component, uint32_t size, uint32_t crc)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_START_LEN];
+ _mav_put_uint32_t(buf, 0, size);
+ _mav_put_uint32_t(buf, 4, crc);
+ _mav_put_uint8_t(buf, 8, target_system);
+ _mav_put_uint8_t(buf, 9, target_component);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_START_LEN);
+#else
+ mavlink_cubepilot_firmware_update_start_t packet;
+ packet.size = size;
+ packet.crc = crc;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_START_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_START;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_START_MIN_LEN, MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_START_LEN, MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_START_CRC);
+}
+
+/**
+ * @brief Pack a cubepilot_firmware_update_start 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 target_system System ID.
+ * @param target_component Component ID.
+ * @param size [bytes] FW Size.
+ * @param crc FW CRC.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_cubepilot_firmware_update_start_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ uint8_t target_system, uint8_t target_component, uint32_t size, uint32_t crc)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_START_LEN];
+ _mav_put_uint32_t(buf, 0, size);
+ _mav_put_uint32_t(buf, 4, crc);
+ _mav_put_uint8_t(buf, 8, target_system);
+ _mav_put_uint8_t(buf, 9, target_component);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_START_LEN);
+#else
+ mavlink_cubepilot_firmware_update_start_t packet;
+ packet.size = size;
+ packet.crc = crc;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_START_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_START;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_START_MIN_LEN, MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_START_LEN, MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_START_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_START_MIN_LEN, MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_START_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a cubepilot_firmware_update_start 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 target_system System ID.
+ * @param target_component Component ID.
+ * @param size [bytes] FW Size.
+ * @param crc FW CRC.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_cubepilot_firmware_update_start_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint8_t target_system,uint8_t target_component,uint32_t size,uint32_t crc)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_START_LEN];
+ _mav_put_uint32_t(buf, 0, size);
+ _mav_put_uint32_t(buf, 4, crc);
+ _mav_put_uint8_t(buf, 8, target_system);
+ _mav_put_uint8_t(buf, 9, target_component);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_START_LEN);
+#else
+ mavlink_cubepilot_firmware_update_start_t packet;
+ packet.size = size;
+ packet.crc = crc;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_START_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_START;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_START_MIN_LEN, MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_START_LEN, MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_START_CRC);
+}
+
+/**
+ * @brief Encode a cubepilot_firmware_update_start 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 cubepilot_firmware_update_start C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_cubepilot_firmware_update_start_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_cubepilot_firmware_update_start_t* cubepilot_firmware_update_start)
+{
+ return mavlink_msg_cubepilot_firmware_update_start_pack(system_id, component_id, msg, cubepilot_firmware_update_start->target_system, cubepilot_firmware_update_start->target_component, cubepilot_firmware_update_start->size, cubepilot_firmware_update_start->crc);
+}
+
+/**
+ * @brief Encode a cubepilot_firmware_update_start 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 cubepilot_firmware_update_start C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_cubepilot_firmware_update_start_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_cubepilot_firmware_update_start_t* cubepilot_firmware_update_start)
+{
+ return mavlink_msg_cubepilot_firmware_update_start_pack_chan(system_id, component_id, chan, msg, cubepilot_firmware_update_start->target_system, cubepilot_firmware_update_start->target_component, cubepilot_firmware_update_start->size, cubepilot_firmware_update_start->crc);
+}
+
+/**
+ * @brief Encode a cubepilot_firmware_update_start 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 cubepilot_firmware_update_start C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_cubepilot_firmware_update_start_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_cubepilot_firmware_update_start_t* cubepilot_firmware_update_start)
+{
+ return mavlink_msg_cubepilot_firmware_update_start_pack_status(system_id, component_id, _status, msg, cubepilot_firmware_update_start->target_system, cubepilot_firmware_update_start->target_component, cubepilot_firmware_update_start->size, cubepilot_firmware_update_start->crc);
+}
+
+/**
+ * @brief Send a cubepilot_firmware_update_start message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param target_system System ID.
+ * @param target_component Component ID.
+ * @param size [bytes] FW Size.
+ * @param crc FW CRC.
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_cubepilot_firmware_update_start_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint32_t size, uint32_t crc)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_START_LEN];
+ _mav_put_uint32_t(buf, 0, size);
+ _mav_put_uint32_t(buf, 4, crc);
+ _mav_put_uint8_t(buf, 8, target_system);
+ _mav_put_uint8_t(buf, 9, target_component);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_START, buf, MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_START_MIN_LEN, MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_START_LEN, MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_START_CRC);
+#else
+ mavlink_cubepilot_firmware_update_start_t packet;
+ packet.size = size;
+ packet.crc = crc;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_START, (const char *)&packet, MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_START_MIN_LEN, MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_START_LEN, MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_START_CRC);
+#endif
+}
+
+/**
+ * @brief Send a cubepilot_firmware_update_start message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_cubepilot_firmware_update_start_send_struct(mavlink_channel_t chan, const mavlink_cubepilot_firmware_update_start_t* cubepilot_firmware_update_start)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_cubepilot_firmware_update_start_send(chan, cubepilot_firmware_update_start->target_system, cubepilot_firmware_update_start->target_component, cubepilot_firmware_update_start->size, cubepilot_firmware_update_start->crc);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_START, (const char *)cubepilot_firmware_update_start, MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_START_MIN_LEN, MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_START_LEN, MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_START_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_START_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_cubepilot_firmware_update_start_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint32_t size, uint32_t crc)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint32_t(buf, 0, size);
+ _mav_put_uint32_t(buf, 4, crc);
+ _mav_put_uint8_t(buf, 8, target_system);
+ _mav_put_uint8_t(buf, 9, target_component);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_START, buf, MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_START_MIN_LEN, MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_START_LEN, MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_START_CRC);
+#else
+ mavlink_cubepilot_firmware_update_start_t *packet = (mavlink_cubepilot_firmware_update_start_t *)msgbuf;
+ packet->size = size;
+ packet->crc = crc;
+ packet->target_system = target_system;
+ packet->target_component = target_component;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_START, (const char *)packet, MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_START_MIN_LEN, MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_START_LEN, MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_START_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE CUBEPILOT_FIRMWARE_UPDATE_START UNPACKING
+
+
+/**
+ * @brief Get field target_system from cubepilot_firmware_update_start message
+ *
+ * @return System ID.
+ */
+static inline uint8_t mavlink_msg_cubepilot_firmware_update_start_get_target_system(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 8);
+}
+
+/**
+ * @brief Get field target_component from cubepilot_firmware_update_start message
+ *
+ * @return Component ID.
+ */
+static inline uint8_t mavlink_msg_cubepilot_firmware_update_start_get_target_component(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 9);
+}
+
+/**
+ * @brief Get field size from cubepilot_firmware_update_start message
+ *
+ * @return [bytes] FW Size.
+ */
+static inline uint32_t mavlink_msg_cubepilot_firmware_update_start_get_size(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint32_t(msg, 0);
+}
+
+/**
+ * @brief Get field crc from cubepilot_firmware_update_start message
+ *
+ * @return FW CRC.
+ */
+static inline uint32_t mavlink_msg_cubepilot_firmware_update_start_get_crc(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint32_t(msg, 4);
+}
+
+/**
+ * @brief Decode a cubepilot_firmware_update_start message into a struct
+ *
+ * @param msg The message to decode
+ * @param cubepilot_firmware_update_start C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_cubepilot_firmware_update_start_decode(const mavlink_message_t* msg, mavlink_cubepilot_firmware_update_start_t* cubepilot_firmware_update_start)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ cubepilot_firmware_update_start->size = mavlink_msg_cubepilot_firmware_update_start_get_size(msg);
+ cubepilot_firmware_update_start->crc = mavlink_msg_cubepilot_firmware_update_start_get_crc(msg);
+ cubepilot_firmware_update_start->target_system = mavlink_msg_cubepilot_firmware_update_start_get_target_system(msg);
+ cubepilot_firmware_update_start->target_component = mavlink_msg_cubepilot_firmware_update_start_get_target_component(msg);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_START_LEN? msg->len : MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_START_LEN;
+ memset(cubepilot_firmware_update_start, 0, MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_START_LEN);
+ memcpy(cubepilot_firmware_update_start, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/cubepilot/mavlink_msg_cubepilot_raw_rc.h b/lib/main/MAVLink/cubepilot/mavlink_msg_cubepilot_raw_rc.h
new file mode 100644
index 00000000000..06d0cf8ae46
--- /dev/null
+++ b/lib/main/MAVLink/cubepilot/mavlink_msg_cubepilot_raw_rc.h
@@ -0,0 +1,260 @@
+#pragma once
+// MESSAGE CUBEPILOT_RAW_RC PACKING
+
+#define MAVLINK_MSG_ID_CUBEPILOT_RAW_RC 50001
+
+
+typedef struct __mavlink_cubepilot_raw_rc_t {
+ uint8_t rc_raw[32]; /*< */
+} mavlink_cubepilot_raw_rc_t;
+
+#define MAVLINK_MSG_ID_CUBEPILOT_RAW_RC_LEN 32
+#define MAVLINK_MSG_ID_CUBEPILOT_RAW_RC_MIN_LEN 32
+#define MAVLINK_MSG_ID_50001_LEN 32
+#define MAVLINK_MSG_ID_50001_MIN_LEN 32
+
+#define MAVLINK_MSG_ID_CUBEPILOT_RAW_RC_CRC 246
+#define MAVLINK_MSG_ID_50001_CRC 246
+
+#define MAVLINK_MSG_CUBEPILOT_RAW_RC_FIELD_RC_RAW_LEN 32
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_CUBEPILOT_RAW_RC { \
+ 50001, \
+ "CUBEPILOT_RAW_RC", \
+ 1, \
+ { { "rc_raw", NULL, MAVLINK_TYPE_UINT8_T, 32, 0, offsetof(mavlink_cubepilot_raw_rc_t, rc_raw) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_CUBEPILOT_RAW_RC { \
+ "CUBEPILOT_RAW_RC", \
+ 1, \
+ { { "rc_raw", NULL, MAVLINK_TYPE_UINT8_T, 32, 0, offsetof(mavlink_cubepilot_raw_rc_t, rc_raw) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a cubepilot_raw_rc 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 rc_raw
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_cubepilot_raw_rc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ const uint8_t *rc_raw)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_CUBEPILOT_RAW_RC_LEN];
+
+ _mav_put_uint8_t_array(buf, 0, rc_raw, 32);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CUBEPILOT_RAW_RC_LEN);
+#else
+ mavlink_cubepilot_raw_rc_t packet;
+
+ mav_array_assign_uint8_t(packet.rc_raw, rc_raw, 32);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CUBEPILOT_RAW_RC_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_CUBEPILOT_RAW_RC;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CUBEPILOT_RAW_RC_MIN_LEN, MAVLINK_MSG_ID_CUBEPILOT_RAW_RC_LEN, MAVLINK_MSG_ID_CUBEPILOT_RAW_RC_CRC);
+}
+
+/**
+ * @brief Pack a cubepilot_raw_rc 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 rc_raw
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_cubepilot_raw_rc_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ const uint8_t *rc_raw)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_CUBEPILOT_RAW_RC_LEN];
+
+ _mav_put_uint8_t_array(buf, 0, rc_raw, 32);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CUBEPILOT_RAW_RC_LEN);
+#else
+ mavlink_cubepilot_raw_rc_t packet;
+
+ mav_array_memcpy(packet.rc_raw, rc_raw, sizeof(uint8_t)*32);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CUBEPILOT_RAW_RC_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_CUBEPILOT_RAW_RC;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_CUBEPILOT_RAW_RC_MIN_LEN, MAVLINK_MSG_ID_CUBEPILOT_RAW_RC_LEN, MAVLINK_MSG_ID_CUBEPILOT_RAW_RC_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_CUBEPILOT_RAW_RC_MIN_LEN, MAVLINK_MSG_ID_CUBEPILOT_RAW_RC_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a cubepilot_raw_rc 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 rc_raw
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_cubepilot_raw_rc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ const uint8_t *rc_raw)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_CUBEPILOT_RAW_RC_LEN];
+
+ _mav_put_uint8_t_array(buf, 0, rc_raw, 32);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CUBEPILOT_RAW_RC_LEN);
+#else
+ mavlink_cubepilot_raw_rc_t packet;
+
+ mav_array_assign_uint8_t(packet.rc_raw, rc_raw, 32);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CUBEPILOT_RAW_RC_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_CUBEPILOT_RAW_RC;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CUBEPILOT_RAW_RC_MIN_LEN, MAVLINK_MSG_ID_CUBEPILOT_RAW_RC_LEN, MAVLINK_MSG_ID_CUBEPILOT_RAW_RC_CRC);
+}
+
+/**
+ * @brief Encode a cubepilot_raw_rc 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 cubepilot_raw_rc C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_cubepilot_raw_rc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_cubepilot_raw_rc_t* cubepilot_raw_rc)
+{
+ return mavlink_msg_cubepilot_raw_rc_pack(system_id, component_id, msg, cubepilot_raw_rc->rc_raw);
+}
+
+/**
+ * @brief Encode a cubepilot_raw_rc 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 cubepilot_raw_rc C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_cubepilot_raw_rc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_cubepilot_raw_rc_t* cubepilot_raw_rc)
+{
+ return mavlink_msg_cubepilot_raw_rc_pack_chan(system_id, component_id, chan, msg, cubepilot_raw_rc->rc_raw);
+}
+
+/**
+ * @brief Encode a cubepilot_raw_rc 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 cubepilot_raw_rc C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_cubepilot_raw_rc_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_cubepilot_raw_rc_t* cubepilot_raw_rc)
+{
+ return mavlink_msg_cubepilot_raw_rc_pack_status(system_id, component_id, _status, msg, cubepilot_raw_rc->rc_raw);
+}
+
+/**
+ * @brief Send a cubepilot_raw_rc message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param rc_raw
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_cubepilot_raw_rc_send(mavlink_channel_t chan, const uint8_t *rc_raw)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_CUBEPILOT_RAW_RC_LEN];
+
+ _mav_put_uint8_t_array(buf, 0, rc_raw, 32);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CUBEPILOT_RAW_RC, buf, MAVLINK_MSG_ID_CUBEPILOT_RAW_RC_MIN_LEN, MAVLINK_MSG_ID_CUBEPILOT_RAW_RC_LEN, MAVLINK_MSG_ID_CUBEPILOT_RAW_RC_CRC);
+#else
+ mavlink_cubepilot_raw_rc_t packet;
+
+ mav_array_assign_uint8_t(packet.rc_raw, rc_raw, 32);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CUBEPILOT_RAW_RC, (const char *)&packet, MAVLINK_MSG_ID_CUBEPILOT_RAW_RC_MIN_LEN, MAVLINK_MSG_ID_CUBEPILOT_RAW_RC_LEN, MAVLINK_MSG_ID_CUBEPILOT_RAW_RC_CRC);
+#endif
+}
+
+/**
+ * @brief Send a cubepilot_raw_rc message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_cubepilot_raw_rc_send_struct(mavlink_channel_t chan, const mavlink_cubepilot_raw_rc_t* cubepilot_raw_rc)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_cubepilot_raw_rc_send(chan, cubepilot_raw_rc->rc_raw);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CUBEPILOT_RAW_RC, (const char *)cubepilot_raw_rc, MAVLINK_MSG_ID_CUBEPILOT_RAW_RC_MIN_LEN, MAVLINK_MSG_ID_CUBEPILOT_RAW_RC_LEN, MAVLINK_MSG_ID_CUBEPILOT_RAW_RC_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_CUBEPILOT_RAW_RC_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_cubepilot_raw_rc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, const uint8_t *rc_raw)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+
+ _mav_put_uint8_t_array(buf, 0, rc_raw, 32);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CUBEPILOT_RAW_RC, buf, MAVLINK_MSG_ID_CUBEPILOT_RAW_RC_MIN_LEN, MAVLINK_MSG_ID_CUBEPILOT_RAW_RC_LEN, MAVLINK_MSG_ID_CUBEPILOT_RAW_RC_CRC);
+#else
+ mavlink_cubepilot_raw_rc_t *packet = (mavlink_cubepilot_raw_rc_t *)msgbuf;
+
+ mav_array_assign_uint8_t(packet->rc_raw, rc_raw, 32);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CUBEPILOT_RAW_RC, (const char *)packet, MAVLINK_MSG_ID_CUBEPILOT_RAW_RC_MIN_LEN, MAVLINK_MSG_ID_CUBEPILOT_RAW_RC_LEN, MAVLINK_MSG_ID_CUBEPILOT_RAW_RC_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE CUBEPILOT_RAW_RC UNPACKING
+
+
+/**
+ * @brief Get field rc_raw from cubepilot_raw_rc message
+ *
+ * @return
+ */
+static inline uint16_t mavlink_msg_cubepilot_raw_rc_get_rc_raw(const mavlink_message_t* msg, uint8_t *rc_raw)
+{
+ return _MAV_RETURN_uint8_t_array(msg, rc_raw, 32, 0);
+}
+
+/**
+ * @brief Decode a cubepilot_raw_rc message into a struct
+ *
+ * @param msg The message to decode
+ * @param cubepilot_raw_rc C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_cubepilot_raw_rc_decode(const mavlink_message_t* msg, mavlink_cubepilot_raw_rc_t* cubepilot_raw_rc)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_cubepilot_raw_rc_get_rc_raw(msg, cubepilot_raw_rc->rc_raw);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_CUBEPILOT_RAW_RC_LEN? msg->len : MAVLINK_MSG_ID_CUBEPILOT_RAW_RC_LEN;
+ memset(cubepilot_raw_rc, 0, MAVLINK_MSG_ID_CUBEPILOT_RAW_RC_LEN);
+ memcpy(cubepilot_raw_rc, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/cubepilot/mavlink_msg_herelink_telem.h b/lib/main/MAVLink/cubepilot/mavlink_msg_herelink_telem.h
new file mode 100644
index 00000000000..28ac075cfe8
--- /dev/null
+++ b/lib/main/MAVLink/cubepilot/mavlink_msg_herelink_telem.h
@@ -0,0 +1,428 @@
+#pragma once
+// MESSAGE HERELINK_TELEM PACKING
+
+#define MAVLINK_MSG_ID_HERELINK_TELEM 50003
+
+
+typedef struct __mavlink_herelink_telem_t {
+ uint32_t rf_freq; /*< */
+ uint32_t link_bw; /*< */
+ uint32_t link_rate; /*< */
+ int16_t snr; /*< */
+ int16_t cpu_temp; /*< */
+ int16_t board_temp; /*< */
+ uint8_t rssi; /*< */
+} mavlink_herelink_telem_t;
+
+#define MAVLINK_MSG_ID_HERELINK_TELEM_LEN 19
+#define MAVLINK_MSG_ID_HERELINK_TELEM_MIN_LEN 19
+#define MAVLINK_MSG_ID_50003_LEN 19
+#define MAVLINK_MSG_ID_50003_MIN_LEN 19
+
+#define MAVLINK_MSG_ID_HERELINK_TELEM_CRC 62
+#define MAVLINK_MSG_ID_50003_CRC 62
+
+
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_HERELINK_TELEM { \
+ 50003, \
+ "HERELINK_TELEM", \
+ 7, \
+ { { "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 18, offsetof(mavlink_herelink_telem_t, rssi) }, \
+ { "snr", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_herelink_telem_t, snr) }, \
+ { "rf_freq", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_herelink_telem_t, rf_freq) }, \
+ { "link_bw", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_herelink_telem_t, link_bw) }, \
+ { "link_rate", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_herelink_telem_t, link_rate) }, \
+ { "cpu_temp", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_herelink_telem_t, cpu_temp) }, \
+ { "board_temp", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_herelink_telem_t, board_temp) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_HERELINK_TELEM { \
+ "HERELINK_TELEM", \
+ 7, \
+ { { "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 18, offsetof(mavlink_herelink_telem_t, rssi) }, \
+ { "snr", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_herelink_telem_t, snr) }, \
+ { "rf_freq", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_herelink_telem_t, rf_freq) }, \
+ { "link_bw", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_herelink_telem_t, link_bw) }, \
+ { "link_rate", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_herelink_telem_t, link_rate) }, \
+ { "cpu_temp", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_herelink_telem_t, cpu_temp) }, \
+ { "board_temp", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_herelink_telem_t, board_temp) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a herelink_telem 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 rssi
+ * @param snr
+ * @param rf_freq
+ * @param link_bw
+ * @param link_rate
+ * @param cpu_temp
+ * @param board_temp
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_herelink_telem_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint8_t rssi, int16_t snr, uint32_t rf_freq, uint32_t link_bw, uint32_t link_rate, int16_t cpu_temp, int16_t board_temp)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_HERELINK_TELEM_LEN];
+ _mav_put_uint32_t(buf, 0, rf_freq);
+ _mav_put_uint32_t(buf, 4, link_bw);
+ _mav_put_uint32_t(buf, 8, link_rate);
+ _mav_put_int16_t(buf, 12, snr);
+ _mav_put_int16_t(buf, 14, cpu_temp);
+ _mav_put_int16_t(buf, 16, board_temp);
+ _mav_put_uint8_t(buf, 18, rssi);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HERELINK_TELEM_LEN);
+#else
+ mavlink_herelink_telem_t packet;
+ packet.rf_freq = rf_freq;
+ packet.link_bw = link_bw;
+ packet.link_rate = link_rate;
+ packet.snr = snr;
+ packet.cpu_temp = cpu_temp;
+ packet.board_temp = board_temp;
+ packet.rssi = rssi;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HERELINK_TELEM_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_HERELINK_TELEM;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HERELINK_TELEM_MIN_LEN, MAVLINK_MSG_ID_HERELINK_TELEM_LEN, MAVLINK_MSG_ID_HERELINK_TELEM_CRC);
+}
+
+/**
+ * @brief Pack a herelink_telem 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 rssi
+ * @param snr
+ * @param rf_freq
+ * @param link_bw
+ * @param link_rate
+ * @param cpu_temp
+ * @param board_temp
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_herelink_telem_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ uint8_t rssi, int16_t snr, uint32_t rf_freq, uint32_t link_bw, uint32_t link_rate, int16_t cpu_temp, int16_t board_temp)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_HERELINK_TELEM_LEN];
+ _mav_put_uint32_t(buf, 0, rf_freq);
+ _mav_put_uint32_t(buf, 4, link_bw);
+ _mav_put_uint32_t(buf, 8, link_rate);
+ _mav_put_int16_t(buf, 12, snr);
+ _mav_put_int16_t(buf, 14, cpu_temp);
+ _mav_put_int16_t(buf, 16, board_temp);
+ _mav_put_uint8_t(buf, 18, rssi);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HERELINK_TELEM_LEN);
+#else
+ mavlink_herelink_telem_t packet;
+ packet.rf_freq = rf_freq;
+ packet.link_bw = link_bw;
+ packet.link_rate = link_rate;
+ packet.snr = snr;
+ packet.cpu_temp = cpu_temp;
+ packet.board_temp = board_temp;
+ packet.rssi = rssi;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HERELINK_TELEM_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_HERELINK_TELEM;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_HERELINK_TELEM_MIN_LEN, MAVLINK_MSG_ID_HERELINK_TELEM_LEN, MAVLINK_MSG_ID_HERELINK_TELEM_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_HERELINK_TELEM_MIN_LEN, MAVLINK_MSG_ID_HERELINK_TELEM_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a herelink_telem 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 rssi
+ * @param snr
+ * @param rf_freq
+ * @param link_bw
+ * @param link_rate
+ * @param cpu_temp
+ * @param board_temp
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_herelink_telem_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint8_t rssi,int16_t snr,uint32_t rf_freq,uint32_t link_bw,uint32_t link_rate,int16_t cpu_temp,int16_t board_temp)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_HERELINK_TELEM_LEN];
+ _mav_put_uint32_t(buf, 0, rf_freq);
+ _mav_put_uint32_t(buf, 4, link_bw);
+ _mav_put_uint32_t(buf, 8, link_rate);
+ _mav_put_int16_t(buf, 12, snr);
+ _mav_put_int16_t(buf, 14, cpu_temp);
+ _mav_put_int16_t(buf, 16, board_temp);
+ _mav_put_uint8_t(buf, 18, rssi);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HERELINK_TELEM_LEN);
+#else
+ mavlink_herelink_telem_t packet;
+ packet.rf_freq = rf_freq;
+ packet.link_bw = link_bw;
+ packet.link_rate = link_rate;
+ packet.snr = snr;
+ packet.cpu_temp = cpu_temp;
+ packet.board_temp = board_temp;
+ packet.rssi = rssi;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HERELINK_TELEM_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_HERELINK_TELEM;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HERELINK_TELEM_MIN_LEN, MAVLINK_MSG_ID_HERELINK_TELEM_LEN, MAVLINK_MSG_ID_HERELINK_TELEM_CRC);
+}
+
+/**
+ * @brief Encode a herelink_telem 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 herelink_telem C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_herelink_telem_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_herelink_telem_t* herelink_telem)
+{
+ return mavlink_msg_herelink_telem_pack(system_id, component_id, msg, herelink_telem->rssi, herelink_telem->snr, herelink_telem->rf_freq, herelink_telem->link_bw, herelink_telem->link_rate, herelink_telem->cpu_temp, herelink_telem->board_temp);
+}
+
+/**
+ * @brief Encode a herelink_telem 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 herelink_telem C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_herelink_telem_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_herelink_telem_t* herelink_telem)
+{
+ return mavlink_msg_herelink_telem_pack_chan(system_id, component_id, chan, msg, herelink_telem->rssi, herelink_telem->snr, herelink_telem->rf_freq, herelink_telem->link_bw, herelink_telem->link_rate, herelink_telem->cpu_temp, herelink_telem->board_temp);
+}
+
+/**
+ * @brief Encode a herelink_telem 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 herelink_telem C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_herelink_telem_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_herelink_telem_t* herelink_telem)
+{
+ return mavlink_msg_herelink_telem_pack_status(system_id, component_id, _status, msg, herelink_telem->rssi, herelink_telem->snr, herelink_telem->rf_freq, herelink_telem->link_bw, herelink_telem->link_rate, herelink_telem->cpu_temp, herelink_telem->board_temp);
+}
+
+/**
+ * @brief Send a herelink_telem message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param rssi
+ * @param snr
+ * @param rf_freq
+ * @param link_bw
+ * @param link_rate
+ * @param cpu_temp
+ * @param board_temp
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_herelink_telem_send(mavlink_channel_t chan, uint8_t rssi, int16_t snr, uint32_t rf_freq, uint32_t link_bw, uint32_t link_rate, int16_t cpu_temp, int16_t board_temp)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_HERELINK_TELEM_LEN];
+ _mav_put_uint32_t(buf, 0, rf_freq);
+ _mav_put_uint32_t(buf, 4, link_bw);
+ _mav_put_uint32_t(buf, 8, link_rate);
+ _mav_put_int16_t(buf, 12, snr);
+ _mav_put_int16_t(buf, 14, cpu_temp);
+ _mav_put_int16_t(buf, 16, board_temp);
+ _mav_put_uint8_t(buf, 18, rssi);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HERELINK_TELEM, buf, MAVLINK_MSG_ID_HERELINK_TELEM_MIN_LEN, MAVLINK_MSG_ID_HERELINK_TELEM_LEN, MAVLINK_MSG_ID_HERELINK_TELEM_CRC);
+#else
+ mavlink_herelink_telem_t packet;
+ packet.rf_freq = rf_freq;
+ packet.link_bw = link_bw;
+ packet.link_rate = link_rate;
+ packet.snr = snr;
+ packet.cpu_temp = cpu_temp;
+ packet.board_temp = board_temp;
+ packet.rssi = rssi;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HERELINK_TELEM, (const char *)&packet, MAVLINK_MSG_ID_HERELINK_TELEM_MIN_LEN, MAVLINK_MSG_ID_HERELINK_TELEM_LEN, MAVLINK_MSG_ID_HERELINK_TELEM_CRC);
+#endif
+}
+
+/**
+ * @brief Send a herelink_telem message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_herelink_telem_send_struct(mavlink_channel_t chan, const mavlink_herelink_telem_t* herelink_telem)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_herelink_telem_send(chan, herelink_telem->rssi, herelink_telem->snr, herelink_telem->rf_freq, herelink_telem->link_bw, herelink_telem->link_rate, herelink_telem->cpu_temp, herelink_telem->board_temp);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HERELINK_TELEM, (const char *)herelink_telem, MAVLINK_MSG_ID_HERELINK_TELEM_MIN_LEN, MAVLINK_MSG_ID_HERELINK_TELEM_LEN, MAVLINK_MSG_ID_HERELINK_TELEM_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_HERELINK_TELEM_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_herelink_telem_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t rssi, int16_t snr, uint32_t rf_freq, uint32_t link_bw, uint32_t link_rate, int16_t cpu_temp, int16_t board_temp)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint32_t(buf, 0, rf_freq);
+ _mav_put_uint32_t(buf, 4, link_bw);
+ _mav_put_uint32_t(buf, 8, link_rate);
+ _mav_put_int16_t(buf, 12, snr);
+ _mav_put_int16_t(buf, 14, cpu_temp);
+ _mav_put_int16_t(buf, 16, board_temp);
+ _mav_put_uint8_t(buf, 18, rssi);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HERELINK_TELEM, buf, MAVLINK_MSG_ID_HERELINK_TELEM_MIN_LEN, MAVLINK_MSG_ID_HERELINK_TELEM_LEN, MAVLINK_MSG_ID_HERELINK_TELEM_CRC);
+#else
+ mavlink_herelink_telem_t *packet = (mavlink_herelink_telem_t *)msgbuf;
+ packet->rf_freq = rf_freq;
+ packet->link_bw = link_bw;
+ packet->link_rate = link_rate;
+ packet->snr = snr;
+ packet->cpu_temp = cpu_temp;
+ packet->board_temp = board_temp;
+ packet->rssi = rssi;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HERELINK_TELEM, (const char *)packet, MAVLINK_MSG_ID_HERELINK_TELEM_MIN_LEN, MAVLINK_MSG_ID_HERELINK_TELEM_LEN, MAVLINK_MSG_ID_HERELINK_TELEM_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE HERELINK_TELEM UNPACKING
+
+
+/**
+ * @brief Get field rssi from herelink_telem message
+ *
+ * @return
+ */
+static inline uint8_t mavlink_msg_herelink_telem_get_rssi(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 18);
+}
+
+/**
+ * @brief Get field snr from herelink_telem message
+ *
+ * @return
+ */
+static inline int16_t mavlink_msg_herelink_telem_get_snr(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_int16_t(msg, 12);
+}
+
+/**
+ * @brief Get field rf_freq from herelink_telem message
+ *
+ * @return
+ */
+static inline uint32_t mavlink_msg_herelink_telem_get_rf_freq(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint32_t(msg, 0);
+}
+
+/**
+ * @brief Get field link_bw from herelink_telem message
+ *
+ * @return
+ */
+static inline uint32_t mavlink_msg_herelink_telem_get_link_bw(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint32_t(msg, 4);
+}
+
+/**
+ * @brief Get field link_rate from herelink_telem message
+ *
+ * @return
+ */
+static inline uint32_t mavlink_msg_herelink_telem_get_link_rate(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint32_t(msg, 8);
+}
+
+/**
+ * @brief Get field cpu_temp from herelink_telem message
+ *
+ * @return
+ */
+static inline int16_t mavlink_msg_herelink_telem_get_cpu_temp(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_int16_t(msg, 14);
+}
+
+/**
+ * @brief Get field board_temp from herelink_telem message
+ *
+ * @return
+ */
+static inline int16_t mavlink_msg_herelink_telem_get_board_temp(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_int16_t(msg, 16);
+}
+
+/**
+ * @brief Decode a herelink_telem message into a struct
+ *
+ * @param msg The message to decode
+ * @param herelink_telem C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_herelink_telem_decode(const mavlink_message_t* msg, mavlink_herelink_telem_t* herelink_telem)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ herelink_telem->rf_freq = mavlink_msg_herelink_telem_get_rf_freq(msg);
+ herelink_telem->link_bw = mavlink_msg_herelink_telem_get_link_bw(msg);
+ herelink_telem->link_rate = mavlink_msg_herelink_telem_get_link_rate(msg);
+ herelink_telem->snr = mavlink_msg_herelink_telem_get_snr(msg);
+ herelink_telem->cpu_temp = mavlink_msg_herelink_telem_get_cpu_temp(msg);
+ herelink_telem->board_temp = mavlink_msg_herelink_telem_get_board_temp(msg);
+ herelink_telem->rssi = mavlink_msg_herelink_telem_get_rssi(msg);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_HERELINK_TELEM_LEN? msg->len : MAVLINK_MSG_ID_HERELINK_TELEM_LEN;
+ memset(herelink_telem, 0, MAVLINK_MSG_ID_HERELINK_TELEM_LEN);
+ memcpy(herelink_telem, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/cubepilot/mavlink_msg_herelink_video_stream_information.h b/lib/main/MAVLink/cubepilot/mavlink_msg_herelink_video_stream_information.h
new file mode 100644
index 00000000000..6d0c12af926
--- /dev/null
+++ b/lib/main/MAVLink/cubepilot/mavlink_msg_herelink_video_stream_information.h
@@ -0,0 +1,446 @@
+#pragma once
+// MESSAGE HERELINK_VIDEO_STREAM_INFORMATION PACKING
+
+#define MAVLINK_MSG_ID_HERELINK_VIDEO_STREAM_INFORMATION 50002
+
+
+typedef struct __mavlink_herelink_video_stream_information_t {
+ float framerate; /*< [Hz] Frame rate.*/
+ uint32_t bitrate; /*< [bits/s] Bit rate.*/
+ uint16_t resolution_h; /*< [pix] Horizontal resolution.*/
+ uint16_t resolution_v; /*< [pix] Vertical resolution.*/
+ uint16_t rotation; /*< [deg] Video image rotation clockwise.*/
+ uint8_t camera_id; /*< Video Stream ID (1 for first, 2 for second, etc.)*/
+ uint8_t status; /*< Number of streams available.*/
+ char uri[230]; /*< Video stream URI (TCP or RTSP URI ground station should connect to) or port number (UDP port ground station should listen to).*/
+} mavlink_herelink_video_stream_information_t;
+
+#define MAVLINK_MSG_ID_HERELINK_VIDEO_STREAM_INFORMATION_LEN 246
+#define MAVLINK_MSG_ID_HERELINK_VIDEO_STREAM_INFORMATION_MIN_LEN 246
+#define MAVLINK_MSG_ID_50002_LEN 246
+#define MAVLINK_MSG_ID_50002_MIN_LEN 246
+
+#define MAVLINK_MSG_ID_HERELINK_VIDEO_STREAM_INFORMATION_CRC 181
+#define MAVLINK_MSG_ID_50002_CRC 181
+
+#define MAVLINK_MSG_HERELINK_VIDEO_STREAM_INFORMATION_FIELD_URI_LEN 230
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_HERELINK_VIDEO_STREAM_INFORMATION { \
+ 50002, \
+ "HERELINK_VIDEO_STREAM_INFORMATION", \
+ 8, \
+ { { "camera_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 14, offsetof(mavlink_herelink_video_stream_information_t, camera_id) }, \
+ { "status", NULL, MAVLINK_TYPE_UINT8_T, 0, 15, offsetof(mavlink_herelink_video_stream_information_t, status) }, \
+ { "framerate", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_herelink_video_stream_information_t, framerate) }, \
+ { "resolution_h", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_herelink_video_stream_information_t, resolution_h) }, \
+ { "resolution_v", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_herelink_video_stream_information_t, resolution_v) }, \
+ { "bitrate", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_herelink_video_stream_information_t, bitrate) }, \
+ { "rotation", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_herelink_video_stream_information_t, rotation) }, \
+ { "uri", NULL, MAVLINK_TYPE_CHAR, 230, 16, offsetof(mavlink_herelink_video_stream_information_t, uri) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_HERELINK_VIDEO_STREAM_INFORMATION { \
+ "HERELINK_VIDEO_STREAM_INFORMATION", \
+ 8, \
+ { { "camera_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 14, offsetof(mavlink_herelink_video_stream_information_t, camera_id) }, \
+ { "status", NULL, MAVLINK_TYPE_UINT8_T, 0, 15, offsetof(mavlink_herelink_video_stream_information_t, status) }, \
+ { "framerate", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_herelink_video_stream_information_t, framerate) }, \
+ { "resolution_h", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_herelink_video_stream_information_t, resolution_h) }, \
+ { "resolution_v", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_herelink_video_stream_information_t, resolution_v) }, \
+ { "bitrate", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_herelink_video_stream_information_t, bitrate) }, \
+ { "rotation", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_herelink_video_stream_information_t, rotation) }, \
+ { "uri", NULL, MAVLINK_TYPE_CHAR, 230, 16, offsetof(mavlink_herelink_video_stream_information_t, uri) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a herelink_video_stream_information 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 camera_id Video Stream ID (1 for first, 2 for second, etc.)
+ * @param status Number of streams available.
+ * @param framerate [Hz] Frame rate.
+ * @param resolution_h [pix] Horizontal resolution.
+ * @param resolution_v [pix] Vertical resolution.
+ * @param bitrate [bits/s] Bit rate.
+ * @param rotation [deg] Video image rotation clockwise.
+ * @param uri Video stream URI (TCP or RTSP URI ground station should connect to) or port number (UDP port ground station should listen to).
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_herelink_video_stream_information_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint8_t camera_id, uint8_t status, float framerate, uint16_t resolution_h, uint16_t resolution_v, uint32_t bitrate, uint16_t rotation, const char *uri)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_HERELINK_VIDEO_STREAM_INFORMATION_LEN];
+ _mav_put_float(buf, 0, framerate);
+ _mav_put_uint32_t(buf, 4, bitrate);
+ _mav_put_uint16_t(buf, 8, resolution_h);
+ _mav_put_uint16_t(buf, 10, resolution_v);
+ _mav_put_uint16_t(buf, 12, rotation);
+ _mav_put_uint8_t(buf, 14, camera_id);
+ _mav_put_uint8_t(buf, 15, status);
+ _mav_put_char_array(buf, 16, uri, 230);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HERELINK_VIDEO_STREAM_INFORMATION_LEN);
+#else
+ mavlink_herelink_video_stream_information_t packet;
+ packet.framerate = framerate;
+ packet.bitrate = bitrate;
+ packet.resolution_h = resolution_h;
+ packet.resolution_v = resolution_v;
+ packet.rotation = rotation;
+ packet.camera_id = camera_id;
+ packet.status = status;
+ mav_array_assign_char(packet.uri, uri, 230);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HERELINK_VIDEO_STREAM_INFORMATION_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_HERELINK_VIDEO_STREAM_INFORMATION;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HERELINK_VIDEO_STREAM_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_HERELINK_VIDEO_STREAM_INFORMATION_LEN, MAVLINK_MSG_ID_HERELINK_VIDEO_STREAM_INFORMATION_CRC);
+}
+
+/**
+ * @brief Pack a herelink_video_stream_information 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 camera_id Video Stream ID (1 for first, 2 for second, etc.)
+ * @param status Number of streams available.
+ * @param framerate [Hz] Frame rate.
+ * @param resolution_h [pix] Horizontal resolution.
+ * @param resolution_v [pix] Vertical resolution.
+ * @param bitrate [bits/s] Bit rate.
+ * @param rotation [deg] Video image rotation clockwise.
+ * @param uri Video stream URI (TCP or RTSP URI ground station should connect to) or port number (UDP port ground station should listen to).
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_herelink_video_stream_information_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ uint8_t camera_id, uint8_t status, float framerate, uint16_t resolution_h, uint16_t resolution_v, uint32_t bitrate, uint16_t rotation, const char *uri)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_HERELINK_VIDEO_STREAM_INFORMATION_LEN];
+ _mav_put_float(buf, 0, framerate);
+ _mav_put_uint32_t(buf, 4, bitrate);
+ _mav_put_uint16_t(buf, 8, resolution_h);
+ _mav_put_uint16_t(buf, 10, resolution_v);
+ _mav_put_uint16_t(buf, 12, rotation);
+ _mav_put_uint8_t(buf, 14, camera_id);
+ _mav_put_uint8_t(buf, 15, status);
+ _mav_put_char_array(buf, 16, uri, 230);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HERELINK_VIDEO_STREAM_INFORMATION_LEN);
+#else
+ mavlink_herelink_video_stream_information_t packet;
+ packet.framerate = framerate;
+ packet.bitrate = bitrate;
+ packet.resolution_h = resolution_h;
+ packet.resolution_v = resolution_v;
+ packet.rotation = rotation;
+ packet.camera_id = camera_id;
+ packet.status = status;
+ mav_array_memcpy(packet.uri, uri, sizeof(char)*230);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HERELINK_VIDEO_STREAM_INFORMATION_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_HERELINK_VIDEO_STREAM_INFORMATION;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_HERELINK_VIDEO_STREAM_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_HERELINK_VIDEO_STREAM_INFORMATION_LEN, MAVLINK_MSG_ID_HERELINK_VIDEO_STREAM_INFORMATION_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_HERELINK_VIDEO_STREAM_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_HERELINK_VIDEO_STREAM_INFORMATION_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a herelink_video_stream_information 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 camera_id Video Stream ID (1 for first, 2 for second, etc.)
+ * @param status Number of streams available.
+ * @param framerate [Hz] Frame rate.
+ * @param resolution_h [pix] Horizontal resolution.
+ * @param resolution_v [pix] Vertical resolution.
+ * @param bitrate [bits/s] Bit rate.
+ * @param rotation [deg] Video image rotation clockwise.
+ * @param uri Video stream URI (TCP or RTSP URI ground station should connect to) or port number (UDP port ground station should listen to).
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_herelink_video_stream_information_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint8_t camera_id,uint8_t status,float framerate,uint16_t resolution_h,uint16_t resolution_v,uint32_t bitrate,uint16_t rotation,const char *uri)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_HERELINK_VIDEO_STREAM_INFORMATION_LEN];
+ _mav_put_float(buf, 0, framerate);
+ _mav_put_uint32_t(buf, 4, bitrate);
+ _mav_put_uint16_t(buf, 8, resolution_h);
+ _mav_put_uint16_t(buf, 10, resolution_v);
+ _mav_put_uint16_t(buf, 12, rotation);
+ _mav_put_uint8_t(buf, 14, camera_id);
+ _mav_put_uint8_t(buf, 15, status);
+ _mav_put_char_array(buf, 16, uri, 230);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HERELINK_VIDEO_STREAM_INFORMATION_LEN);
+#else
+ mavlink_herelink_video_stream_information_t packet;
+ packet.framerate = framerate;
+ packet.bitrate = bitrate;
+ packet.resolution_h = resolution_h;
+ packet.resolution_v = resolution_v;
+ packet.rotation = rotation;
+ packet.camera_id = camera_id;
+ packet.status = status;
+ mav_array_assign_char(packet.uri, uri, 230);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HERELINK_VIDEO_STREAM_INFORMATION_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_HERELINK_VIDEO_STREAM_INFORMATION;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HERELINK_VIDEO_STREAM_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_HERELINK_VIDEO_STREAM_INFORMATION_LEN, MAVLINK_MSG_ID_HERELINK_VIDEO_STREAM_INFORMATION_CRC);
+}
+
+/**
+ * @brief Encode a herelink_video_stream_information 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 herelink_video_stream_information C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_herelink_video_stream_information_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_herelink_video_stream_information_t* herelink_video_stream_information)
+{
+ return mavlink_msg_herelink_video_stream_information_pack(system_id, component_id, msg, herelink_video_stream_information->camera_id, herelink_video_stream_information->status, herelink_video_stream_information->framerate, herelink_video_stream_information->resolution_h, herelink_video_stream_information->resolution_v, herelink_video_stream_information->bitrate, herelink_video_stream_information->rotation, herelink_video_stream_information->uri);
+}
+
+/**
+ * @brief Encode a herelink_video_stream_information 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 herelink_video_stream_information C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_herelink_video_stream_information_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_herelink_video_stream_information_t* herelink_video_stream_information)
+{
+ return mavlink_msg_herelink_video_stream_information_pack_chan(system_id, component_id, chan, msg, herelink_video_stream_information->camera_id, herelink_video_stream_information->status, herelink_video_stream_information->framerate, herelink_video_stream_information->resolution_h, herelink_video_stream_information->resolution_v, herelink_video_stream_information->bitrate, herelink_video_stream_information->rotation, herelink_video_stream_information->uri);
+}
+
+/**
+ * @brief Encode a herelink_video_stream_information 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 herelink_video_stream_information C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_herelink_video_stream_information_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_herelink_video_stream_information_t* herelink_video_stream_information)
+{
+ return mavlink_msg_herelink_video_stream_information_pack_status(system_id, component_id, _status, msg, herelink_video_stream_information->camera_id, herelink_video_stream_information->status, herelink_video_stream_information->framerate, herelink_video_stream_information->resolution_h, herelink_video_stream_information->resolution_v, herelink_video_stream_information->bitrate, herelink_video_stream_information->rotation, herelink_video_stream_information->uri);
+}
+
+/**
+ * @brief Send a herelink_video_stream_information message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param camera_id Video Stream ID (1 for first, 2 for second, etc.)
+ * @param status Number of streams available.
+ * @param framerate [Hz] Frame rate.
+ * @param resolution_h [pix] Horizontal resolution.
+ * @param resolution_v [pix] Vertical resolution.
+ * @param bitrate [bits/s] Bit rate.
+ * @param rotation [deg] Video image rotation clockwise.
+ * @param uri Video stream URI (TCP or RTSP URI ground station should connect to) or port number (UDP port ground station should listen to).
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_herelink_video_stream_information_send(mavlink_channel_t chan, uint8_t camera_id, uint8_t status, float framerate, uint16_t resolution_h, uint16_t resolution_v, uint32_t bitrate, uint16_t rotation, const char *uri)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_HERELINK_VIDEO_STREAM_INFORMATION_LEN];
+ _mav_put_float(buf, 0, framerate);
+ _mav_put_uint32_t(buf, 4, bitrate);
+ _mav_put_uint16_t(buf, 8, resolution_h);
+ _mav_put_uint16_t(buf, 10, resolution_v);
+ _mav_put_uint16_t(buf, 12, rotation);
+ _mav_put_uint8_t(buf, 14, camera_id);
+ _mav_put_uint8_t(buf, 15, status);
+ _mav_put_char_array(buf, 16, uri, 230);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HERELINK_VIDEO_STREAM_INFORMATION, buf, MAVLINK_MSG_ID_HERELINK_VIDEO_STREAM_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_HERELINK_VIDEO_STREAM_INFORMATION_LEN, MAVLINK_MSG_ID_HERELINK_VIDEO_STREAM_INFORMATION_CRC);
+#else
+ mavlink_herelink_video_stream_information_t packet;
+ packet.framerate = framerate;
+ packet.bitrate = bitrate;
+ packet.resolution_h = resolution_h;
+ packet.resolution_v = resolution_v;
+ packet.rotation = rotation;
+ packet.camera_id = camera_id;
+ packet.status = status;
+ mav_array_assign_char(packet.uri, uri, 230);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HERELINK_VIDEO_STREAM_INFORMATION, (const char *)&packet, MAVLINK_MSG_ID_HERELINK_VIDEO_STREAM_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_HERELINK_VIDEO_STREAM_INFORMATION_LEN, MAVLINK_MSG_ID_HERELINK_VIDEO_STREAM_INFORMATION_CRC);
+#endif
+}
+
+/**
+ * @brief Send a herelink_video_stream_information message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_herelink_video_stream_information_send_struct(mavlink_channel_t chan, const mavlink_herelink_video_stream_information_t* herelink_video_stream_information)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_herelink_video_stream_information_send(chan, herelink_video_stream_information->camera_id, herelink_video_stream_information->status, herelink_video_stream_information->framerate, herelink_video_stream_information->resolution_h, herelink_video_stream_information->resolution_v, herelink_video_stream_information->bitrate, herelink_video_stream_information->rotation, herelink_video_stream_information->uri);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HERELINK_VIDEO_STREAM_INFORMATION, (const char *)herelink_video_stream_information, MAVLINK_MSG_ID_HERELINK_VIDEO_STREAM_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_HERELINK_VIDEO_STREAM_INFORMATION_LEN, MAVLINK_MSG_ID_HERELINK_VIDEO_STREAM_INFORMATION_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_HERELINK_VIDEO_STREAM_INFORMATION_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_herelink_video_stream_information_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t camera_id, uint8_t status, float framerate, uint16_t resolution_h, uint16_t resolution_v, uint32_t bitrate, uint16_t rotation, const char *uri)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_float(buf, 0, framerate);
+ _mav_put_uint32_t(buf, 4, bitrate);
+ _mav_put_uint16_t(buf, 8, resolution_h);
+ _mav_put_uint16_t(buf, 10, resolution_v);
+ _mav_put_uint16_t(buf, 12, rotation);
+ _mav_put_uint8_t(buf, 14, camera_id);
+ _mav_put_uint8_t(buf, 15, status);
+ _mav_put_char_array(buf, 16, uri, 230);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HERELINK_VIDEO_STREAM_INFORMATION, buf, MAVLINK_MSG_ID_HERELINK_VIDEO_STREAM_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_HERELINK_VIDEO_STREAM_INFORMATION_LEN, MAVLINK_MSG_ID_HERELINK_VIDEO_STREAM_INFORMATION_CRC);
+#else
+ mavlink_herelink_video_stream_information_t *packet = (mavlink_herelink_video_stream_information_t *)msgbuf;
+ packet->framerate = framerate;
+ packet->bitrate = bitrate;
+ packet->resolution_h = resolution_h;
+ packet->resolution_v = resolution_v;
+ packet->rotation = rotation;
+ packet->camera_id = camera_id;
+ packet->status = status;
+ mav_array_assign_char(packet->uri, uri, 230);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HERELINK_VIDEO_STREAM_INFORMATION, (const char *)packet, MAVLINK_MSG_ID_HERELINK_VIDEO_STREAM_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_HERELINK_VIDEO_STREAM_INFORMATION_LEN, MAVLINK_MSG_ID_HERELINK_VIDEO_STREAM_INFORMATION_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE HERELINK_VIDEO_STREAM_INFORMATION UNPACKING
+
+
+/**
+ * @brief Get field camera_id from herelink_video_stream_information message
+ *
+ * @return Video Stream ID (1 for first, 2 for second, etc.)
+ */
+static inline uint8_t mavlink_msg_herelink_video_stream_information_get_camera_id(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 14);
+}
+
+/**
+ * @brief Get field status from herelink_video_stream_information message
+ *
+ * @return Number of streams available.
+ */
+static inline uint8_t mavlink_msg_herelink_video_stream_information_get_status(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 15);
+}
+
+/**
+ * @brief Get field framerate from herelink_video_stream_information message
+ *
+ * @return [Hz] Frame rate.
+ */
+static inline float mavlink_msg_herelink_video_stream_information_get_framerate(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 0);
+}
+
+/**
+ * @brief Get field resolution_h from herelink_video_stream_information message
+ *
+ * @return [pix] Horizontal resolution.
+ */
+static inline uint16_t mavlink_msg_herelink_video_stream_information_get_resolution_h(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 8);
+}
+
+/**
+ * @brief Get field resolution_v from herelink_video_stream_information message
+ *
+ * @return [pix] Vertical resolution.
+ */
+static inline uint16_t mavlink_msg_herelink_video_stream_information_get_resolution_v(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 10);
+}
+
+/**
+ * @brief Get field bitrate from herelink_video_stream_information message
+ *
+ * @return [bits/s] Bit rate.
+ */
+static inline uint32_t mavlink_msg_herelink_video_stream_information_get_bitrate(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint32_t(msg, 4);
+}
+
+/**
+ * @brief Get field rotation from herelink_video_stream_information message
+ *
+ * @return [deg] Video image rotation clockwise.
+ */
+static inline uint16_t mavlink_msg_herelink_video_stream_information_get_rotation(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 12);
+}
+
+/**
+ * @brief Get field uri from herelink_video_stream_information message
+ *
+ * @return Video stream URI (TCP or RTSP URI ground station should connect to) or port number (UDP port ground station should listen to).
+ */
+static inline uint16_t mavlink_msg_herelink_video_stream_information_get_uri(const mavlink_message_t* msg, char *uri)
+{
+ return _MAV_RETURN_char_array(msg, uri, 230, 16);
+}
+
+/**
+ * @brief Decode a herelink_video_stream_information message into a struct
+ *
+ * @param msg The message to decode
+ * @param herelink_video_stream_information C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_herelink_video_stream_information_decode(const mavlink_message_t* msg, mavlink_herelink_video_stream_information_t* herelink_video_stream_information)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ herelink_video_stream_information->framerate = mavlink_msg_herelink_video_stream_information_get_framerate(msg);
+ herelink_video_stream_information->bitrate = mavlink_msg_herelink_video_stream_information_get_bitrate(msg);
+ herelink_video_stream_information->resolution_h = mavlink_msg_herelink_video_stream_information_get_resolution_h(msg);
+ herelink_video_stream_information->resolution_v = mavlink_msg_herelink_video_stream_information_get_resolution_v(msg);
+ herelink_video_stream_information->rotation = mavlink_msg_herelink_video_stream_information_get_rotation(msg);
+ herelink_video_stream_information->camera_id = mavlink_msg_herelink_video_stream_information_get_camera_id(msg);
+ herelink_video_stream_information->status = mavlink_msg_herelink_video_stream_information_get_status(msg);
+ mavlink_msg_herelink_video_stream_information_get_uri(msg, herelink_video_stream_information->uri);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_HERELINK_VIDEO_STREAM_INFORMATION_LEN? msg->len : MAVLINK_MSG_ID_HERELINK_VIDEO_STREAM_INFORMATION_LEN;
+ memset(herelink_video_stream_information, 0, MAVLINK_MSG_ID_HERELINK_VIDEO_STREAM_INFORMATION_LEN);
+ memcpy(herelink_video_stream_information, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/cubepilot/testsuite.h b/lib/main/MAVLink/cubepilot/testsuite.h
new file mode 100644
index 00000000000..a22c4ba1208
--- /dev/null
+++ b/lib/main/MAVLink/cubepilot/testsuite.h
@@ -0,0 +1,353 @@
+/** @file
+ * @brief MAVLink comm protocol testsuite generated from cubepilot.xml
+ * @see https://mavlink.io/en/
+ */
+#pragma once
+#ifndef CUBEPILOT_TESTSUITE_H
+#define CUBEPILOT_TESTSUITE_H
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+#ifndef MAVLINK_TEST_ALL
+#define MAVLINK_TEST_ALL
+static void mavlink_test_common(uint8_t, uint8_t, mavlink_message_t *last_msg);
+static void mavlink_test_cubepilot(uint8_t, uint8_t, mavlink_message_t *last_msg);
+
+static void mavlink_test_all(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
+{
+ mavlink_test_common(system_id, component_id, last_msg);
+ mavlink_test_cubepilot(system_id, component_id, last_msg);
+}
+#endif
+
+#include "../common/testsuite.h"
+
+
+static void mavlink_test_cubepilot_raw_rc(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_CUBEPILOT_RAW_RC >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_cubepilot_raw_rc_t packet_in = {
+ { 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 36 }
+ };
+ mavlink_cubepilot_raw_rc_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+
+ mav_array_memcpy(packet1.rc_raw, packet_in.rc_raw, sizeof(uint8_t)*32);
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_CUBEPILOT_RAW_RC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_CUBEPILOT_RAW_RC_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_cubepilot_raw_rc_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_cubepilot_raw_rc_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_cubepilot_raw_rc_pack(system_id, component_id, &msg , packet1.rc_raw );
+ mavlink_msg_cubepilot_raw_rc_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_cubepilot_raw_rc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.rc_raw );
+ mavlink_msg_cubepilot_raw_rc_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_HERELINK_VIDEO_STREAM_INFORMATION >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_herelink_video_stream_information_t packet_in = {
+ 17.0,963497672,17651,17755,17859,175,242,"QRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJK"
+ };
+ mavlink_herelink_video_stream_information_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.framerate = packet_in.framerate;
+ packet1.bitrate = packet_in.bitrate;
+ packet1.resolution_h = packet_in.resolution_h;
+ packet1.resolution_v = packet_in.resolution_v;
+ packet1.rotation = packet_in.rotation;
+ packet1.camera_id = packet_in.camera_id;
+ packet1.status = packet_in.status;
+
+ mav_array_memcpy(packet1.uri, packet_in.uri, sizeof(char)*230);
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_HERELINK_VIDEO_STREAM_INFORMATION_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_HERELINK_VIDEO_STREAM_INFORMATION_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_herelink_video_stream_information_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_herelink_video_stream_information_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_herelink_video_stream_information_pack(system_id, component_id, &msg , packet1.camera_id , packet1.status , packet1.framerate , packet1.resolution_h , packet1.resolution_v , packet1.bitrate , packet1.rotation , packet1.uri );
+ mavlink_msg_herelink_video_stream_information_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_herelink_video_stream_information_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.camera_id , packet1.status , packet1.framerate , packet1.resolution_h , packet1.resolution_v , packet1.bitrate , packet1.rotation , packet1.uri );
+ mavlink_msg_herelink_video_stream_information_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_HERELINK_TELEM >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_herelink_telem_t packet_in = {
+ 963497464,963497672,963497880,17859,17963,18067,187
+ };
+ mavlink_herelink_telem_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.rf_freq = packet_in.rf_freq;
+ packet1.link_bw = packet_in.link_bw;
+ packet1.link_rate = packet_in.link_rate;
+ packet1.snr = packet_in.snr;
+ packet1.cpu_temp = packet_in.cpu_temp;
+ packet1.board_temp = packet_in.board_temp;
+ packet1.rssi = packet_in.rssi;
+
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_HERELINK_TELEM_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_HERELINK_TELEM_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_herelink_telem_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_herelink_telem_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_herelink_telem_pack(system_id, component_id, &msg , packet1.rssi , packet1.snr , packet1.rf_freq , packet1.link_bw , packet1.link_rate , packet1.cpu_temp , packet1.board_temp );
+ mavlink_msg_herelink_telem_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_herelink_telem_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.rssi , packet1.snr , packet1.rf_freq , packet1.link_bw , packet1.link_rate , packet1.cpu_temp , packet1.board_temp );
+ mavlink_msg_herelink_telem_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_START >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_cubepilot_firmware_update_start_t packet_in = {
+ 963497464,963497672,29,96
+ };
+ mavlink_cubepilot_firmware_update_start_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.size = packet_in.size;
+ packet1.crc = packet_in.crc;
+ packet1.target_system = packet_in.target_system;
+ packet1.target_component = packet_in.target_component;
+
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_START_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_START_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_cubepilot_firmware_update_start_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_cubepilot_firmware_update_start_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_cubepilot_firmware_update_start_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.size , packet1.crc );
+ mavlink_msg_cubepilot_firmware_update_start_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_cubepilot_firmware_update_start_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.size , packet1.crc );
+ mavlink_msg_cubepilot_firmware_update_start_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_RESP >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_cubepilot_firmware_update_resp_t packet_in = {
+ 963497464,17,84
+ };
+ mavlink_cubepilot_firmware_update_resp_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.offset = packet_in.offset;
+ packet1.target_system = packet_in.target_system;
+ packet1.target_component = packet_in.target_component;
+
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_RESP_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_CUBEPILOT_FIRMWARE_UPDATE_RESP_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_cubepilot_firmware_update_resp_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_cubepilot_firmware_update_resp_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_cubepilot_firmware_update_resp_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.offset );
+ mavlink_msg_cubepilot_firmware_update_resp_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_cubepilot_firmware_update_resp_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.offset );
+ mavlink_msg_cubepilot_firmware_update_resp_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; imsgid = MAVLINK_MSG_ID_ICAROUS_HEARTBEAT;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_MIN_LEN, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_LEN, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_CRC);
+}
+
+/**
+ * @brief Pack a icarous_heartbeat 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 status See the FMS_STATE enum.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_icarous_heartbeat_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ uint8_t status)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_LEN];
+ _mav_put_uint8_t(buf, 0, status);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_LEN);
+#else
+ mavlink_icarous_heartbeat_t packet;
+ packet.status = status;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_ICAROUS_HEARTBEAT;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_MIN_LEN, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_LEN, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_MIN_LEN, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a icarous_heartbeat 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 status See the FMS_STATE enum.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_icarous_heartbeat_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint8_t status)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_LEN];
+ _mav_put_uint8_t(buf, 0, status);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_LEN);
+#else
+ mavlink_icarous_heartbeat_t packet;
+ packet.status = status;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_ICAROUS_HEARTBEAT;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_MIN_LEN, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_LEN, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_CRC);
+}
+
+/**
+ * @brief Encode a icarous_heartbeat 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 icarous_heartbeat C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_icarous_heartbeat_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_icarous_heartbeat_t* icarous_heartbeat)
+{
+ return mavlink_msg_icarous_heartbeat_pack(system_id, component_id, msg, icarous_heartbeat->status);
+}
+
+/**
+ * @brief Encode a icarous_heartbeat 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 icarous_heartbeat C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_icarous_heartbeat_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_icarous_heartbeat_t* icarous_heartbeat)
+{
+ return mavlink_msg_icarous_heartbeat_pack_chan(system_id, component_id, chan, msg, icarous_heartbeat->status);
+}
+
+/**
+ * @brief Encode a icarous_heartbeat 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 icarous_heartbeat C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_icarous_heartbeat_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_icarous_heartbeat_t* icarous_heartbeat)
+{
+ return mavlink_msg_icarous_heartbeat_pack_status(system_id, component_id, _status, msg, icarous_heartbeat->status);
+}
+
+/**
+ * @brief Send a icarous_heartbeat message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param status See the FMS_STATE enum.
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_icarous_heartbeat_send(mavlink_channel_t chan, uint8_t status)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_LEN];
+ _mav_put_uint8_t(buf, 0, status);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT, buf, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_MIN_LEN, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_LEN, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_CRC);
+#else
+ mavlink_icarous_heartbeat_t packet;
+ packet.status = status;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT, (const char *)&packet, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_MIN_LEN, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_LEN, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_CRC);
+#endif
+}
+
+/**
+ * @brief Send a icarous_heartbeat message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_icarous_heartbeat_send_struct(mavlink_channel_t chan, const mavlink_icarous_heartbeat_t* icarous_heartbeat)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_icarous_heartbeat_send(chan, icarous_heartbeat->status);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT, (const char *)icarous_heartbeat, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_MIN_LEN, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_LEN, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_icarous_heartbeat_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t status)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint8_t(buf, 0, status);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT, buf, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_MIN_LEN, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_LEN, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_CRC);
+#else
+ mavlink_icarous_heartbeat_t *packet = (mavlink_icarous_heartbeat_t *)msgbuf;
+ packet->status = status;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT, (const char *)packet, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_MIN_LEN, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_LEN, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE ICAROUS_HEARTBEAT UNPACKING
+
+
+/**
+ * @brief Get field status from icarous_heartbeat message
+ *
+ * @return See the FMS_STATE enum.
+ */
+static inline uint8_t mavlink_msg_icarous_heartbeat_get_status(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 0);
+}
+
+/**
+ * @brief Decode a icarous_heartbeat message into a struct
+ *
+ * @param msg The message to decode
+ * @param icarous_heartbeat C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_icarous_heartbeat_decode(const mavlink_message_t* msg, mavlink_icarous_heartbeat_t* icarous_heartbeat)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ icarous_heartbeat->status = mavlink_msg_icarous_heartbeat_get_status(msg);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_LEN? msg->len : MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_LEN;
+ memset(icarous_heartbeat, 0, MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_LEN);
+ memcpy(icarous_heartbeat, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/icarous/mavlink_msg_icarous_kinematic_bands.h b/lib/main/MAVLink/icarous/mavlink_msg_icarous_kinematic_bands.h
new file mode 100644
index 00000000000..325dde22313
--- /dev/null
+++ b/lib/main/MAVLink/icarous/mavlink_msg_icarous_kinematic_bands.h
@@ -0,0 +1,680 @@
+#pragma once
+// MESSAGE ICAROUS_KINEMATIC_BANDS PACKING
+
+#define MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS 42001
+
+
+typedef struct __mavlink_icarous_kinematic_bands_t {
+ float min1; /*< [deg] min angle (degrees)*/
+ float max1; /*< [deg] max angle (degrees)*/
+ float min2; /*< [deg] min angle (degrees)*/
+ float max2; /*< [deg] max angle (degrees)*/
+ float min3; /*< [deg] min angle (degrees)*/
+ float max3; /*< [deg] max angle (degrees)*/
+ float min4; /*< [deg] min angle (degrees)*/
+ float max4; /*< [deg] max angle (degrees)*/
+ float min5; /*< [deg] min angle (degrees)*/
+ float max5; /*< [deg] max angle (degrees)*/
+ int8_t numBands; /*< Number of track bands*/
+ uint8_t type1; /*< See the TRACK_BAND_TYPES enum.*/
+ uint8_t type2; /*< See the TRACK_BAND_TYPES enum.*/
+ uint8_t type3; /*< See the TRACK_BAND_TYPES enum.*/
+ uint8_t type4; /*< See the TRACK_BAND_TYPES enum.*/
+ uint8_t type5; /*< See the TRACK_BAND_TYPES enum.*/
+} mavlink_icarous_kinematic_bands_t;
+
+#define MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS_LEN 46
+#define MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS_MIN_LEN 46
+#define MAVLINK_MSG_ID_42001_LEN 46
+#define MAVLINK_MSG_ID_42001_MIN_LEN 46
+
+#define MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS_CRC 239
+#define MAVLINK_MSG_ID_42001_CRC 239
+
+
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_ICAROUS_KINEMATIC_BANDS { \
+ 42001, \
+ "ICAROUS_KINEMATIC_BANDS", \
+ 16, \
+ { { "numBands", NULL, MAVLINK_TYPE_INT8_T, 0, 40, offsetof(mavlink_icarous_kinematic_bands_t, numBands) }, \
+ { "type1", NULL, MAVLINK_TYPE_UINT8_T, 0, 41, offsetof(mavlink_icarous_kinematic_bands_t, type1) }, \
+ { "min1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_icarous_kinematic_bands_t, min1) }, \
+ { "max1", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_icarous_kinematic_bands_t, max1) }, \
+ { "type2", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_icarous_kinematic_bands_t, type2) }, \
+ { "min2", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_icarous_kinematic_bands_t, min2) }, \
+ { "max2", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_icarous_kinematic_bands_t, max2) }, \
+ { "type3", NULL, MAVLINK_TYPE_UINT8_T, 0, 43, offsetof(mavlink_icarous_kinematic_bands_t, type3) }, \
+ { "min3", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_icarous_kinematic_bands_t, min3) }, \
+ { "max3", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_icarous_kinematic_bands_t, max3) }, \
+ { "type4", NULL, MAVLINK_TYPE_UINT8_T, 0, 44, offsetof(mavlink_icarous_kinematic_bands_t, type4) }, \
+ { "min4", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_icarous_kinematic_bands_t, min4) }, \
+ { "max4", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_icarous_kinematic_bands_t, max4) }, \
+ { "type5", NULL, MAVLINK_TYPE_UINT8_T, 0, 45, offsetof(mavlink_icarous_kinematic_bands_t, type5) }, \
+ { "min5", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_icarous_kinematic_bands_t, min5) }, \
+ { "max5", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_icarous_kinematic_bands_t, max5) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_ICAROUS_KINEMATIC_BANDS { \
+ "ICAROUS_KINEMATIC_BANDS", \
+ 16, \
+ { { "numBands", NULL, MAVLINK_TYPE_INT8_T, 0, 40, offsetof(mavlink_icarous_kinematic_bands_t, numBands) }, \
+ { "type1", NULL, MAVLINK_TYPE_UINT8_T, 0, 41, offsetof(mavlink_icarous_kinematic_bands_t, type1) }, \
+ { "min1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_icarous_kinematic_bands_t, min1) }, \
+ { "max1", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_icarous_kinematic_bands_t, max1) }, \
+ { "type2", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_icarous_kinematic_bands_t, type2) }, \
+ { "min2", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_icarous_kinematic_bands_t, min2) }, \
+ { "max2", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_icarous_kinematic_bands_t, max2) }, \
+ { "type3", NULL, MAVLINK_TYPE_UINT8_T, 0, 43, offsetof(mavlink_icarous_kinematic_bands_t, type3) }, \
+ { "min3", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_icarous_kinematic_bands_t, min3) }, \
+ { "max3", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_icarous_kinematic_bands_t, max3) }, \
+ { "type4", NULL, MAVLINK_TYPE_UINT8_T, 0, 44, offsetof(mavlink_icarous_kinematic_bands_t, type4) }, \
+ { "min4", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_icarous_kinematic_bands_t, min4) }, \
+ { "max4", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_icarous_kinematic_bands_t, max4) }, \
+ { "type5", NULL, MAVLINK_TYPE_UINT8_T, 0, 45, offsetof(mavlink_icarous_kinematic_bands_t, type5) }, \
+ { "min5", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_icarous_kinematic_bands_t, min5) }, \
+ { "max5", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_icarous_kinematic_bands_t, max5) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a icarous_kinematic_bands 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 numBands Number of track bands
+ * @param type1 See the TRACK_BAND_TYPES enum.
+ * @param min1 [deg] min angle (degrees)
+ * @param max1 [deg] max angle (degrees)
+ * @param type2 See the TRACK_BAND_TYPES enum.
+ * @param min2 [deg] min angle (degrees)
+ * @param max2 [deg] max angle (degrees)
+ * @param type3 See the TRACK_BAND_TYPES enum.
+ * @param min3 [deg] min angle (degrees)
+ * @param max3 [deg] max angle (degrees)
+ * @param type4 See the TRACK_BAND_TYPES enum.
+ * @param min4 [deg] min angle (degrees)
+ * @param max4 [deg] max angle (degrees)
+ * @param type5 See the TRACK_BAND_TYPES enum.
+ * @param min5 [deg] min angle (degrees)
+ * @param max5 [deg] max angle (degrees)
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_icarous_kinematic_bands_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ int8_t numBands, uint8_t type1, float min1, float max1, uint8_t type2, float min2, float max2, uint8_t type3, float min3, float max3, uint8_t type4, float min4, float max4, uint8_t type5, float min5, float max5)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS_LEN];
+ _mav_put_float(buf, 0, min1);
+ _mav_put_float(buf, 4, max1);
+ _mav_put_float(buf, 8, min2);
+ _mav_put_float(buf, 12, max2);
+ _mav_put_float(buf, 16, min3);
+ _mav_put_float(buf, 20, max3);
+ _mav_put_float(buf, 24, min4);
+ _mav_put_float(buf, 28, max4);
+ _mav_put_float(buf, 32, min5);
+ _mav_put_float(buf, 36, max5);
+ _mav_put_int8_t(buf, 40, numBands);
+ _mav_put_uint8_t(buf, 41, type1);
+ _mav_put_uint8_t(buf, 42, type2);
+ _mav_put_uint8_t(buf, 43, type3);
+ _mav_put_uint8_t(buf, 44, type4);
+ _mav_put_uint8_t(buf, 45, type5);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS_LEN);
+#else
+ mavlink_icarous_kinematic_bands_t packet;
+ packet.min1 = min1;
+ packet.max1 = max1;
+ packet.min2 = min2;
+ packet.max2 = max2;
+ packet.min3 = min3;
+ packet.max3 = max3;
+ packet.min4 = min4;
+ packet.max4 = max4;
+ packet.min5 = min5;
+ packet.max5 = max5;
+ packet.numBands = numBands;
+ packet.type1 = type1;
+ packet.type2 = type2;
+ packet.type3 = type3;
+ packet.type4 = type4;
+ packet.type5 = type5;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS_MIN_LEN, MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS_LEN, MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS_CRC);
+}
+
+/**
+ * @brief Pack a icarous_kinematic_bands 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 numBands Number of track bands
+ * @param type1 See the TRACK_BAND_TYPES enum.
+ * @param min1 [deg] min angle (degrees)
+ * @param max1 [deg] max angle (degrees)
+ * @param type2 See the TRACK_BAND_TYPES enum.
+ * @param min2 [deg] min angle (degrees)
+ * @param max2 [deg] max angle (degrees)
+ * @param type3 See the TRACK_BAND_TYPES enum.
+ * @param min3 [deg] min angle (degrees)
+ * @param max3 [deg] max angle (degrees)
+ * @param type4 See the TRACK_BAND_TYPES enum.
+ * @param min4 [deg] min angle (degrees)
+ * @param max4 [deg] max angle (degrees)
+ * @param type5 See the TRACK_BAND_TYPES enum.
+ * @param min5 [deg] min angle (degrees)
+ * @param max5 [deg] max angle (degrees)
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_icarous_kinematic_bands_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ int8_t numBands, uint8_t type1, float min1, float max1, uint8_t type2, float min2, float max2, uint8_t type3, float min3, float max3, uint8_t type4, float min4, float max4, uint8_t type5, float min5, float max5)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS_LEN];
+ _mav_put_float(buf, 0, min1);
+ _mav_put_float(buf, 4, max1);
+ _mav_put_float(buf, 8, min2);
+ _mav_put_float(buf, 12, max2);
+ _mav_put_float(buf, 16, min3);
+ _mav_put_float(buf, 20, max3);
+ _mav_put_float(buf, 24, min4);
+ _mav_put_float(buf, 28, max4);
+ _mav_put_float(buf, 32, min5);
+ _mav_put_float(buf, 36, max5);
+ _mav_put_int8_t(buf, 40, numBands);
+ _mav_put_uint8_t(buf, 41, type1);
+ _mav_put_uint8_t(buf, 42, type2);
+ _mav_put_uint8_t(buf, 43, type3);
+ _mav_put_uint8_t(buf, 44, type4);
+ _mav_put_uint8_t(buf, 45, type5);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS_LEN);
+#else
+ mavlink_icarous_kinematic_bands_t packet;
+ packet.min1 = min1;
+ packet.max1 = max1;
+ packet.min2 = min2;
+ packet.max2 = max2;
+ packet.min3 = min3;
+ packet.max3 = max3;
+ packet.min4 = min4;
+ packet.max4 = max4;
+ packet.min5 = min5;
+ packet.max5 = max5;
+ packet.numBands = numBands;
+ packet.type1 = type1;
+ packet.type2 = type2;
+ packet.type3 = type3;
+ packet.type4 = type4;
+ packet.type5 = type5;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS_MIN_LEN, MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS_LEN, MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS_MIN_LEN, MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a icarous_kinematic_bands 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 numBands Number of track bands
+ * @param type1 See the TRACK_BAND_TYPES enum.
+ * @param min1 [deg] min angle (degrees)
+ * @param max1 [deg] max angle (degrees)
+ * @param type2 See the TRACK_BAND_TYPES enum.
+ * @param min2 [deg] min angle (degrees)
+ * @param max2 [deg] max angle (degrees)
+ * @param type3 See the TRACK_BAND_TYPES enum.
+ * @param min3 [deg] min angle (degrees)
+ * @param max3 [deg] max angle (degrees)
+ * @param type4 See the TRACK_BAND_TYPES enum.
+ * @param min4 [deg] min angle (degrees)
+ * @param max4 [deg] max angle (degrees)
+ * @param type5 See the TRACK_BAND_TYPES enum.
+ * @param min5 [deg] min angle (degrees)
+ * @param max5 [deg] max angle (degrees)
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_icarous_kinematic_bands_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ int8_t numBands,uint8_t type1,float min1,float max1,uint8_t type2,float min2,float max2,uint8_t type3,float min3,float max3,uint8_t type4,float min4,float max4,uint8_t type5,float min5,float max5)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS_LEN];
+ _mav_put_float(buf, 0, min1);
+ _mav_put_float(buf, 4, max1);
+ _mav_put_float(buf, 8, min2);
+ _mav_put_float(buf, 12, max2);
+ _mav_put_float(buf, 16, min3);
+ _mav_put_float(buf, 20, max3);
+ _mav_put_float(buf, 24, min4);
+ _mav_put_float(buf, 28, max4);
+ _mav_put_float(buf, 32, min5);
+ _mav_put_float(buf, 36, max5);
+ _mav_put_int8_t(buf, 40, numBands);
+ _mav_put_uint8_t(buf, 41, type1);
+ _mav_put_uint8_t(buf, 42, type2);
+ _mav_put_uint8_t(buf, 43, type3);
+ _mav_put_uint8_t(buf, 44, type4);
+ _mav_put_uint8_t(buf, 45, type5);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS_LEN);
+#else
+ mavlink_icarous_kinematic_bands_t packet;
+ packet.min1 = min1;
+ packet.max1 = max1;
+ packet.min2 = min2;
+ packet.max2 = max2;
+ packet.min3 = min3;
+ packet.max3 = max3;
+ packet.min4 = min4;
+ packet.max4 = max4;
+ packet.min5 = min5;
+ packet.max5 = max5;
+ packet.numBands = numBands;
+ packet.type1 = type1;
+ packet.type2 = type2;
+ packet.type3 = type3;
+ packet.type4 = type4;
+ packet.type5 = type5;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS_MIN_LEN, MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS_LEN, MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS_CRC);
+}
+
+/**
+ * @brief Encode a icarous_kinematic_bands 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 icarous_kinematic_bands C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_icarous_kinematic_bands_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_icarous_kinematic_bands_t* icarous_kinematic_bands)
+{
+ return mavlink_msg_icarous_kinematic_bands_pack(system_id, component_id, msg, icarous_kinematic_bands->numBands, icarous_kinematic_bands->type1, icarous_kinematic_bands->min1, icarous_kinematic_bands->max1, icarous_kinematic_bands->type2, icarous_kinematic_bands->min2, icarous_kinematic_bands->max2, icarous_kinematic_bands->type3, icarous_kinematic_bands->min3, icarous_kinematic_bands->max3, icarous_kinematic_bands->type4, icarous_kinematic_bands->min4, icarous_kinematic_bands->max4, icarous_kinematic_bands->type5, icarous_kinematic_bands->min5, icarous_kinematic_bands->max5);
+}
+
+/**
+ * @brief Encode a icarous_kinematic_bands 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 icarous_kinematic_bands C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_icarous_kinematic_bands_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_icarous_kinematic_bands_t* icarous_kinematic_bands)
+{
+ return mavlink_msg_icarous_kinematic_bands_pack_chan(system_id, component_id, chan, msg, icarous_kinematic_bands->numBands, icarous_kinematic_bands->type1, icarous_kinematic_bands->min1, icarous_kinematic_bands->max1, icarous_kinematic_bands->type2, icarous_kinematic_bands->min2, icarous_kinematic_bands->max2, icarous_kinematic_bands->type3, icarous_kinematic_bands->min3, icarous_kinematic_bands->max3, icarous_kinematic_bands->type4, icarous_kinematic_bands->min4, icarous_kinematic_bands->max4, icarous_kinematic_bands->type5, icarous_kinematic_bands->min5, icarous_kinematic_bands->max5);
+}
+
+/**
+ * @brief Encode a icarous_kinematic_bands 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 icarous_kinematic_bands C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_icarous_kinematic_bands_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_icarous_kinematic_bands_t* icarous_kinematic_bands)
+{
+ return mavlink_msg_icarous_kinematic_bands_pack_status(system_id, component_id, _status, msg, icarous_kinematic_bands->numBands, icarous_kinematic_bands->type1, icarous_kinematic_bands->min1, icarous_kinematic_bands->max1, icarous_kinematic_bands->type2, icarous_kinematic_bands->min2, icarous_kinematic_bands->max2, icarous_kinematic_bands->type3, icarous_kinematic_bands->min3, icarous_kinematic_bands->max3, icarous_kinematic_bands->type4, icarous_kinematic_bands->min4, icarous_kinematic_bands->max4, icarous_kinematic_bands->type5, icarous_kinematic_bands->min5, icarous_kinematic_bands->max5);
+}
+
+/**
+ * @brief Send a icarous_kinematic_bands message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param numBands Number of track bands
+ * @param type1 See the TRACK_BAND_TYPES enum.
+ * @param min1 [deg] min angle (degrees)
+ * @param max1 [deg] max angle (degrees)
+ * @param type2 See the TRACK_BAND_TYPES enum.
+ * @param min2 [deg] min angle (degrees)
+ * @param max2 [deg] max angle (degrees)
+ * @param type3 See the TRACK_BAND_TYPES enum.
+ * @param min3 [deg] min angle (degrees)
+ * @param max3 [deg] max angle (degrees)
+ * @param type4 See the TRACK_BAND_TYPES enum.
+ * @param min4 [deg] min angle (degrees)
+ * @param max4 [deg] max angle (degrees)
+ * @param type5 See the TRACK_BAND_TYPES enum.
+ * @param min5 [deg] min angle (degrees)
+ * @param max5 [deg] max angle (degrees)
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_icarous_kinematic_bands_send(mavlink_channel_t chan, int8_t numBands, uint8_t type1, float min1, float max1, uint8_t type2, float min2, float max2, uint8_t type3, float min3, float max3, uint8_t type4, float min4, float max4, uint8_t type5, float min5, float max5)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS_LEN];
+ _mav_put_float(buf, 0, min1);
+ _mav_put_float(buf, 4, max1);
+ _mav_put_float(buf, 8, min2);
+ _mav_put_float(buf, 12, max2);
+ _mav_put_float(buf, 16, min3);
+ _mav_put_float(buf, 20, max3);
+ _mav_put_float(buf, 24, min4);
+ _mav_put_float(buf, 28, max4);
+ _mav_put_float(buf, 32, min5);
+ _mav_put_float(buf, 36, max5);
+ _mav_put_int8_t(buf, 40, numBands);
+ _mav_put_uint8_t(buf, 41, type1);
+ _mav_put_uint8_t(buf, 42, type2);
+ _mav_put_uint8_t(buf, 43, type3);
+ _mav_put_uint8_t(buf, 44, type4);
+ _mav_put_uint8_t(buf, 45, type5);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS, buf, MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS_MIN_LEN, MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS_LEN, MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS_CRC);
+#else
+ mavlink_icarous_kinematic_bands_t packet;
+ packet.min1 = min1;
+ packet.max1 = max1;
+ packet.min2 = min2;
+ packet.max2 = max2;
+ packet.min3 = min3;
+ packet.max3 = max3;
+ packet.min4 = min4;
+ packet.max4 = max4;
+ packet.min5 = min5;
+ packet.max5 = max5;
+ packet.numBands = numBands;
+ packet.type1 = type1;
+ packet.type2 = type2;
+ packet.type3 = type3;
+ packet.type4 = type4;
+ packet.type5 = type5;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS, (const char *)&packet, MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS_MIN_LEN, MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS_LEN, MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS_CRC);
+#endif
+}
+
+/**
+ * @brief Send a icarous_kinematic_bands message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_icarous_kinematic_bands_send_struct(mavlink_channel_t chan, const mavlink_icarous_kinematic_bands_t* icarous_kinematic_bands)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_icarous_kinematic_bands_send(chan, icarous_kinematic_bands->numBands, icarous_kinematic_bands->type1, icarous_kinematic_bands->min1, icarous_kinematic_bands->max1, icarous_kinematic_bands->type2, icarous_kinematic_bands->min2, icarous_kinematic_bands->max2, icarous_kinematic_bands->type3, icarous_kinematic_bands->min3, icarous_kinematic_bands->max3, icarous_kinematic_bands->type4, icarous_kinematic_bands->min4, icarous_kinematic_bands->max4, icarous_kinematic_bands->type5, icarous_kinematic_bands->min5, icarous_kinematic_bands->max5);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS, (const char *)icarous_kinematic_bands, MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS_MIN_LEN, MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS_LEN, MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_icarous_kinematic_bands_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, int8_t numBands, uint8_t type1, float min1, float max1, uint8_t type2, float min2, float max2, uint8_t type3, float min3, float max3, uint8_t type4, float min4, float max4, uint8_t type5, float min5, float max5)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_float(buf, 0, min1);
+ _mav_put_float(buf, 4, max1);
+ _mav_put_float(buf, 8, min2);
+ _mav_put_float(buf, 12, max2);
+ _mav_put_float(buf, 16, min3);
+ _mav_put_float(buf, 20, max3);
+ _mav_put_float(buf, 24, min4);
+ _mav_put_float(buf, 28, max4);
+ _mav_put_float(buf, 32, min5);
+ _mav_put_float(buf, 36, max5);
+ _mav_put_int8_t(buf, 40, numBands);
+ _mav_put_uint8_t(buf, 41, type1);
+ _mav_put_uint8_t(buf, 42, type2);
+ _mav_put_uint8_t(buf, 43, type3);
+ _mav_put_uint8_t(buf, 44, type4);
+ _mav_put_uint8_t(buf, 45, type5);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS, buf, MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS_MIN_LEN, MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS_LEN, MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS_CRC);
+#else
+ mavlink_icarous_kinematic_bands_t *packet = (mavlink_icarous_kinematic_bands_t *)msgbuf;
+ packet->min1 = min1;
+ packet->max1 = max1;
+ packet->min2 = min2;
+ packet->max2 = max2;
+ packet->min3 = min3;
+ packet->max3 = max3;
+ packet->min4 = min4;
+ packet->max4 = max4;
+ packet->min5 = min5;
+ packet->max5 = max5;
+ packet->numBands = numBands;
+ packet->type1 = type1;
+ packet->type2 = type2;
+ packet->type3 = type3;
+ packet->type4 = type4;
+ packet->type5 = type5;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS, (const char *)packet, MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS_MIN_LEN, MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS_LEN, MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE ICAROUS_KINEMATIC_BANDS UNPACKING
+
+
+/**
+ * @brief Get field numBands from icarous_kinematic_bands message
+ *
+ * @return Number of track bands
+ */
+static inline int8_t mavlink_msg_icarous_kinematic_bands_get_numBands(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_int8_t(msg, 40);
+}
+
+/**
+ * @brief Get field type1 from icarous_kinematic_bands message
+ *
+ * @return See the TRACK_BAND_TYPES enum.
+ */
+static inline uint8_t mavlink_msg_icarous_kinematic_bands_get_type1(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 41);
+}
+
+/**
+ * @brief Get field min1 from icarous_kinematic_bands message
+ *
+ * @return [deg] min angle (degrees)
+ */
+static inline float mavlink_msg_icarous_kinematic_bands_get_min1(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 0);
+}
+
+/**
+ * @brief Get field max1 from icarous_kinematic_bands message
+ *
+ * @return [deg] max angle (degrees)
+ */
+static inline float mavlink_msg_icarous_kinematic_bands_get_max1(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 4);
+}
+
+/**
+ * @brief Get field type2 from icarous_kinematic_bands message
+ *
+ * @return See the TRACK_BAND_TYPES enum.
+ */
+static inline uint8_t mavlink_msg_icarous_kinematic_bands_get_type2(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 42);
+}
+
+/**
+ * @brief Get field min2 from icarous_kinematic_bands message
+ *
+ * @return [deg] min angle (degrees)
+ */
+static inline float mavlink_msg_icarous_kinematic_bands_get_min2(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 8);
+}
+
+/**
+ * @brief Get field max2 from icarous_kinematic_bands message
+ *
+ * @return [deg] max angle (degrees)
+ */
+static inline float mavlink_msg_icarous_kinematic_bands_get_max2(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 12);
+}
+
+/**
+ * @brief Get field type3 from icarous_kinematic_bands message
+ *
+ * @return See the TRACK_BAND_TYPES enum.
+ */
+static inline uint8_t mavlink_msg_icarous_kinematic_bands_get_type3(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 43);
+}
+
+/**
+ * @brief Get field min3 from icarous_kinematic_bands message
+ *
+ * @return [deg] min angle (degrees)
+ */
+static inline float mavlink_msg_icarous_kinematic_bands_get_min3(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 16);
+}
+
+/**
+ * @brief Get field max3 from icarous_kinematic_bands message
+ *
+ * @return [deg] max angle (degrees)
+ */
+static inline float mavlink_msg_icarous_kinematic_bands_get_max3(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 20);
+}
+
+/**
+ * @brief Get field type4 from icarous_kinematic_bands message
+ *
+ * @return See the TRACK_BAND_TYPES enum.
+ */
+static inline uint8_t mavlink_msg_icarous_kinematic_bands_get_type4(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 44);
+}
+
+/**
+ * @brief Get field min4 from icarous_kinematic_bands message
+ *
+ * @return [deg] min angle (degrees)
+ */
+static inline float mavlink_msg_icarous_kinematic_bands_get_min4(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 24);
+}
+
+/**
+ * @brief Get field max4 from icarous_kinematic_bands message
+ *
+ * @return [deg] max angle (degrees)
+ */
+static inline float mavlink_msg_icarous_kinematic_bands_get_max4(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 28);
+}
+
+/**
+ * @brief Get field type5 from icarous_kinematic_bands message
+ *
+ * @return See the TRACK_BAND_TYPES enum.
+ */
+static inline uint8_t mavlink_msg_icarous_kinematic_bands_get_type5(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 45);
+}
+
+/**
+ * @brief Get field min5 from icarous_kinematic_bands message
+ *
+ * @return [deg] min angle (degrees)
+ */
+static inline float mavlink_msg_icarous_kinematic_bands_get_min5(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 32);
+}
+
+/**
+ * @brief Get field max5 from icarous_kinematic_bands message
+ *
+ * @return [deg] max angle (degrees)
+ */
+static inline float mavlink_msg_icarous_kinematic_bands_get_max5(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 36);
+}
+
+/**
+ * @brief Decode a icarous_kinematic_bands message into a struct
+ *
+ * @param msg The message to decode
+ * @param icarous_kinematic_bands C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_icarous_kinematic_bands_decode(const mavlink_message_t* msg, mavlink_icarous_kinematic_bands_t* icarous_kinematic_bands)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ icarous_kinematic_bands->min1 = mavlink_msg_icarous_kinematic_bands_get_min1(msg);
+ icarous_kinematic_bands->max1 = mavlink_msg_icarous_kinematic_bands_get_max1(msg);
+ icarous_kinematic_bands->min2 = mavlink_msg_icarous_kinematic_bands_get_min2(msg);
+ icarous_kinematic_bands->max2 = mavlink_msg_icarous_kinematic_bands_get_max2(msg);
+ icarous_kinematic_bands->min3 = mavlink_msg_icarous_kinematic_bands_get_min3(msg);
+ icarous_kinematic_bands->max3 = mavlink_msg_icarous_kinematic_bands_get_max3(msg);
+ icarous_kinematic_bands->min4 = mavlink_msg_icarous_kinematic_bands_get_min4(msg);
+ icarous_kinematic_bands->max4 = mavlink_msg_icarous_kinematic_bands_get_max4(msg);
+ icarous_kinematic_bands->min5 = mavlink_msg_icarous_kinematic_bands_get_min5(msg);
+ icarous_kinematic_bands->max5 = mavlink_msg_icarous_kinematic_bands_get_max5(msg);
+ icarous_kinematic_bands->numBands = mavlink_msg_icarous_kinematic_bands_get_numBands(msg);
+ icarous_kinematic_bands->type1 = mavlink_msg_icarous_kinematic_bands_get_type1(msg);
+ icarous_kinematic_bands->type2 = mavlink_msg_icarous_kinematic_bands_get_type2(msg);
+ icarous_kinematic_bands->type3 = mavlink_msg_icarous_kinematic_bands_get_type3(msg);
+ icarous_kinematic_bands->type4 = mavlink_msg_icarous_kinematic_bands_get_type4(msg);
+ icarous_kinematic_bands->type5 = mavlink_msg_icarous_kinematic_bands_get_type5(msg);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS_LEN? msg->len : MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS_LEN;
+ memset(icarous_kinematic_bands, 0, MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS_LEN);
+ memcpy(icarous_kinematic_bands, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/icarous/testsuite.h b/lib/main/MAVLink/icarous/testsuite.h
new file mode 100644
index 00000000000..6526c7fb795
--- /dev/null
+++ b/lib/main/MAVLink/icarous/testsuite.h
@@ -0,0 +1,170 @@
+/** @file
+ * @brief MAVLink comm protocol testsuite generated from icarous.xml
+ * @see https://mavlink.io/en/
+ */
+#pragma once
+#ifndef ICAROUS_TESTSUITE_H
+#define ICAROUS_TESTSUITE_H
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+#ifndef MAVLINK_TEST_ALL
+#define MAVLINK_TEST_ALL
+
+static void mavlink_test_icarous(uint8_t, uint8_t, mavlink_message_t *last_msg);
+
+static void mavlink_test_all(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
+{
+
+ mavlink_test_icarous(system_id, component_id, last_msg);
+}
+#endif
+
+
+
+
+static void mavlink_test_icarous_heartbeat(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_ICAROUS_HEARTBEAT >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_icarous_heartbeat_t packet_in = {
+ 5
+ };
+ mavlink_icarous_heartbeat_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.status = packet_in.status;
+
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_ICAROUS_HEARTBEAT_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_icarous_heartbeat_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_icarous_heartbeat_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_icarous_heartbeat_pack(system_id, component_id, &msg , packet1.status );
+ mavlink_msg_icarous_heartbeat_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_icarous_heartbeat_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.status );
+ mavlink_msg_icarous_heartbeat_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_icarous_kinematic_bands_t packet_in = {
+ 17.0,45.0,73.0,101.0,129.0,157.0,185.0,213.0,241.0,269.0,125,192,3,70,137,204
+ };
+ mavlink_icarous_kinematic_bands_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.min1 = packet_in.min1;
+ packet1.max1 = packet_in.max1;
+ packet1.min2 = packet_in.min2;
+ packet1.max2 = packet_in.max2;
+ packet1.min3 = packet_in.min3;
+ packet1.max3 = packet_in.max3;
+ packet1.min4 = packet_in.min4;
+ packet1.max4 = packet_in.max4;
+ packet1.min5 = packet_in.min5;
+ packet1.max5 = packet_in.max5;
+ packet1.numBands = packet_in.numBands;
+ packet1.type1 = packet_in.type1;
+ packet1.type2 = packet_in.type2;
+ packet1.type3 = packet_in.type3;
+ packet1.type4 = packet_in.type4;
+ packet1.type5 = packet_in.type5;
+
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_ICAROUS_KINEMATIC_BANDS_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_icarous_kinematic_bands_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_icarous_kinematic_bands_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_icarous_kinematic_bands_pack(system_id, component_id, &msg , packet1.numBands , packet1.type1 , packet1.min1 , packet1.max1 , packet1.type2 , packet1.min2 , packet1.max2 , packet1.type3 , packet1.min3 , packet1.max3 , packet1.type4 , packet1.min4 , packet1.max4 , packet1.type5 , packet1.min5 , packet1.max5 );
+ mavlink_msg_icarous_kinematic_bands_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_icarous_kinematic_bands_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.numBands , packet1.type1 , packet1.min1 , packet1.max1 , packet1.type2 , packet1.min2 , packet1.max2 , packet1.type3 , packet1.min3 , packet1.max3 , packet1.type4 , packet1.min4 , packet1.max4 , packet1.type5 , packet1.min5 , packet1.max5 );
+ mavlink_msg_icarous_kinematic_bands_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; imsgid = MAVLINK_MSG_ID_LOWEHEISER_GOV_EFI;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOWEHEISER_GOV_EFI_MIN_LEN, MAVLINK_MSG_ID_LOWEHEISER_GOV_EFI_LEN, MAVLINK_MSG_ID_LOWEHEISER_GOV_EFI_CRC);
+}
+
+/**
+ * @brief Pack a loweheiser_gov_efi 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 volt_batt [V] Generator Battery voltage.
+ * @param curr_batt [A] Generator Battery current.
+ * @param curr_gen [A] Current being produced by generator.
+ * @param curr_rot [A] Load current being consumed by the UAV (sum of curr_gen and curr_batt)
+ * @param fuel_level [l] Generator fuel remaining in litres.
+ * @param throttle [%] Throttle Output.
+ * @param runtime [s] Seconds this generator has run since it was rebooted.
+ * @param until_maintenance [s] Seconds until this generator requires maintenance. A negative value indicates maintenance is past due.
+ * @param rectifier_temp [degC] The Temperature of the rectifier.
+ * @param generator_temp [degC] The temperature of the mechanical motor, fuel cell core or generator.
+ * @param efi_batt [V] EFI Supply Voltage.
+ * @param efi_rpm [rpm] Motor RPM.
+ * @param efi_pw [ms] Injector pulse-width in milliseconds.
+ * @param efi_fuel_flow Fuel flow rate in litres/hour.
+ * @param efi_fuel_consumed [l] Fuel consumed.
+ * @param efi_baro [kPa] Atmospheric pressure.
+ * @param efi_mat [degC] Manifold Air Temperature.
+ * @param efi_clt [degC] Cylinder Head Temperature.
+ * @param efi_tps [%] Throttle Position.
+ * @param efi_exhaust_gas_temperature [degC] Exhaust gas temperature.
+ * @param efi_index EFI index.
+ * @param generator_status Generator status.
+ * @param efi_status EFI status.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_loweheiser_gov_efi_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ float volt_batt, float curr_batt, float curr_gen, float curr_rot, float fuel_level, float throttle, uint32_t runtime, int32_t until_maintenance, float rectifier_temp, float generator_temp, float efi_batt, float efi_rpm, float efi_pw, float efi_fuel_flow, float efi_fuel_consumed, float efi_baro, float efi_mat, float efi_clt, float efi_tps, float efi_exhaust_gas_temperature, uint8_t efi_index, uint16_t generator_status, uint16_t efi_status)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_LOWEHEISER_GOV_EFI_LEN];
+ _mav_put_float(buf, 0, volt_batt);
+ _mav_put_float(buf, 4, curr_batt);
+ _mav_put_float(buf, 8, curr_gen);
+ _mav_put_float(buf, 12, curr_rot);
+ _mav_put_float(buf, 16, fuel_level);
+ _mav_put_float(buf, 20, throttle);
+ _mav_put_uint32_t(buf, 24, runtime);
+ _mav_put_int32_t(buf, 28, until_maintenance);
+ _mav_put_float(buf, 32, rectifier_temp);
+ _mav_put_float(buf, 36, generator_temp);
+ _mav_put_float(buf, 40, efi_batt);
+ _mav_put_float(buf, 44, efi_rpm);
+ _mav_put_float(buf, 48, efi_pw);
+ _mav_put_float(buf, 52, efi_fuel_flow);
+ _mav_put_float(buf, 56, efi_fuel_consumed);
+ _mav_put_float(buf, 60, efi_baro);
+ _mav_put_float(buf, 64, efi_mat);
+ _mav_put_float(buf, 68, efi_clt);
+ _mav_put_float(buf, 72, efi_tps);
+ _mav_put_float(buf, 76, efi_exhaust_gas_temperature);
+ _mav_put_uint16_t(buf, 80, generator_status);
+ _mav_put_uint16_t(buf, 82, efi_status);
+ _mav_put_uint8_t(buf, 84, efi_index);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOWEHEISER_GOV_EFI_LEN);
+#else
+ mavlink_loweheiser_gov_efi_t packet;
+ packet.volt_batt = volt_batt;
+ packet.curr_batt = curr_batt;
+ packet.curr_gen = curr_gen;
+ packet.curr_rot = curr_rot;
+ packet.fuel_level = fuel_level;
+ packet.throttle = throttle;
+ packet.runtime = runtime;
+ packet.until_maintenance = until_maintenance;
+ packet.rectifier_temp = rectifier_temp;
+ packet.generator_temp = generator_temp;
+ packet.efi_batt = efi_batt;
+ packet.efi_rpm = efi_rpm;
+ packet.efi_pw = efi_pw;
+ packet.efi_fuel_flow = efi_fuel_flow;
+ packet.efi_fuel_consumed = efi_fuel_consumed;
+ packet.efi_baro = efi_baro;
+ packet.efi_mat = efi_mat;
+ packet.efi_clt = efi_clt;
+ packet.efi_tps = efi_tps;
+ packet.efi_exhaust_gas_temperature = efi_exhaust_gas_temperature;
+ packet.generator_status = generator_status;
+ packet.efi_status = efi_status;
+ packet.efi_index = efi_index;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOWEHEISER_GOV_EFI_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_LOWEHEISER_GOV_EFI;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_LOWEHEISER_GOV_EFI_MIN_LEN, MAVLINK_MSG_ID_LOWEHEISER_GOV_EFI_LEN, MAVLINK_MSG_ID_LOWEHEISER_GOV_EFI_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_LOWEHEISER_GOV_EFI_MIN_LEN, MAVLINK_MSG_ID_LOWEHEISER_GOV_EFI_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a loweheiser_gov_efi 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 volt_batt [V] Generator Battery voltage.
+ * @param curr_batt [A] Generator Battery current.
+ * @param curr_gen [A] Current being produced by generator.
+ * @param curr_rot [A] Load current being consumed by the UAV (sum of curr_gen and curr_batt)
+ * @param fuel_level [l] Generator fuel remaining in litres.
+ * @param throttle [%] Throttle Output.
+ * @param runtime [s] Seconds this generator has run since it was rebooted.
+ * @param until_maintenance [s] Seconds until this generator requires maintenance. A negative value indicates maintenance is past due.
+ * @param rectifier_temp [degC] The Temperature of the rectifier.
+ * @param generator_temp [degC] The temperature of the mechanical motor, fuel cell core or generator.
+ * @param efi_batt [V] EFI Supply Voltage.
+ * @param efi_rpm [rpm] Motor RPM.
+ * @param efi_pw [ms] Injector pulse-width in milliseconds.
+ * @param efi_fuel_flow Fuel flow rate in litres/hour.
+ * @param efi_fuel_consumed [l] Fuel consumed.
+ * @param efi_baro [kPa] Atmospheric pressure.
+ * @param efi_mat [degC] Manifold Air Temperature.
+ * @param efi_clt [degC] Cylinder Head Temperature.
+ * @param efi_tps [%] Throttle Position.
+ * @param efi_exhaust_gas_temperature [degC] Exhaust gas temperature.
+ * @param efi_index EFI index.
+ * @param generator_status Generator status.
+ * @param efi_status EFI status.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_loweheiser_gov_efi_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ float volt_batt,float curr_batt,float curr_gen,float curr_rot,float fuel_level,float throttle,uint32_t runtime,int32_t until_maintenance,float rectifier_temp,float generator_temp,float efi_batt,float efi_rpm,float efi_pw,float efi_fuel_flow,float efi_fuel_consumed,float efi_baro,float efi_mat,float efi_clt,float efi_tps,float efi_exhaust_gas_temperature,uint8_t efi_index,uint16_t generator_status,uint16_t efi_status)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_LOWEHEISER_GOV_EFI_LEN];
+ _mav_put_float(buf, 0, volt_batt);
+ _mav_put_float(buf, 4, curr_batt);
+ _mav_put_float(buf, 8, curr_gen);
+ _mav_put_float(buf, 12, curr_rot);
+ _mav_put_float(buf, 16, fuel_level);
+ _mav_put_float(buf, 20, throttle);
+ _mav_put_uint32_t(buf, 24, runtime);
+ _mav_put_int32_t(buf, 28, until_maintenance);
+ _mav_put_float(buf, 32, rectifier_temp);
+ _mav_put_float(buf, 36, generator_temp);
+ _mav_put_float(buf, 40, efi_batt);
+ _mav_put_float(buf, 44, efi_rpm);
+ _mav_put_float(buf, 48, efi_pw);
+ _mav_put_float(buf, 52, efi_fuel_flow);
+ _mav_put_float(buf, 56, efi_fuel_consumed);
+ _mav_put_float(buf, 60, efi_baro);
+ _mav_put_float(buf, 64, efi_mat);
+ _mav_put_float(buf, 68, efi_clt);
+ _mav_put_float(buf, 72, efi_tps);
+ _mav_put_float(buf, 76, efi_exhaust_gas_temperature);
+ _mav_put_uint16_t(buf, 80, generator_status);
+ _mav_put_uint16_t(buf, 82, efi_status);
+ _mav_put_uint8_t(buf, 84, efi_index);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOWEHEISER_GOV_EFI_LEN);
+#else
+ mavlink_loweheiser_gov_efi_t packet;
+ packet.volt_batt = volt_batt;
+ packet.curr_batt = curr_batt;
+ packet.curr_gen = curr_gen;
+ packet.curr_rot = curr_rot;
+ packet.fuel_level = fuel_level;
+ packet.throttle = throttle;
+ packet.runtime = runtime;
+ packet.until_maintenance = until_maintenance;
+ packet.rectifier_temp = rectifier_temp;
+ packet.generator_temp = generator_temp;
+ packet.efi_batt = efi_batt;
+ packet.efi_rpm = efi_rpm;
+ packet.efi_pw = efi_pw;
+ packet.efi_fuel_flow = efi_fuel_flow;
+ packet.efi_fuel_consumed = efi_fuel_consumed;
+ packet.efi_baro = efi_baro;
+ packet.efi_mat = efi_mat;
+ packet.efi_clt = efi_clt;
+ packet.efi_tps = efi_tps;
+ packet.efi_exhaust_gas_temperature = efi_exhaust_gas_temperature;
+ packet.generator_status = generator_status;
+ packet.efi_status = efi_status;
+ packet.efi_index = efi_index;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOWEHEISER_GOV_EFI_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_LOWEHEISER_GOV_EFI;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOWEHEISER_GOV_EFI_MIN_LEN, MAVLINK_MSG_ID_LOWEHEISER_GOV_EFI_LEN, MAVLINK_MSG_ID_LOWEHEISER_GOV_EFI_CRC);
+}
+
+/**
+ * @brief Encode a loweheiser_gov_efi 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 loweheiser_gov_efi C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_loweheiser_gov_efi_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_loweheiser_gov_efi_t* loweheiser_gov_efi)
+{
+ return mavlink_msg_loweheiser_gov_efi_pack(system_id, component_id, msg, loweheiser_gov_efi->volt_batt, loweheiser_gov_efi->curr_batt, loweheiser_gov_efi->curr_gen, loweheiser_gov_efi->curr_rot, loweheiser_gov_efi->fuel_level, loweheiser_gov_efi->throttle, loweheiser_gov_efi->runtime, loweheiser_gov_efi->until_maintenance, loweheiser_gov_efi->rectifier_temp, loweheiser_gov_efi->generator_temp, loweheiser_gov_efi->efi_batt, loweheiser_gov_efi->efi_rpm, loweheiser_gov_efi->efi_pw, loweheiser_gov_efi->efi_fuel_flow, loweheiser_gov_efi->efi_fuel_consumed, loweheiser_gov_efi->efi_baro, loweheiser_gov_efi->efi_mat, loweheiser_gov_efi->efi_clt, loweheiser_gov_efi->efi_tps, loweheiser_gov_efi->efi_exhaust_gas_temperature, loweheiser_gov_efi->efi_index, loweheiser_gov_efi->generator_status, loweheiser_gov_efi->efi_status);
+}
+
+/**
+ * @brief Encode a loweheiser_gov_efi 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 loweheiser_gov_efi C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_loweheiser_gov_efi_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_loweheiser_gov_efi_t* loweheiser_gov_efi)
+{
+ return mavlink_msg_loweheiser_gov_efi_pack_chan(system_id, component_id, chan, msg, loweheiser_gov_efi->volt_batt, loweheiser_gov_efi->curr_batt, loweheiser_gov_efi->curr_gen, loweheiser_gov_efi->curr_rot, loweheiser_gov_efi->fuel_level, loweheiser_gov_efi->throttle, loweheiser_gov_efi->runtime, loweheiser_gov_efi->until_maintenance, loweheiser_gov_efi->rectifier_temp, loweheiser_gov_efi->generator_temp, loweheiser_gov_efi->efi_batt, loweheiser_gov_efi->efi_rpm, loweheiser_gov_efi->efi_pw, loweheiser_gov_efi->efi_fuel_flow, loweheiser_gov_efi->efi_fuel_consumed, loweheiser_gov_efi->efi_baro, loweheiser_gov_efi->efi_mat, loweheiser_gov_efi->efi_clt, loweheiser_gov_efi->efi_tps, loweheiser_gov_efi->efi_exhaust_gas_temperature, loweheiser_gov_efi->efi_index, loweheiser_gov_efi->generator_status, loweheiser_gov_efi->efi_status);
+}
+
+/**
+ * @brief Encode a loweheiser_gov_efi 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 loweheiser_gov_efi C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_loweheiser_gov_efi_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_loweheiser_gov_efi_t* loweheiser_gov_efi)
+{
+ return mavlink_msg_loweheiser_gov_efi_pack_status(system_id, component_id, _status, msg, loweheiser_gov_efi->volt_batt, loweheiser_gov_efi->curr_batt, loweheiser_gov_efi->curr_gen, loweheiser_gov_efi->curr_rot, loweheiser_gov_efi->fuel_level, loweheiser_gov_efi->throttle, loweheiser_gov_efi->runtime, loweheiser_gov_efi->until_maintenance, loweheiser_gov_efi->rectifier_temp, loweheiser_gov_efi->generator_temp, loweheiser_gov_efi->efi_batt, loweheiser_gov_efi->efi_rpm, loweheiser_gov_efi->efi_pw, loweheiser_gov_efi->efi_fuel_flow, loweheiser_gov_efi->efi_fuel_consumed, loweheiser_gov_efi->efi_baro, loweheiser_gov_efi->efi_mat, loweheiser_gov_efi->efi_clt, loweheiser_gov_efi->efi_tps, loweheiser_gov_efi->efi_exhaust_gas_temperature, loweheiser_gov_efi->efi_index, loweheiser_gov_efi->generator_status, loweheiser_gov_efi->efi_status);
+}
+
+/**
+ * @brief Send a loweheiser_gov_efi message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param volt_batt [V] Generator Battery voltage.
+ * @param curr_batt [A] Generator Battery current.
+ * @param curr_gen [A] Current being produced by generator.
+ * @param curr_rot [A] Load current being consumed by the UAV (sum of curr_gen and curr_batt)
+ * @param fuel_level [l] Generator fuel remaining in litres.
+ * @param throttle [%] Throttle Output.
+ * @param runtime [s] Seconds this generator has run since it was rebooted.
+ * @param until_maintenance [s] Seconds until this generator requires maintenance. A negative value indicates maintenance is past due.
+ * @param rectifier_temp [degC] The Temperature of the rectifier.
+ * @param generator_temp [degC] The temperature of the mechanical motor, fuel cell core or generator.
+ * @param efi_batt [V] EFI Supply Voltage.
+ * @param efi_rpm [rpm] Motor RPM.
+ * @param efi_pw [ms] Injector pulse-width in milliseconds.
+ * @param efi_fuel_flow Fuel flow rate in litres/hour.
+ * @param efi_fuel_consumed [l] Fuel consumed.
+ * @param efi_baro [kPa] Atmospheric pressure.
+ * @param efi_mat [degC] Manifold Air Temperature.
+ * @param efi_clt [degC] Cylinder Head Temperature.
+ * @param efi_tps [%] Throttle Position.
+ * @param efi_exhaust_gas_temperature [degC] Exhaust gas temperature.
+ * @param efi_index EFI index.
+ * @param generator_status Generator status.
+ * @param efi_status EFI status.
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_loweheiser_gov_efi_send(mavlink_channel_t chan, float volt_batt, float curr_batt, float curr_gen, float curr_rot, float fuel_level, float throttle, uint32_t runtime, int32_t until_maintenance, float rectifier_temp, float generator_temp, float efi_batt, float efi_rpm, float efi_pw, float efi_fuel_flow, float efi_fuel_consumed, float efi_baro, float efi_mat, float efi_clt, float efi_tps, float efi_exhaust_gas_temperature, uint8_t efi_index, uint16_t generator_status, uint16_t efi_status)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_LOWEHEISER_GOV_EFI_LEN];
+ _mav_put_float(buf, 0, volt_batt);
+ _mav_put_float(buf, 4, curr_batt);
+ _mav_put_float(buf, 8, curr_gen);
+ _mav_put_float(buf, 12, curr_rot);
+ _mav_put_float(buf, 16, fuel_level);
+ _mav_put_float(buf, 20, throttle);
+ _mav_put_uint32_t(buf, 24, runtime);
+ _mav_put_int32_t(buf, 28, until_maintenance);
+ _mav_put_float(buf, 32, rectifier_temp);
+ _mav_put_float(buf, 36, generator_temp);
+ _mav_put_float(buf, 40, efi_batt);
+ _mav_put_float(buf, 44, efi_rpm);
+ _mav_put_float(buf, 48, efi_pw);
+ _mav_put_float(buf, 52, efi_fuel_flow);
+ _mav_put_float(buf, 56, efi_fuel_consumed);
+ _mav_put_float(buf, 60, efi_baro);
+ _mav_put_float(buf, 64, efi_mat);
+ _mav_put_float(buf, 68, efi_clt);
+ _mav_put_float(buf, 72, efi_tps);
+ _mav_put_float(buf, 76, efi_exhaust_gas_temperature);
+ _mav_put_uint16_t(buf, 80, generator_status);
+ _mav_put_uint16_t(buf, 82, efi_status);
+ _mav_put_uint8_t(buf, 84, efi_index);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOWEHEISER_GOV_EFI, buf, MAVLINK_MSG_ID_LOWEHEISER_GOV_EFI_MIN_LEN, MAVLINK_MSG_ID_LOWEHEISER_GOV_EFI_LEN, MAVLINK_MSG_ID_LOWEHEISER_GOV_EFI_CRC);
+#else
+ mavlink_loweheiser_gov_efi_t packet;
+ packet.volt_batt = volt_batt;
+ packet.curr_batt = curr_batt;
+ packet.curr_gen = curr_gen;
+ packet.curr_rot = curr_rot;
+ packet.fuel_level = fuel_level;
+ packet.throttle = throttle;
+ packet.runtime = runtime;
+ packet.until_maintenance = until_maintenance;
+ packet.rectifier_temp = rectifier_temp;
+ packet.generator_temp = generator_temp;
+ packet.efi_batt = efi_batt;
+ packet.efi_rpm = efi_rpm;
+ packet.efi_pw = efi_pw;
+ packet.efi_fuel_flow = efi_fuel_flow;
+ packet.efi_fuel_consumed = efi_fuel_consumed;
+ packet.efi_baro = efi_baro;
+ packet.efi_mat = efi_mat;
+ packet.efi_clt = efi_clt;
+ packet.efi_tps = efi_tps;
+ packet.efi_exhaust_gas_temperature = efi_exhaust_gas_temperature;
+ packet.generator_status = generator_status;
+ packet.efi_status = efi_status;
+ packet.efi_index = efi_index;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOWEHEISER_GOV_EFI, (const char *)&packet, MAVLINK_MSG_ID_LOWEHEISER_GOV_EFI_MIN_LEN, MAVLINK_MSG_ID_LOWEHEISER_GOV_EFI_LEN, MAVLINK_MSG_ID_LOWEHEISER_GOV_EFI_CRC);
+#endif
+}
+
+/**
+ * @brief Send a loweheiser_gov_efi message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_loweheiser_gov_efi_send_struct(mavlink_channel_t chan, const mavlink_loweheiser_gov_efi_t* loweheiser_gov_efi)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_loweheiser_gov_efi_send(chan, loweheiser_gov_efi->volt_batt, loweheiser_gov_efi->curr_batt, loweheiser_gov_efi->curr_gen, loweheiser_gov_efi->curr_rot, loweheiser_gov_efi->fuel_level, loweheiser_gov_efi->throttle, loweheiser_gov_efi->runtime, loweheiser_gov_efi->until_maintenance, loweheiser_gov_efi->rectifier_temp, loweheiser_gov_efi->generator_temp, loweheiser_gov_efi->efi_batt, loweheiser_gov_efi->efi_rpm, loweheiser_gov_efi->efi_pw, loweheiser_gov_efi->efi_fuel_flow, loweheiser_gov_efi->efi_fuel_consumed, loweheiser_gov_efi->efi_baro, loweheiser_gov_efi->efi_mat, loweheiser_gov_efi->efi_clt, loweheiser_gov_efi->efi_tps, loweheiser_gov_efi->efi_exhaust_gas_temperature, loweheiser_gov_efi->efi_index, loweheiser_gov_efi->generator_status, loweheiser_gov_efi->efi_status);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOWEHEISER_GOV_EFI, (const char *)loweheiser_gov_efi, MAVLINK_MSG_ID_LOWEHEISER_GOV_EFI_MIN_LEN, MAVLINK_MSG_ID_LOWEHEISER_GOV_EFI_LEN, MAVLINK_MSG_ID_LOWEHEISER_GOV_EFI_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_LOWEHEISER_GOV_EFI_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_loweheiser_gov_efi_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, float volt_batt, float curr_batt, float curr_gen, float curr_rot, float fuel_level, float throttle, uint32_t runtime, int32_t until_maintenance, float rectifier_temp, float generator_temp, float efi_batt, float efi_rpm, float efi_pw, float efi_fuel_flow, float efi_fuel_consumed, float efi_baro, float efi_mat, float efi_clt, float efi_tps, float efi_exhaust_gas_temperature, uint8_t efi_index, uint16_t generator_status, uint16_t efi_status)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_float(buf, 0, volt_batt);
+ _mav_put_float(buf, 4, curr_batt);
+ _mav_put_float(buf, 8, curr_gen);
+ _mav_put_float(buf, 12, curr_rot);
+ _mav_put_float(buf, 16, fuel_level);
+ _mav_put_float(buf, 20, throttle);
+ _mav_put_uint32_t(buf, 24, runtime);
+ _mav_put_int32_t(buf, 28, until_maintenance);
+ _mav_put_float(buf, 32, rectifier_temp);
+ _mav_put_float(buf, 36, generator_temp);
+ _mav_put_float(buf, 40, efi_batt);
+ _mav_put_float(buf, 44, efi_rpm);
+ _mav_put_float(buf, 48, efi_pw);
+ _mav_put_float(buf, 52, efi_fuel_flow);
+ _mav_put_float(buf, 56, efi_fuel_consumed);
+ _mav_put_float(buf, 60, efi_baro);
+ _mav_put_float(buf, 64, efi_mat);
+ _mav_put_float(buf, 68, efi_clt);
+ _mav_put_float(buf, 72, efi_tps);
+ _mav_put_float(buf, 76, efi_exhaust_gas_temperature);
+ _mav_put_uint16_t(buf, 80, generator_status);
+ _mav_put_uint16_t(buf, 82, efi_status);
+ _mav_put_uint8_t(buf, 84, efi_index);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOWEHEISER_GOV_EFI, buf, MAVLINK_MSG_ID_LOWEHEISER_GOV_EFI_MIN_LEN, MAVLINK_MSG_ID_LOWEHEISER_GOV_EFI_LEN, MAVLINK_MSG_ID_LOWEHEISER_GOV_EFI_CRC);
+#else
+ mavlink_loweheiser_gov_efi_t *packet = (mavlink_loweheiser_gov_efi_t *)msgbuf;
+ packet->volt_batt = volt_batt;
+ packet->curr_batt = curr_batt;
+ packet->curr_gen = curr_gen;
+ packet->curr_rot = curr_rot;
+ packet->fuel_level = fuel_level;
+ packet->throttle = throttle;
+ packet->runtime = runtime;
+ packet->until_maintenance = until_maintenance;
+ packet->rectifier_temp = rectifier_temp;
+ packet->generator_temp = generator_temp;
+ packet->efi_batt = efi_batt;
+ packet->efi_rpm = efi_rpm;
+ packet->efi_pw = efi_pw;
+ packet->efi_fuel_flow = efi_fuel_flow;
+ packet->efi_fuel_consumed = efi_fuel_consumed;
+ packet->efi_baro = efi_baro;
+ packet->efi_mat = efi_mat;
+ packet->efi_clt = efi_clt;
+ packet->efi_tps = efi_tps;
+ packet->efi_exhaust_gas_temperature = efi_exhaust_gas_temperature;
+ packet->generator_status = generator_status;
+ packet->efi_status = efi_status;
+ packet->efi_index = efi_index;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOWEHEISER_GOV_EFI, (const char *)packet, MAVLINK_MSG_ID_LOWEHEISER_GOV_EFI_MIN_LEN, MAVLINK_MSG_ID_LOWEHEISER_GOV_EFI_LEN, MAVLINK_MSG_ID_LOWEHEISER_GOV_EFI_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE LOWEHEISER_GOV_EFI UNPACKING
+
+
+/**
+ * @brief Get field volt_batt from loweheiser_gov_efi message
+ *
+ * @return [V] Generator Battery voltage.
+ */
+static inline float mavlink_msg_loweheiser_gov_efi_get_volt_batt(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 0);
+}
+
+/**
+ * @brief Get field curr_batt from loweheiser_gov_efi message
+ *
+ * @return [A] Generator Battery current.
+ */
+static inline float mavlink_msg_loweheiser_gov_efi_get_curr_batt(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 4);
+}
+
+/**
+ * @brief Get field curr_gen from loweheiser_gov_efi message
+ *
+ * @return [A] Current being produced by generator.
+ */
+static inline float mavlink_msg_loweheiser_gov_efi_get_curr_gen(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 8);
+}
+
+/**
+ * @brief Get field curr_rot from loweheiser_gov_efi message
+ *
+ * @return [A] Load current being consumed by the UAV (sum of curr_gen and curr_batt)
+ */
+static inline float mavlink_msg_loweheiser_gov_efi_get_curr_rot(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 12);
+}
+
+/**
+ * @brief Get field fuel_level from loweheiser_gov_efi message
+ *
+ * @return [l] Generator fuel remaining in litres.
+ */
+static inline float mavlink_msg_loweheiser_gov_efi_get_fuel_level(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 16);
+}
+
+/**
+ * @brief Get field throttle from loweheiser_gov_efi message
+ *
+ * @return [%] Throttle Output.
+ */
+static inline float mavlink_msg_loweheiser_gov_efi_get_throttle(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 20);
+}
+
+/**
+ * @brief Get field runtime from loweheiser_gov_efi message
+ *
+ * @return [s] Seconds this generator has run since it was rebooted.
+ */
+static inline uint32_t mavlink_msg_loweheiser_gov_efi_get_runtime(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint32_t(msg, 24);
+}
+
+/**
+ * @brief Get field until_maintenance from loweheiser_gov_efi message
+ *
+ * @return [s] Seconds until this generator requires maintenance. A negative value indicates maintenance is past due.
+ */
+static inline int32_t mavlink_msg_loweheiser_gov_efi_get_until_maintenance(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_int32_t(msg, 28);
+}
+
+/**
+ * @brief Get field rectifier_temp from loweheiser_gov_efi message
+ *
+ * @return [degC] The Temperature of the rectifier.
+ */
+static inline float mavlink_msg_loweheiser_gov_efi_get_rectifier_temp(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 32);
+}
+
+/**
+ * @brief Get field generator_temp from loweheiser_gov_efi message
+ *
+ * @return [degC] The temperature of the mechanical motor, fuel cell core or generator.
+ */
+static inline float mavlink_msg_loweheiser_gov_efi_get_generator_temp(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 36);
+}
+
+/**
+ * @brief Get field efi_batt from loweheiser_gov_efi message
+ *
+ * @return [V] EFI Supply Voltage.
+ */
+static inline float mavlink_msg_loweheiser_gov_efi_get_efi_batt(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 40);
+}
+
+/**
+ * @brief Get field efi_rpm from loweheiser_gov_efi message
+ *
+ * @return [rpm] Motor RPM.
+ */
+static inline float mavlink_msg_loweheiser_gov_efi_get_efi_rpm(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 44);
+}
+
+/**
+ * @brief Get field efi_pw from loweheiser_gov_efi message
+ *
+ * @return [ms] Injector pulse-width in milliseconds.
+ */
+static inline float mavlink_msg_loweheiser_gov_efi_get_efi_pw(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 48);
+}
+
+/**
+ * @brief Get field efi_fuel_flow from loweheiser_gov_efi message
+ *
+ * @return Fuel flow rate in litres/hour.
+ */
+static inline float mavlink_msg_loweheiser_gov_efi_get_efi_fuel_flow(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 52);
+}
+
+/**
+ * @brief Get field efi_fuel_consumed from loweheiser_gov_efi message
+ *
+ * @return [l] Fuel consumed.
+ */
+static inline float mavlink_msg_loweheiser_gov_efi_get_efi_fuel_consumed(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 56);
+}
+
+/**
+ * @brief Get field efi_baro from loweheiser_gov_efi message
+ *
+ * @return [kPa] Atmospheric pressure.
+ */
+static inline float mavlink_msg_loweheiser_gov_efi_get_efi_baro(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 60);
+}
+
+/**
+ * @brief Get field efi_mat from loweheiser_gov_efi message
+ *
+ * @return [degC] Manifold Air Temperature.
+ */
+static inline float mavlink_msg_loweheiser_gov_efi_get_efi_mat(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 64);
+}
+
+/**
+ * @brief Get field efi_clt from loweheiser_gov_efi message
+ *
+ * @return [degC] Cylinder Head Temperature.
+ */
+static inline float mavlink_msg_loweheiser_gov_efi_get_efi_clt(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 68);
+}
+
+/**
+ * @brief Get field efi_tps from loweheiser_gov_efi message
+ *
+ * @return [%] Throttle Position.
+ */
+static inline float mavlink_msg_loweheiser_gov_efi_get_efi_tps(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 72);
+}
+
+/**
+ * @brief Get field efi_exhaust_gas_temperature from loweheiser_gov_efi message
+ *
+ * @return [degC] Exhaust gas temperature.
+ */
+static inline float mavlink_msg_loweheiser_gov_efi_get_efi_exhaust_gas_temperature(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 76);
+}
+
+/**
+ * @brief Get field efi_index from loweheiser_gov_efi message
+ *
+ * @return EFI index.
+ */
+static inline uint8_t mavlink_msg_loweheiser_gov_efi_get_efi_index(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 84);
+}
+
+/**
+ * @brief Get field generator_status from loweheiser_gov_efi message
+ *
+ * @return Generator status.
+ */
+static inline uint16_t mavlink_msg_loweheiser_gov_efi_get_generator_status(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 80);
+}
+
+/**
+ * @brief Get field efi_status from loweheiser_gov_efi message
+ *
+ * @return EFI status.
+ */
+static inline uint16_t mavlink_msg_loweheiser_gov_efi_get_efi_status(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 82);
+}
+
+/**
+ * @brief Decode a loweheiser_gov_efi message into a struct
+ *
+ * @param msg The message to decode
+ * @param loweheiser_gov_efi C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_loweheiser_gov_efi_decode(const mavlink_message_t* msg, mavlink_loweheiser_gov_efi_t* loweheiser_gov_efi)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ loweheiser_gov_efi->volt_batt = mavlink_msg_loweheiser_gov_efi_get_volt_batt(msg);
+ loweheiser_gov_efi->curr_batt = mavlink_msg_loweheiser_gov_efi_get_curr_batt(msg);
+ loweheiser_gov_efi->curr_gen = mavlink_msg_loweheiser_gov_efi_get_curr_gen(msg);
+ loweheiser_gov_efi->curr_rot = mavlink_msg_loweheiser_gov_efi_get_curr_rot(msg);
+ loweheiser_gov_efi->fuel_level = mavlink_msg_loweheiser_gov_efi_get_fuel_level(msg);
+ loweheiser_gov_efi->throttle = mavlink_msg_loweheiser_gov_efi_get_throttle(msg);
+ loweheiser_gov_efi->runtime = mavlink_msg_loweheiser_gov_efi_get_runtime(msg);
+ loweheiser_gov_efi->until_maintenance = mavlink_msg_loweheiser_gov_efi_get_until_maintenance(msg);
+ loweheiser_gov_efi->rectifier_temp = mavlink_msg_loweheiser_gov_efi_get_rectifier_temp(msg);
+ loweheiser_gov_efi->generator_temp = mavlink_msg_loweheiser_gov_efi_get_generator_temp(msg);
+ loweheiser_gov_efi->efi_batt = mavlink_msg_loweheiser_gov_efi_get_efi_batt(msg);
+ loweheiser_gov_efi->efi_rpm = mavlink_msg_loweheiser_gov_efi_get_efi_rpm(msg);
+ loweheiser_gov_efi->efi_pw = mavlink_msg_loweheiser_gov_efi_get_efi_pw(msg);
+ loweheiser_gov_efi->efi_fuel_flow = mavlink_msg_loweheiser_gov_efi_get_efi_fuel_flow(msg);
+ loweheiser_gov_efi->efi_fuel_consumed = mavlink_msg_loweheiser_gov_efi_get_efi_fuel_consumed(msg);
+ loweheiser_gov_efi->efi_baro = mavlink_msg_loweheiser_gov_efi_get_efi_baro(msg);
+ loweheiser_gov_efi->efi_mat = mavlink_msg_loweheiser_gov_efi_get_efi_mat(msg);
+ loweheiser_gov_efi->efi_clt = mavlink_msg_loweheiser_gov_efi_get_efi_clt(msg);
+ loweheiser_gov_efi->efi_tps = mavlink_msg_loweheiser_gov_efi_get_efi_tps(msg);
+ loweheiser_gov_efi->efi_exhaust_gas_temperature = mavlink_msg_loweheiser_gov_efi_get_efi_exhaust_gas_temperature(msg);
+ loweheiser_gov_efi->generator_status = mavlink_msg_loweheiser_gov_efi_get_generator_status(msg);
+ loweheiser_gov_efi->efi_status = mavlink_msg_loweheiser_gov_efi_get_efi_status(msg);
+ loweheiser_gov_efi->efi_index = mavlink_msg_loweheiser_gov_efi_get_efi_index(msg);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_LOWEHEISER_GOV_EFI_LEN? msg->len : MAVLINK_MSG_ID_LOWEHEISER_GOV_EFI_LEN;
+ memset(loweheiser_gov_efi, 0, MAVLINK_MSG_ID_LOWEHEISER_GOV_EFI_LEN);
+ memcpy(loweheiser_gov_efi, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/loweheiser/testsuite.h b/lib/main/MAVLink/loweheiser/testsuite.h
new file mode 100644
index 00000000000..94f4f49d39b
--- /dev/null
+++ b/lib/main/MAVLink/loweheiser/testsuite.h
@@ -0,0 +1,117 @@
+/** @file
+ * @brief MAVLink comm protocol testsuite generated from loweheiser.xml
+ * @see https://mavlink.io/en/
+ */
+#pragma once
+#ifndef LOWEHEISER_TESTSUITE_H
+#define LOWEHEISER_TESTSUITE_H
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+#ifndef MAVLINK_TEST_ALL
+#define MAVLINK_TEST_ALL
+static void mavlink_test_minimal(uint8_t, uint8_t, mavlink_message_t *last_msg);
+static void mavlink_test_loweheiser(uint8_t, uint8_t, mavlink_message_t *last_msg);
+
+static void mavlink_test_all(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
+{
+ mavlink_test_minimal(system_id, component_id, last_msg);
+ mavlink_test_loweheiser(system_id, component_id, last_msg);
+}
+#endif
+
+#include "../minimal/testsuite.h"
+
+
+static void mavlink_test_loweheiser_gov_efi(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_LOWEHEISER_GOV_EFI >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_loweheiser_gov_efi_t packet_in = {
+ 17.0,45.0,73.0,101.0,129.0,157.0,963498712,963498920,241.0,269.0,297.0,325.0,353.0,381.0,409.0,437.0,465.0,493.0,521.0,549.0,21395,21499,1
+ };
+ mavlink_loweheiser_gov_efi_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.volt_batt = packet_in.volt_batt;
+ packet1.curr_batt = packet_in.curr_batt;
+ packet1.curr_gen = packet_in.curr_gen;
+ packet1.curr_rot = packet_in.curr_rot;
+ packet1.fuel_level = packet_in.fuel_level;
+ packet1.throttle = packet_in.throttle;
+ packet1.runtime = packet_in.runtime;
+ packet1.until_maintenance = packet_in.until_maintenance;
+ packet1.rectifier_temp = packet_in.rectifier_temp;
+ packet1.generator_temp = packet_in.generator_temp;
+ packet1.efi_batt = packet_in.efi_batt;
+ packet1.efi_rpm = packet_in.efi_rpm;
+ packet1.efi_pw = packet_in.efi_pw;
+ packet1.efi_fuel_flow = packet_in.efi_fuel_flow;
+ packet1.efi_fuel_consumed = packet_in.efi_fuel_consumed;
+ packet1.efi_baro = packet_in.efi_baro;
+ packet1.efi_mat = packet_in.efi_mat;
+ packet1.efi_clt = packet_in.efi_clt;
+ packet1.efi_tps = packet_in.efi_tps;
+ packet1.efi_exhaust_gas_temperature = packet_in.efi_exhaust_gas_temperature;
+ packet1.generator_status = packet_in.generator_status;
+ packet1.efi_status = packet_in.efi_status;
+ packet1.efi_index = packet_in.efi_index;
+
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_LOWEHEISER_GOV_EFI_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_LOWEHEISER_GOV_EFI_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_loweheiser_gov_efi_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_loweheiser_gov_efi_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_loweheiser_gov_efi_pack(system_id, component_id, &msg , packet1.volt_batt , packet1.curr_batt , packet1.curr_gen , packet1.curr_rot , packet1.fuel_level , packet1.throttle , packet1.runtime , packet1.until_maintenance , packet1.rectifier_temp , packet1.generator_temp , packet1.efi_batt , packet1.efi_rpm , packet1.efi_pw , packet1.efi_fuel_flow , packet1.efi_fuel_consumed , packet1.efi_baro , packet1.efi_mat , packet1.efi_clt , packet1.efi_tps , packet1.efi_exhaust_gas_temperature , packet1.efi_index , packet1.generator_status , packet1.efi_status );
+ mavlink_msg_loweheiser_gov_efi_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_loweheiser_gov_efi_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.volt_batt , packet1.curr_batt , packet1.curr_gen , packet1.curr_rot , packet1.fuel_level , packet1.throttle , packet1.runtime , packet1.until_maintenance , packet1.rectifier_temp , packet1.generator_temp , packet1.efi_batt , packet1.efi_rpm , packet1.efi_pw , packet1.efi_fuel_flow , packet1.efi_fuel_consumed , packet1.efi_baro , packet1.efi_mat , packet1.efi_clt , packet1.efi_tps , packet1.efi_exhaust_gas_temperature , packet1.efi_index , packet1.generator_status , packet1.efi_status );
+ mavlink_msg_loweheiser_gov_efi_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_PROTOCOL_VERSION >= 256) {
- return;
- }
-#endif
- mavlink_message_t msg;
- uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
- uint16_t i;
- mavlink_protocol_version_t packet_in = {
- 17235,17339,17443,{ 151, 152, 153, 154, 155, 156, 157, 158 },{ 175, 176, 177, 178, 179, 180, 181, 182 }
- };
- mavlink_protocol_version_t packet1, packet2;
- memset(&packet1, 0, sizeof(packet1));
- packet1.version = packet_in.version;
- packet1.min_version = packet_in.min_version;
- packet1.max_version = packet_in.max_version;
-
- mav_array_memcpy(packet1.spec_version_hash, packet_in.spec_version_hash, sizeof(uint8_t)*8);
- mav_array_memcpy(packet1.library_version_hash, packet_in.library_version_hash, sizeof(uint8_t)*8);
-
-#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
- if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
- // cope with extensions
- memset(MAVLINK_MSG_ID_PROTOCOL_VERSION_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_PROTOCOL_VERSION_MIN_LEN);
- }
-#endif
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_protocol_version_encode(system_id, component_id, &msg, &packet1);
- mavlink_msg_protocol_version_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_protocol_version_pack(system_id, component_id, &msg , packet1.version , packet1.min_version , packet1.max_version , packet1.spec_version_hash , packet1.library_version_hash );
- mavlink_msg_protocol_version_decode(&msg, &packet2);
- MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
-
- memset(&packet2, 0, sizeof(packet2));
- mavlink_msg_protocol_version_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.version , packet1.min_version , packet1.max_version , packet1.spec_version_hash , packet1.library_version_hash );
- mavlink_msg_protocol_version_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_GLOBAL_POSITION_INT >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_global_position_int_t packet_in = {
+ 963497464,963497672,963497880,963498088,963498296,18275,18379,18483,18587
+ };
+ mavlink_global_position_int_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.time_boot_ms = packet_in.time_boot_ms;
+ packet1.lat = packet_in.lat;
+ packet1.lon = packet_in.lon;
+ packet1.alt = packet_in.alt;
+ packet1.relative_alt = packet_in.relative_alt;
+ packet1.vx = packet_in.vx;
+ packet1.vy = packet_in.vy;
+ packet1.vz = packet_in.vz;
+ packet1.hdg = packet_in.hdg;
+
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_GLOBAL_POSITION_INT_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_GLOBAL_POSITION_INT_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_global_position_int_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_global_position_int_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_global_position_int_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.lat , packet1.lon , packet1.alt , packet1.relative_alt , packet1.vx , packet1.vy , packet1.vz , packet1.hdg );
+ mavlink_msg_global_position_int_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_global_position_int_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.lat , packet1.lon , packet1.alt , packet1.relative_alt , packet1.vx , packet1.vy , packet1.vz , packet1.hdg );
+ mavlink_msg_global_position_int_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; imsgid = MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_EXT;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_EXT_MIN_LEN, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_EXT_LEN, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_EXT_CRC);
+}
+
+/**
+ * @brief Pack a autopilot_state_for_gimbal_device_ext 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 target_system System ID.
+ * @param target_component Component ID.
+ * @param time_boot_us [us] Timestamp (time since system boot).
+ * @param wind_x [m/s] Wind X speed in NED (North,Est, Down). NAN if unknown.
+ * @param wind_y [m/s] Wind Y speed in NED (North, East, Down). NAN if unknown.
+ * @param wind_correction_angle [rad] Correction angle due to wind. NaN if unknown.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_autopilot_state_for_gimbal_device_ext_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ uint8_t target_system, uint8_t target_component, uint64_t time_boot_us, float wind_x, float wind_y, float wind_correction_angle)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_EXT_LEN];
+ _mav_put_uint64_t(buf, 0, time_boot_us);
+ _mav_put_float(buf, 8, wind_x);
+ _mav_put_float(buf, 12, wind_y);
+ _mav_put_float(buf, 16, wind_correction_angle);
+ _mav_put_uint8_t(buf, 20, target_system);
+ _mav_put_uint8_t(buf, 21, target_component);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_EXT_LEN);
+#else
+ mavlink_autopilot_state_for_gimbal_device_ext_t packet;
+ packet.time_boot_us = time_boot_us;
+ packet.wind_x = wind_x;
+ packet.wind_y = wind_y;
+ packet.wind_correction_angle = wind_correction_angle;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_EXT_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_EXT;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_EXT_MIN_LEN, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_EXT_LEN, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_EXT_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_EXT_MIN_LEN, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_EXT_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a autopilot_state_for_gimbal_device_ext 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 target_system System ID.
+ * @param target_component Component ID.
+ * @param time_boot_us [us] Timestamp (time since system boot).
+ * @param wind_x [m/s] Wind X speed in NED (North,Est, Down). NAN if unknown.
+ * @param wind_y [m/s] Wind Y speed in NED (North, East, Down). NAN if unknown.
+ * @param wind_correction_angle [rad] Correction angle due to wind. NaN if unknown.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_autopilot_state_for_gimbal_device_ext_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint8_t target_system,uint8_t target_component,uint64_t time_boot_us,float wind_x,float wind_y,float wind_correction_angle)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_EXT_LEN];
+ _mav_put_uint64_t(buf, 0, time_boot_us);
+ _mav_put_float(buf, 8, wind_x);
+ _mav_put_float(buf, 12, wind_y);
+ _mav_put_float(buf, 16, wind_correction_angle);
+ _mav_put_uint8_t(buf, 20, target_system);
+ _mav_put_uint8_t(buf, 21, target_component);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_EXT_LEN);
+#else
+ mavlink_autopilot_state_for_gimbal_device_ext_t packet;
+ packet.time_boot_us = time_boot_us;
+ packet.wind_x = wind_x;
+ packet.wind_y = wind_y;
+ packet.wind_correction_angle = wind_correction_angle;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_EXT_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_EXT;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_EXT_MIN_LEN, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_EXT_LEN, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_EXT_CRC);
+}
+
+/**
+ * @brief Encode a autopilot_state_for_gimbal_device_ext 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 autopilot_state_for_gimbal_device_ext C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_autopilot_state_for_gimbal_device_ext_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_autopilot_state_for_gimbal_device_ext_t* autopilot_state_for_gimbal_device_ext)
+{
+ return mavlink_msg_autopilot_state_for_gimbal_device_ext_pack(system_id, component_id, msg, autopilot_state_for_gimbal_device_ext->target_system, autopilot_state_for_gimbal_device_ext->target_component, autopilot_state_for_gimbal_device_ext->time_boot_us, autopilot_state_for_gimbal_device_ext->wind_x, autopilot_state_for_gimbal_device_ext->wind_y, autopilot_state_for_gimbal_device_ext->wind_correction_angle);
+}
+
+/**
+ * @brief Encode a autopilot_state_for_gimbal_device_ext 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 autopilot_state_for_gimbal_device_ext C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_autopilot_state_for_gimbal_device_ext_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_autopilot_state_for_gimbal_device_ext_t* autopilot_state_for_gimbal_device_ext)
+{
+ return mavlink_msg_autopilot_state_for_gimbal_device_ext_pack_chan(system_id, component_id, chan, msg, autopilot_state_for_gimbal_device_ext->target_system, autopilot_state_for_gimbal_device_ext->target_component, autopilot_state_for_gimbal_device_ext->time_boot_us, autopilot_state_for_gimbal_device_ext->wind_x, autopilot_state_for_gimbal_device_ext->wind_y, autopilot_state_for_gimbal_device_ext->wind_correction_angle);
+}
+
+/**
+ * @brief Encode a autopilot_state_for_gimbal_device_ext 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 autopilot_state_for_gimbal_device_ext C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_autopilot_state_for_gimbal_device_ext_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_autopilot_state_for_gimbal_device_ext_t* autopilot_state_for_gimbal_device_ext)
+{
+ return mavlink_msg_autopilot_state_for_gimbal_device_ext_pack_status(system_id, component_id, _status, msg, autopilot_state_for_gimbal_device_ext->target_system, autopilot_state_for_gimbal_device_ext->target_component, autopilot_state_for_gimbal_device_ext->time_boot_us, autopilot_state_for_gimbal_device_ext->wind_x, autopilot_state_for_gimbal_device_ext->wind_y, autopilot_state_for_gimbal_device_ext->wind_correction_angle);
+}
+
+/**
+ * @brief Send a autopilot_state_for_gimbal_device_ext message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param target_system System ID.
+ * @param target_component Component ID.
+ * @param time_boot_us [us] Timestamp (time since system boot).
+ * @param wind_x [m/s] Wind X speed in NED (North,Est, Down). NAN if unknown.
+ * @param wind_y [m/s] Wind Y speed in NED (North, East, Down). NAN if unknown.
+ * @param wind_correction_angle [rad] Correction angle due to wind. NaN if unknown.
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_autopilot_state_for_gimbal_device_ext_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint64_t time_boot_us, float wind_x, float wind_y, float wind_correction_angle)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_EXT_LEN];
+ _mav_put_uint64_t(buf, 0, time_boot_us);
+ _mav_put_float(buf, 8, wind_x);
+ _mav_put_float(buf, 12, wind_y);
+ _mav_put_float(buf, 16, wind_correction_angle);
+ _mav_put_uint8_t(buf, 20, target_system);
+ _mav_put_uint8_t(buf, 21, target_component);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_EXT, buf, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_EXT_MIN_LEN, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_EXT_LEN, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_EXT_CRC);
+#else
+ mavlink_autopilot_state_for_gimbal_device_ext_t packet;
+ packet.time_boot_us = time_boot_us;
+ packet.wind_x = wind_x;
+ packet.wind_y = wind_y;
+ packet.wind_correction_angle = wind_correction_angle;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_EXT, (const char *)&packet, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_EXT_MIN_LEN, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_EXT_LEN, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_EXT_CRC);
+#endif
+}
+
+/**
+ * @brief Send a autopilot_state_for_gimbal_device_ext message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_autopilot_state_for_gimbal_device_ext_send_struct(mavlink_channel_t chan, const mavlink_autopilot_state_for_gimbal_device_ext_t* autopilot_state_for_gimbal_device_ext)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_autopilot_state_for_gimbal_device_ext_send(chan, autopilot_state_for_gimbal_device_ext->target_system, autopilot_state_for_gimbal_device_ext->target_component, autopilot_state_for_gimbal_device_ext->time_boot_us, autopilot_state_for_gimbal_device_ext->wind_x, autopilot_state_for_gimbal_device_ext->wind_y, autopilot_state_for_gimbal_device_ext->wind_correction_angle);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_EXT, (const char *)autopilot_state_for_gimbal_device_ext, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_EXT_MIN_LEN, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_EXT_LEN, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_EXT_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_EXT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_autopilot_state_for_gimbal_device_ext_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint64_t time_boot_us, float wind_x, float wind_y, float wind_correction_angle)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint64_t(buf, 0, time_boot_us);
+ _mav_put_float(buf, 8, wind_x);
+ _mav_put_float(buf, 12, wind_y);
+ _mav_put_float(buf, 16, wind_correction_angle);
+ _mav_put_uint8_t(buf, 20, target_system);
+ _mav_put_uint8_t(buf, 21, target_component);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_EXT, buf, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_EXT_MIN_LEN, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_EXT_LEN, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_EXT_CRC);
+#else
+ mavlink_autopilot_state_for_gimbal_device_ext_t *packet = (mavlink_autopilot_state_for_gimbal_device_ext_t *)msgbuf;
+ packet->time_boot_us = time_boot_us;
+ packet->wind_x = wind_x;
+ packet->wind_y = wind_y;
+ packet->wind_correction_angle = wind_correction_angle;
+ packet->target_system = target_system;
+ packet->target_component = target_component;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_EXT, (const char *)packet, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_EXT_MIN_LEN, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_EXT_LEN, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_EXT_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_EXT UNPACKING
+
+
+/**
+ * @brief Get field target_system from autopilot_state_for_gimbal_device_ext message
+ *
+ * @return System ID.
+ */
+static inline uint8_t mavlink_msg_autopilot_state_for_gimbal_device_ext_get_target_system(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 20);
+}
+
+/**
+ * @brief Get field target_component from autopilot_state_for_gimbal_device_ext message
+ *
+ * @return Component ID.
+ */
+static inline uint8_t mavlink_msg_autopilot_state_for_gimbal_device_ext_get_target_component(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 21);
+}
+
+/**
+ * @brief Get field time_boot_us from autopilot_state_for_gimbal_device_ext message
+ *
+ * @return [us] Timestamp (time since system boot).
+ */
+static inline uint64_t mavlink_msg_autopilot_state_for_gimbal_device_ext_get_time_boot_us(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint64_t(msg, 0);
+}
+
+/**
+ * @brief Get field wind_x from autopilot_state_for_gimbal_device_ext message
+ *
+ * @return [m/s] Wind X speed in NED (North,Est, Down). NAN if unknown.
+ */
+static inline float mavlink_msg_autopilot_state_for_gimbal_device_ext_get_wind_x(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 8);
+}
+
+/**
+ * @brief Get field wind_y from autopilot_state_for_gimbal_device_ext message
+ *
+ * @return [m/s] Wind Y speed in NED (North, East, Down). NAN if unknown.
+ */
+static inline float mavlink_msg_autopilot_state_for_gimbal_device_ext_get_wind_y(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 12);
+}
+
+/**
+ * @brief Get field wind_correction_angle from autopilot_state_for_gimbal_device_ext message
+ *
+ * @return [rad] Correction angle due to wind. NaN if unknown.
+ */
+static inline float mavlink_msg_autopilot_state_for_gimbal_device_ext_get_wind_correction_angle(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 16);
+}
+
+/**
+ * @brief Decode a autopilot_state_for_gimbal_device_ext message into a struct
+ *
+ * @param msg The message to decode
+ * @param autopilot_state_for_gimbal_device_ext C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_autopilot_state_for_gimbal_device_ext_decode(const mavlink_message_t* msg, mavlink_autopilot_state_for_gimbal_device_ext_t* autopilot_state_for_gimbal_device_ext)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ autopilot_state_for_gimbal_device_ext->time_boot_us = mavlink_msg_autopilot_state_for_gimbal_device_ext_get_time_boot_us(msg);
+ autopilot_state_for_gimbal_device_ext->wind_x = mavlink_msg_autopilot_state_for_gimbal_device_ext_get_wind_x(msg);
+ autopilot_state_for_gimbal_device_ext->wind_y = mavlink_msg_autopilot_state_for_gimbal_device_ext_get_wind_y(msg);
+ autopilot_state_for_gimbal_device_ext->wind_correction_angle = mavlink_msg_autopilot_state_for_gimbal_device_ext_get_wind_correction_angle(msg);
+ autopilot_state_for_gimbal_device_ext->target_system = mavlink_msg_autopilot_state_for_gimbal_device_ext_get_target_system(msg);
+ autopilot_state_for_gimbal_device_ext->target_component = mavlink_msg_autopilot_state_for_gimbal_device_ext_get_target_component(msg);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_EXT_LEN? msg->len : MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_EXT_LEN;
+ memset(autopilot_state_for_gimbal_device_ext, 0, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_EXT_LEN);
+ memcpy(autopilot_state_for_gimbal_device_ext, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/storm32/mavlink_msg_frsky_passthrough_array.h b/lib/main/MAVLink/storm32/mavlink_msg_frsky_passthrough_array.h
new file mode 100644
index 00000000000..7438641874d
--- /dev/null
+++ b/lib/main/MAVLink/storm32/mavlink_msg_frsky_passthrough_array.h
@@ -0,0 +1,306 @@
+#pragma once
+// MESSAGE FRSKY_PASSTHROUGH_ARRAY PACKING
+
+#define MAVLINK_MSG_ID_FRSKY_PASSTHROUGH_ARRAY 60040
+
+
+typedef struct __mavlink_frsky_passthrough_array_t {
+ uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/
+ uint8_t count; /*< Number of passthrough packets in this message.*/
+ uint8_t packet_buf[240]; /*< Passthrough packet buffer. A packet has 6 bytes: uint16_t id + uint32_t data. The array has space for 40 packets.*/
+} mavlink_frsky_passthrough_array_t;
+
+#define MAVLINK_MSG_ID_FRSKY_PASSTHROUGH_ARRAY_LEN 245
+#define MAVLINK_MSG_ID_FRSKY_PASSTHROUGH_ARRAY_MIN_LEN 245
+#define MAVLINK_MSG_ID_60040_LEN 245
+#define MAVLINK_MSG_ID_60040_MIN_LEN 245
+
+#define MAVLINK_MSG_ID_FRSKY_PASSTHROUGH_ARRAY_CRC 156
+#define MAVLINK_MSG_ID_60040_CRC 156
+
+#define MAVLINK_MSG_FRSKY_PASSTHROUGH_ARRAY_FIELD_PACKET_BUF_LEN 240
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_FRSKY_PASSTHROUGH_ARRAY { \
+ 60040, \
+ "FRSKY_PASSTHROUGH_ARRAY", \
+ 3, \
+ { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_frsky_passthrough_array_t, time_boot_ms) }, \
+ { "count", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_frsky_passthrough_array_t, count) }, \
+ { "packet_buf", NULL, MAVLINK_TYPE_UINT8_T, 240, 5, offsetof(mavlink_frsky_passthrough_array_t, packet_buf) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_FRSKY_PASSTHROUGH_ARRAY { \
+ "FRSKY_PASSTHROUGH_ARRAY", \
+ 3, \
+ { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_frsky_passthrough_array_t, time_boot_ms) }, \
+ { "count", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_frsky_passthrough_array_t, count) }, \
+ { "packet_buf", NULL, MAVLINK_TYPE_UINT8_T, 240, 5, offsetof(mavlink_frsky_passthrough_array_t, packet_buf) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a frsky_passthrough_array 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 time_boot_ms [ms] Timestamp (time since system boot).
+ * @param count Number of passthrough packets in this message.
+ * @param packet_buf Passthrough packet buffer. A packet has 6 bytes: uint16_t id + uint32_t data. The array has space for 40 packets.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_frsky_passthrough_array_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint32_t time_boot_ms, uint8_t count, const uint8_t *packet_buf)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_FRSKY_PASSTHROUGH_ARRAY_LEN];
+ _mav_put_uint32_t(buf, 0, time_boot_ms);
+ _mav_put_uint8_t(buf, 4, count);
+ _mav_put_uint8_t_array(buf, 5, packet_buf, 240);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FRSKY_PASSTHROUGH_ARRAY_LEN);
+#else
+ mavlink_frsky_passthrough_array_t packet;
+ packet.time_boot_ms = time_boot_ms;
+ packet.count = count;
+ mav_array_assign_uint8_t(packet.packet_buf, packet_buf, 240);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FRSKY_PASSTHROUGH_ARRAY_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_FRSKY_PASSTHROUGH_ARRAY;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FRSKY_PASSTHROUGH_ARRAY_MIN_LEN, MAVLINK_MSG_ID_FRSKY_PASSTHROUGH_ARRAY_LEN, MAVLINK_MSG_ID_FRSKY_PASSTHROUGH_ARRAY_CRC);
+}
+
+/**
+ * @brief Pack a frsky_passthrough_array 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 time_boot_ms [ms] Timestamp (time since system boot).
+ * @param count Number of passthrough packets in this message.
+ * @param packet_buf Passthrough packet buffer. A packet has 6 bytes: uint16_t id + uint32_t data. The array has space for 40 packets.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_frsky_passthrough_array_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ uint32_t time_boot_ms, uint8_t count, const uint8_t *packet_buf)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_FRSKY_PASSTHROUGH_ARRAY_LEN];
+ _mav_put_uint32_t(buf, 0, time_boot_ms);
+ _mav_put_uint8_t(buf, 4, count);
+ _mav_put_uint8_t_array(buf, 5, packet_buf, 240);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FRSKY_PASSTHROUGH_ARRAY_LEN);
+#else
+ mavlink_frsky_passthrough_array_t packet;
+ packet.time_boot_ms = time_boot_ms;
+ packet.count = count;
+ mav_array_memcpy(packet.packet_buf, packet_buf, sizeof(uint8_t)*240);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FRSKY_PASSTHROUGH_ARRAY_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_FRSKY_PASSTHROUGH_ARRAY;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_FRSKY_PASSTHROUGH_ARRAY_MIN_LEN, MAVLINK_MSG_ID_FRSKY_PASSTHROUGH_ARRAY_LEN, MAVLINK_MSG_ID_FRSKY_PASSTHROUGH_ARRAY_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_FRSKY_PASSTHROUGH_ARRAY_MIN_LEN, MAVLINK_MSG_ID_FRSKY_PASSTHROUGH_ARRAY_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a frsky_passthrough_array 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 time_boot_ms [ms] Timestamp (time since system boot).
+ * @param count Number of passthrough packets in this message.
+ * @param packet_buf Passthrough packet buffer. A packet has 6 bytes: uint16_t id + uint32_t data. The array has space for 40 packets.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_frsky_passthrough_array_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint32_t time_boot_ms,uint8_t count,const uint8_t *packet_buf)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_FRSKY_PASSTHROUGH_ARRAY_LEN];
+ _mav_put_uint32_t(buf, 0, time_boot_ms);
+ _mav_put_uint8_t(buf, 4, count);
+ _mav_put_uint8_t_array(buf, 5, packet_buf, 240);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FRSKY_PASSTHROUGH_ARRAY_LEN);
+#else
+ mavlink_frsky_passthrough_array_t packet;
+ packet.time_boot_ms = time_boot_ms;
+ packet.count = count;
+ mav_array_assign_uint8_t(packet.packet_buf, packet_buf, 240);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FRSKY_PASSTHROUGH_ARRAY_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_FRSKY_PASSTHROUGH_ARRAY;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FRSKY_PASSTHROUGH_ARRAY_MIN_LEN, MAVLINK_MSG_ID_FRSKY_PASSTHROUGH_ARRAY_LEN, MAVLINK_MSG_ID_FRSKY_PASSTHROUGH_ARRAY_CRC);
+}
+
+/**
+ * @brief Encode a frsky_passthrough_array 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 frsky_passthrough_array C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_frsky_passthrough_array_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_frsky_passthrough_array_t* frsky_passthrough_array)
+{
+ return mavlink_msg_frsky_passthrough_array_pack(system_id, component_id, msg, frsky_passthrough_array->time_boot_ms, frsky_passthrough_array->count, frsky_passthrough_array->packet_buf);
+}
+
+/**
+ * @brief Encode a frsky_passthrough_array 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 frsky_passthrough_array C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_frsky_passthrough_array_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_frsky_passthrough_array_t* frsky_passthrough_array)
+{
+ return mavlink_msg_frsky_passthrough_array_pack_chan(system_id, component_id, chan, msg, frsky_passthrough_array->time_boot_ms, frsky_passthrough_array->count, frsky_passthrough_array->packet_buf);
+}
+
+/**
+ * @brief Encode a frsky_passthrough_array 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 frsky_passthrough_array C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_frsky_passthrough_array_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_frsky_passthrough_array_t* frsky_passthrough_array)
+{
+ return mavlink_msg_frsky_passthrough_array_pack_status(system_id, component_id, _status, msg, frsky_passthrough_array->time_boot_ms, frsky_passthrough_array->count, frsky_passthrough_array->packet_buf);
+}
+
+/**
+ * @brief Send a frsky_passthrough_array message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param time_boot_ms [ms] Timestamp (time since system boot).
+ * @param count Number of passthrough packets in this message.
+ * @param packet_buf Passthrough packet buffer. A packet has 6 bytes: uint16_t id + uint32_t data. The array has space for 40 packets.
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_frsky_passthrough_array_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t count, const uint8_t *packet_buf)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_FRSKY_PASSTHROUGH_ARRAY_LEN];
+ _mav_put_uint32_t(buf, 0, time_boot_ms);
+ _mav_put_uint8_t(buf, 4, count);
+ _mav_put_uint8_t_array(buf, 5, packet_buf, 240);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FRSKY_PASSTHROUGH_ARRAY, buf, MAVLINK_MSG_ID_FRSKY_PASSTHROUGH_ARRAY_MIN_LEN, MAVLINK_MSG_ID_FRSKY_PASSTHROUGH_ARRAY_LEN, MAVLINK_MSG_ID_FRSKY_PASSTHROUGH_ARRAY_CRC);
+#else
+ mavlink_frsky_passthrough_array_t packet;
+ packet.time_boot_ms = time_boot_ms;
+ packet.count = count;
+ mav_array_assign_uint8_t(packet.packet_buf, packet_buf, 240);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FRSKY_PASSTHROUGH_ARRAY, (const char *)&packet, MAVLINK_MSG_ID_FRSKY_PASSTHROUGH_ARRAY_MIN_LEN, MAVLINK_MSG_ID_FRSKY_PASSTHROUGH_ARRAY_LEN, MAVLINK_MSG_ID_FRSKY_PASSTHROUGH_ARRAY_CRC);
+#endif
+}
+
+/**
+ * @brief Send a frsky_passthrough_array message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_frsky_passthrough_array_send_struct(mavlink_channel_t chan, const mavlink_frsky_passthrough_array_t* frsky_passthrough_array)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_frsky_passthrough_array_send(chan, frsky_passthrough_array->time_boot_ms, frsky_passthrough_array->count, frsky_passthrough_array->packet_buf);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FRSKY_PASSTHROUGH_ARRAY, (const char *)frsky_passthrough_array, MAVLINK_MSG_ID_FRSKY_PASSTHROUGH_ARRAY_MIN_LEN, MAVLINK_MSG_ID_FRSKY_PASSTHROUGH_ARRAY_LEN, MAVLINK_MSG_ID_FRSKY_PASSTHROUGH_ARRAY_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_FRSKY_PASSTHROUGH_ARRAY_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_frsky_passthrough_array_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t count, const uint8_t *packet_buf)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint32_t(buf, 0, time_boot_ms);
+ _mav_put_uint8_t(buf, 4, count);
+ _mav_put_uint8_t_array(buf, 5, packet_buf, 240);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FRSKY_PASSTHROUGH_ARRAY, buf, MAVLINK_MSG_ID_FRSKY_PASSTHROUGH_ARRAY_MIN_LEN, MAVLINK_MSG_ID_FRSKY_PASSTHROUGH_ARRAY_LEN, MAVLINK_MSG_ID_FRSKY_PASSTHROUGH_ARRAY_CRC);
+#else
+ mavlink_frsky_passthrough_array_t *packet = (mavlink_frsky_passthrough_array_t *)msgbuf;
+ packet->time_boot_ms = time_boot_ms;
+ packet->count = count;
+ mav_array_assign_uint8_t(packet->packet_buf, packet_buf, 240);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FRSKY_PASSTHROUGH_ARRAY, (const char *)packet, MAVLINK_MSG_ID_FRSKY_PASSTHROUGH_ARRAY_MIN_LEN, MAVLINK_MSG_ID_FRSKY_PASSTHROUGH_ARRAY_LEN, MAVLINK_MSG_ID_FRSKY_PASSTHROUGH_ARRAY_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE FRSKY_PASSTHROUGH_ARRAY UNPACKING
+
+
+/**
+ * @brief Get field time_boot_ms from frsky_passthrough_array message
+ *
+ * @return [ms] Timestamp (time since system boot).
+ */
+static inline uint32_t mavlink_msg_frsky_passthrough_array_get_time_boot_ms(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint32_t(msg, 0);
+}
+
+/**
+ * @brief Get field count from frsky_passthrough_array message
+ *
+ * @return Number of passthrough packets in this message.
+ */
+static inline uint8_t mavlink_msg_frsky_passthrough_array_get_count(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 4);
+}
+
+/**
+ * @brief Get field packet_buf from frsky_passthrough_array message
+ *
+ * @return Passthrough packet buffer. A packet has 6 bytes: uint16_t id + uint32_t data. The array has space for 40 packets.
+ */
+static inline uint16_t mavlink_msg_frsky_passthrough_array_get_packet_buf(const mavlink_message_t* msg, uint8_t *packet_buf)
+{
+ return _MAV_RETURN_uint8_t_array(msg, packet_buf, 240, 5);
+}
+
+/**
+ * @brief Decode a frsky_passthrough_array message into a struct
+ *
+ * @param msg The message to decode
+ * @param frsky_passthrough_array C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_frsky_passthrough_array_decode(const mavlink_message_t* msg, mavlink_frsky_passthrough_array_t* frsky_passthrough_array)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ frsky_passthrough_array->time_boot_ms = mavlink_msg_frsky_passthrough_array_get_time_boot_ms(msg);
+ frsky_passthrough_array->count = mavlink_msg_frsky_passthrough_array_get_count(msg);
+ mavlink_msg_frsky_passthrough_array_get_packet_buf(msg, frsky_passthrough_array->packet_buf);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_FRSKY_PASSTHROUGH_ARRAY_LEN? msg->len : MAVLINK_MSG_ID_FRSKY_PASSTHROUGH_ARRAY_LEN;
+ memset(frsky_passthrough_array, 0, MAVLINK_MSG_ID_FRSKY_PASSTHROUGH_ARRAY_LEN);
+ memcpy(frsky_passthrough_array, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/storm32/mavlink_msg_mlrs_radio_link_flow_control.h b/lib/main/MAVLink/storm32/mavlink_msg_mlrs_radio_link_flow_control.h
new file mode 100644
index 00000000000..c589921dc05
--- /dev/null
+++ b/lib/main/MAVLink/storm32/mavlink_msg_mlrs_radio_link_flow_control.h
@@ -0,0 +1,372 @@
+#pragma once
+// MESSAGE MLRS_RADIO_LINK_FLOW_CONTROL PACKING
+
+#define MAVLINK_MSG_ID_MLRS_RADIO_LINK_FLOW_CONTROL 60047
+
+
+typedef struct __mavlink_mlrs_radio_link_flow_control_t {
+ uint16_t tx_ser_rate; /*< [bytes/s] Transmitted bytes per second, UINT16_MAX: invalid/unknown.*/
+ uint16_t rx_ser_rate; /*< [bytes/s] Received bytes per second, UINT16_MAX: invalid/unknown.*/
+ uint8_t tx_used_ser_bandwidth; /*< [c%] Transmit bandwidth consumption. Values: 0..100, UINT8_MAX: invalid/unknown.*/
+ uint8_t rx_used_ser_bandwidth; /*< [c%] Receive bandwidth consumption. Values: 0..100, UINT8_MAX: invalid/unknown.*/
+ uint8_t txbuf; /*< [c%] For compatibility with legacy method. UINT8_MAX: unknown.*/
+} mavlink_mlrs_radio_link_flow_control_t;
+
+#define MAVLINK_MSG_ID_MLRS_RADIO_LINK_FLOW_CONTROL_LEN 7
+#define MAVLINK_MSG_ID_MLRS_RADIO_LINK_FLOW_CONTROL_MIN_LEN 7
+#define MAVLINK_MSG_ID_60047_LEN 7
+#define MAVLINK_MSG_ID_60047_MIN_LEN 7
+
+#define MAVLINK_MSG_ID_MLRS_RADIO_LINK_FLOW_CONTROL_CRC 55
+#define MAVLINK_MSG_ID_60047_CRC 55
+
+
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_MLRS_RADIO_LINK_FLOW_CONTROL { \
+ 60047, \
+ "MLRS_RADIO_LINK_FLOW_CONTROL", \
+ 5, \
+ { { "tx_ser_rate", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mlrs_radio_link_flow_control_t, tx_ser_rate) }, \
+ { "rx_ser_rate", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_mlrs_radio_link_flow_control_t, rx_ser_rate) }, \
+ { "tx_used_ser_bandwidth", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_mlrs_radio_link_flow_control_t, tx_used_ser_bandwidth) }, \
+ { "rx_used_ser_bandwidth", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_mlrs_radio_link_flow_control_t, rx_used_ser_bandwidth) }, \
+ { "txbuf", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_mlrs_radio_link_flow_control_t, txbuf) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_MLRS_RADIO_LINK_FLOW_CONTROL { \
+ "MLRS_RADIO_LINK_FLOW_CONTROL", \
+ 5, \
+ { { "tx_ser_rate", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mlrs_radio_link_flow_control_t, tx_ser_rate) }, \
+ { "rx_ser_rate", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_mlrs_radio_link_flow_control_t, rx_ser_rate) }, \
+ { "tx_used_ser_bandwidth", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_mlrs_radio_link_flow_control_t, tx_used_ser_bandwidth) }, \
+ { "rx_used_ser_bandwidth", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_mlrs_radio_link_flow_control_t, rx_used_ser_bandwidth) }, \
+ { "txbuf", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_mlrs_radio_link_flow_control_t, txbuf) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a mlrs_radio_link_flow_control 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 tx_ser_rate [bytes/s] Transmitted bytes per second, UINT16_MAX: invalid/unknown.
+ * @param rx_ser_rate [bytes/s] Received bytes per second, UINT16_MAX: invalid/unknown.
+ * @param tx_used_ser_bandwidth [c%] Transmit bandwidth consumption. Values: 0..100, UINT8_MAX: invalid/unknown.
+ * @param rx_used_ser_bandwidth [c%] Receive bandwidth consumption. Values: 0..100, UINT8_MAX: invalid/unknown.
+ * @param txbuf [c%] For compatibility with legacy method. UINT8_MAX: unknown.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_mlrs_radio_link_flow_control_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint16_t tx_ser_rate, uint16_t rx_ser_rate, uint8_t tx_used_ser_bandwidth, uint8_t rx_used_ser_bandwidth, uint8_t txbuf)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_MLRS_RADIO_LINK_FLOW_CONTROL_LEN];
+ _mav_put_uint16_t(buf, 0, tx_ser_rate);
+ _mav_put_uint16_t(buf, 2, rx_ser_rate);
+ _mav_put_uint8_t(buf, 4, tx_used_ser_bandwidth);
+ _mav_put_uint8_t(buf, 5, rx_used_ser_bandwidth);
+ _mav_put_uint8_t(buf, 6, txbuf);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MLRS_RADIO_LINK_FLOW_CONTROL_LEN);
+#else
+ mavlink_mlrs_radio_link_flow_control_t packet;
+ packet.tx_ser_rate = tx_ser_rate;
+ packet.rx_ser_rate = rx_ser_rate;
+ packet.tx_used_ser_bandwidth = tx_used_ser_bandwidth;
+ packet.rx_used_ser_bandwidth = rx_used_ser_bandwidth;
+ packet.txbuf = txbuf;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MLRS_RADIO_LINK_FLOW_CONTROL_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_MLRS_RADIO_LINK_FLOW_CONTROL;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MLRS_RADIO_LINK_FLOW_CONTROL_MIN_LEN, MAVLINK_MSG_ID_MLRS_RADIO_LINK_FLOW_CONTROL_LEN, MAVLINK_MSG_ID_MLRS_RADIO_LINK_FLOW_CONTROL_CRC);
+}
+
+/**
+ * @brief Pack a mlrs_radio_link_flow_control 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 tx_ser_rate [bytes/s] Transmitted bytes per second, UINT16_MAX: invalid/unknown.
+ * @param rx_ser_rate [bytes/s] Received bytes per second, UINT16_MAX: invalid/unknown.
+ * @param tx_used_ser_bandwidth [c%] Transmit bandwidth consumption. Values: 0..100, UINT8_MAX: invalid/unknown.
+ * @param rx_used_ser_bandwidth [c%] Receive bandwidth consumption. Values: 0..100, UINT8_MAX: invalid/unknown.
+ * @param txbuf [c%] For compatibility with legacy method. UINT8_MAX: unknown.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_mlrs_radio_link_flow_control_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ uint16_t tx_ser_rate, uint16_t rx_ser_rate, uint8_t tx_used_ser_bandwidth, uint8_t rx_used_ser_bandwidth, uint8_t txbuf)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_MLRS_RADIO_LINK_FLOW_CONTROL_LEN];
+ _mav_put_uint16_t(buf, 0, tx_ser_rate);
+ _mav_put_uint16_t(buf, 2, rx_ser_rate);
+ _mav_put_uint8_t(buf, 4, tx_used_ser_bandwidth);
+ _mav_put_uint8_t(buf, 5, rx_used_ser_bandwidth);
+ _mav_put_uint8_t(buf, 6, txbuf);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MLRS_RADIO_LINK_FLOW_CONTROL_LEN);
+#else
+ mavlink_mlrs_radio_link_flow_control_t packet;
+ packet.tx_ser_rate = tx_ser_rate;
+ packet.rx_ser_rate = rx_ser_rate;
+ packet.tx_used_ser_bandwidth = tx_used_ser_bandwidth;
+ packet.rx_used_ser_bandwidth = rx_used_ser_bandwidth;
+ packet.txbuf = txbuf;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MLRS_RADIO_LINK_FLOW_CONTROL_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_MLRS_RADIO_LINK_FLOW_CONTROL;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_MLRS_RADIO_LINK_FLOW_CONTROL_MIN_LEN, MAVLINK_MSG_ID_MLRS_RADIO_LINK_FLOW_CONTROL_LEN, MAVLINK_MSG_ID_MLRS_RADIO_LINK_FLOW_CONTROL_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_MLRS_RADIO_LINK_FLOW_CONTROL_MIN_LEN, MAVLINK_MSG_ID_MLRS_RADIO_LINK_FLOW_CONTROL_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a mlrs_radio_link_flow_control 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 tx_ser_rate [bytes/s] Transmitted bytes per second, UINT16_MAX: invalid/unknown.
+ * @param rx_ser_rate [bytes/s] Received bytes per second, UINT16_MAX: invalid/unknown.
+ * @param tx_used_ser_bandwidth [c%] Transmit bandwidth consumption. Values: 0..100, UINT8_MAX: invalid/unknown.
+ * @param rx_used_ser_bandwidth [c%] Receive bandwidth consumption. Values: 0..100, UINT8_MAX: invalid/unknown.
+ * @param txbuf [c%] For compatibility with legacy method. UINT8_MAX: unknown.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_mlrs_radio_link_flow_control_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint16_t tx_ser_rate,uint16_t rx_ser_rate,uint8_t tx_used_ser_bandwidth,uint8_t rx_used_ser_bandwidth,uint8_t txbuf)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_MLRS_RADIO_LINK_FLOW_CONTROL_LEN];
+ _mav_put_uint16_t(buf, 0, tx_ser_rate);
+ _mav_put_uint16_t(buf, 2, rx_ser_rate);
+ _mav_put_uint8_t(buf, 4, tx_used_ser_bandwidth);
+ _mav_put_uint8_t(buf, 5, rx_used_ser_bandwidth);
+ _mav_put_uint8_t(buf, 6, txbuf);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MLRS_RADIO_LINK_FLOW_CONTROL_LEN);
+#else
+ mavlink_mlrs_radio_link_flow_control_t packet;
+ packet.tx_ser_rate = tx_ser_rate;
+ packet.rx_ser_rate = rx_ser_rate;
+ packet.tx_used_ser_bandwidth = tx_used_ser_bandwidth;
+ packet.rx_used_ser_bandwidth = rx_used_ser_bandwidth;
+ packet.txbuf = txbuf;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MLRS_RADIO_LINK_FLOW_CONTROL_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_MLRS_RADIO_LINK_FLOW_CONTROL;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MLRS_RADIO_LINK_FLOW_CONTROL_MIN_LEN, MAVLINK_MSG_ID_MLRS_RADIO_LINK_FLOW_CONTROL_LEN, MAVLINK_MSG_ID_MLRS_RADIO_LINK_FLOW_CONTROL_CRC);
+}
+
+/**
+ * @brief Encode a mlrs_radio_link_flow_control 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 mlrs_radio_link_flow_control C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_mlrs_radio_link_flow_control_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mlrs_radio_link_flow_control_t* mlrs_radio_link_flow_control)
+{
+ return mavlink_msg_mlrs_radio_link_flow_control_pack(system_id, component_id, msg, mlrs_radio_link_flow_control->tx_ser_rate, mlrs_radio_link_flow_control->rx_ser_rate, mlrs_radio_link_flow_control->tx_used_ser_bandwidth, mlrs_radio_link_flow_control->rx_used_ser_bandwidth, mlrs_radio_link_flow_control->txbuf);
+}
+
+/**
+ * @brief Encode a mlrs_radio_link_flow_control 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 mlrs_radio_link_flow_control C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_mlrs_radio_link_flow_control_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mlrs_radio_link_flow_control_t* mlrs_radio_link_flow_control)
+{
+ return mavlink_msg_mlrs_radio_link_flow_control_pack_chan(system_id, component_id, chan, msg, mlrs_radio_link_flow_control->tx_ser_rate, mlrs_radio_link_flow_control->rx_ser_rate, mlrs_radio_link_flow_control->tx_used_ser_bandwidth, mlrs_radio_link_flow_control->rx_used_ser_bandwidth, mlrs_radio_link_flow_control->txbuf);
+}
+
+/**
+ * @brief Encode a mlrs_radio_link_flow_control 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 mlrs_radio_link_flow_control C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_mlrs_radio_link_flow_control_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_mlrs_radio_link_flow_control_t* mlrs_radio_link_flow_control)
+{
+ return mavlink_msg_mlrs_radio_link_flow_control_pack_status(system_id, component_id, _status, msg, mlrs_radio_link_flow_control->tx_ser_rate, mlrs_radio_link_flow_control->rx_ser_rate, mlrs_radio_link_flow_control->tx_used_ser_bandwidth, mlrs_radio_link_flow_control->rx_used_ser_bandwidth, mlrs_radio_link_flow_control->txbuf);
+}
+
+/**
+ * @brief Send a mlrs_radio_link_flow_control message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param tx_ser_rate [bytes/s] Transmitted bytes per second, UINT16_MAX: invalid/unknown.
+ * @param rx_ser_rate [bytes/s] Received bytes per second, UINT16_MAX: invalid/unknown.
+ * @param tx_used_ser_bandwidth [c%] Transmit bandwidth consumption. Values: 0..100, UINT8_MAX: invalid/unknown.
+ * @param rx_used_ser_bandwidth [c%] Receive bandwidth consumption. Values: 0..100, UINT8_MAX: invalid/unknown.
+ * @param txbuf [c%] For compatibility with legacy method. UINT8_MAX: unknown.
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_mlrs_radio_link_flow_control_send(mavlink_channel_t chan, uint16_t tx_ser_rate, uint16_t rx_ser_rate, uint8_t tx_used_ser_bandwidth, uint8_t rx_used_ser_bandwidth, uint8_t txbuf)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_MLRS_RADIO_LINK_FLOW_CONTROL_LEN];
+ _mav_put_uint16_t(buf, 0, tx_ser_rate);
+ _mav_put_uint16_t(buf, 2, rx_ser_rate);
+ _mav_put_uint8_t(buf, 4, tx_used_ser_bandwidth);
+ _mav_put_uint8_t(buf, 5, rx_used_ser_bandwidth);
+ _mav_put_uint8_t(buf, 6, txbuf);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MLRS_RADIO_LINK_FLOW_CONTROL, buf, MAVLINK_MSG_ID_MLRS_RADIO_LINK_FLOW_CONTROL_MIN_LEN, MAVLINK_MSG_ID_MLRS_RADIO_LINK_FLOW_CONTROL_LEN, MAVLINK_MSG_ID_MLRS_RADIO_LINK_FLOW_CONTROL_CRC);
+#else
+ mavlink_mlrs_radio_link_flow_control_t packet;
+ packet.tx_ser_rate = tx_ser_rate;
+ packet.rx_ser_rate = rx_ser_rate;
+ packet.tx_used_ser_bandwidth = tx_used_ser_bandwidth;
+ packet.rx_used_ser_bandwidth = rx_used_ser_bandwidth;
+ packet.txbuf = txbuf;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MLRS_RADIO_LINK_FLOW_CONTROL, (const char *)&packet, MAVLINK_MSG_ID_MLRS_RADIO_LINK_FLOW_CONTROL_MIN_LEN, MAVLINK_MSG_ID_MLRS_RADIO_LINK_FLOW_CONTROL_LEN, MAVLINK_MSG_ID_MLRS_RADIO_LINK_FLOW_CONTROL_CRC);
+#endif
+}
+
+/**
+ * @brief Send a mlrs_radio_link_flow_control message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_mlrs_radio_link_flow_control_send_struct(mavlink_channel_t chan, const mavlink_mlrs_radio_link_flow_control_t* mlrs_radio_link_flow_control)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_mlrs_radio_link_flow_control_send(chan, mlrs_radio_link_flow_control->tx_ser_rate, mlrs_radio_link_flow_control->rx_ser_rate, mlrs_radio_link_flow_control->tx_used_ser_bandwidth, mlrs_radio_link_flow_control->rx_used_ser_bandwidth, mlrs_radio_link_flow_control->txbuf);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MLRS_RADIO_LINK_FLOW_CONTROL, (const char *)mlrs_radio_link_flow_control, MAVLINK_MSG_ID_MLRS_RADIO_LINK_FLOW_CONTROL_MIN_LEN, MAVLINK_MSG_ID_MLRS_RADIO_LINK_FLOW_CONTROL_LEN, MAVLINK_MSG_ID_MLRS_RADIO_LINK_FLOW_CONTROL_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_MLRS_RADIO_LINK_FLOW_CONTROL_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_mlrs_radio_link_flow_control_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t tx_ser_rate, uint16_t rx_ser_rate, uint8_t tx_used_ser_bandwidth, uint8_t rx_used_ser_bandwidth, uint8_t txbuf)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint16_t(buf, 0, tx_ser_rate);
+ _mav_put_uint16_t(buf, 2, rx_ser_rate);
+ _mav_put_uint8_t(buf, 4, tx_used_ser_bandwidth);
+ _mav_put_uint8_t(buf, 5, rx_used_ser_bandwidth);
+ _mav_put_uint8_t(buf, 6, txbuf);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MLRS_RADIO_LINK_FLOW_CONTROL, buf, MAVLINK_MSG_ID_MLRS_RADIO_LINK_FLOW_CONTROL_MIN_LEN, MAVLINK_MSG_ID_MLRS_RADIO_LINK_FLOW_CONTROL_LEN, MAVLINK_MSG_ID_MLRS_RADIO_LINK_FLOW_CONTROL_CRC);
+#else
+ mavlink_mlrs_radio_link_flow_control_t *packet = (mavlink_mlrs_radio_link_flow_control_t *)msgbuf;
+ packet->tx_ser_rate = tx_ser_rate;
+ packet->rx_ser_rate = rx_ser_rate;
+ packet->tx_used_ser_bandwidth = tx_used_ser_bandwidth;
+ packet->rx_used_ser_bandwidth = rx_used_ser_bandwidth;
+ packet->txbuf = txbuf;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MLRS_RADIO_LINK_FLOW_CONTROL, (const char *)packet, MAVLINK_MSG_ID_MLRS_RADIO_LINK_FLOW_CONTROL_MIN_LEN, MAVLINK_MSG_ID_MLRS_RADIO_LINK_FLOW_CONTROL_LEN, MAVLINK_MSG_ID_MLRS_RADIO_LINK_FLOW_CONTROL_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE MLRS_RADIO_LINK_FLOW_CONTROL UNPACKING
+
+
+/**
+ * @brief Get field tx_ser_rate from mlrs_radio_link_flow_control message
+ *
+ * @return [bytes/s] Transmitted bytes per second, UINT16_MAX: invalid/unknown.
+ */
+static inline uint16_t mavlink_msg_mlrs_radio_link_flow_control_get_tx_ser_rate(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 0);
+}
+
+/**
+ * @brief Get field rx_ser_rate from mlrs_radio_link_flow_control message
+ *
+ * @return [bytes/s] Received bytes per second, UINT16_MAX: invalid/unknown.
+ */
+static inline uint16_t mavlink_msg_mlrs_radio_link_flow_control_get_rx_ser_rate(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 2);
+}
+
+/**
+ * @brief Get field tx_used_ser_bandwidth from mlrs_radio_link_flow_control message
+ *
+ * @return [c%] Transmit bandwidth consumption. Values: 0..100, UINT8_MAX: invalid/unknown.
+ */
+static inline uint8_t mavlink_msg_mlrs_radio_link_flow_control_get_tx_used_ser_bandwidth(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 4);
+}
+
+/**
+ * @brief Get field rx_used_ser_bandwidth from mlrs_radio_link_flow_control message
+ *
+ * @return [c%] Receive bandwidth consumption. Values: 0..100, UINT8_MAX: invalid/unknown.
+ */
+static inline uint8_t mavlink_msg_mlrs_radio_link_flow_control_get_rx_used_ser_bandwidth(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 5);
+}
+
+/**
+ * @brief Get field txbuf from mlrs_radio_link_flow_control message
+ *
+ * @return [c%] For compatibility with legacy method. UINT8_MAX: unknown.
+ */
+static inline uint8_t mavlink_msg_mlrs_radio_link_flow_control_get_txbuf(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 6);
+}
+
+/**
+ * @brief Decode a mlrs_radio_link_flow_control message into a struct
+ *
+ * @param msg The message to decode
+ * @param mlrs_radio_link_flow_control C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_mlrs_radio_link_flow_control_decode(const mavlink_message_t* msg, mavlink_mlrs_radio_link_flow_control_t* mlrs_radio_link_flow_control)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mlrs_radio_link_flow_control->tx_ser_rate = mavlink_msg_mlrs_radio_link_flow_control_get_tx_ser_rate(msg);
+ mlrs_radio_link_flow_control->rx_ser_rate = mavlink_msg_mlrs_radio_link_flow_control_get_rx_ser_rate(msg);
+ mlrs_radio_link_flow_control->tx_used_ser_bandwidth = mavlink_msg_mlrs_radio_link_flow_control_get_tx_used_ser_bandwidth(msg);
+ mlrs_radio_link_flow_control->rx_used_ser_bandwidth = mavlink_msg_mlrs_radio_link_flow_control_get_rx_used_ser_bandwidth(msg);
+ mlrs_radio_link_flow_control->txbuf = mavlink_msg_mlrs_radio_link_flow_control_get_txbuf(msg);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_MLRS_RADIO_LINK_FLOW_CONTROL_LEN? msg->len : MAVLINK_MSG_ID_MLRS_RADIO_LINK_FLOW_CONTROL_LEN;
+ memset(mlrs_radio_link_flow_control, 0, MAVLINK_MSG_ID_MLRS_RADIO_LINK_FLOW_CONTROL_LEN);
+ memcpy(mlrs_radio_link_flow_control, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/storm32/mavlink_msg_mlrs_radio_link_information.h b/lib/main/MAVLink/storm32/mavlink_msg_mlrs_radio_link_information.h
new file mode 100644
index 00000000000..a331d48d9ba
--- /dev/null
+++ b/lib/main/MAVLink/storm32/mavlink_msg_mlrs_radio_link_information.h
@@ -0,0 +1,615 @@
+#pragma once
+// MESSAGE MLRS_RADIO_LINK_INFORMATION PACKING
+
+#define MAVLINK_MSG_ID_MLRS_RADIO_LINK_INFORMATION 60046
+
+
+typedef struct __mavlink_mlrs_radio_link_information_t {
+ uint16_t tx_frame_rate; /*< [Hz] Frame rate in Hz (frames per second) for Tx to Rx transmission. 0: unknown.*/
+ uint16_t rx_frame_rate; /*< [Hz] Frame rate in Hz (frames per second) for Rx to Tx transmission. Normally equal to tx_packet_rate. 0: unknown.*/
+ uint16_t tx_ser_data_rate; /*< Maximum data rate of serial stream in bytes/s for Tx to Rx transmission. 0: unknown. UINT16_MAX: data rate is 64 KBytes/s or larger.*/
+ uint16_t rx_ser_data_rate; /*< Maximum data rate of serial stream in bytes/s for Rx to Tx transmission. 0: unknown. UINT16_MAX: data rate is 64 KBytes/s or larger.*/
+ uint8_t target_system; /*< System ID (ID of target system, normally flight controller).*/
+ uint8_t target_component; /*< Component ID (normally 0 for broadcast).*/
+ uint8_t type; /*< Radio link type. 0: unknown/generic type.*/
+ uint8_t mode; /*< Operation mode. Radio link dependent. UINT8_MAX: ignore/unknown.*/
+ int8_t tx_power; /*< [dBm] Tx transmit power in dBm. INT8_MAX: unknown.*/
+ int8_t rx_power; /*< [dBm] Rx transmit power in dBm. INT8_MAX: unknown.*/
+ char mode_str[6]; /*< Operation mode as human readable string. Radio link dependent. Terminated by NULL if the string length is less than 6 chars and WITHOUT NULL termination if the length is exactly 6 chars - applications have to provide 6+1 bytes storage if the mode is stored as string. Use a zero-length string if not known.*/
+ char band_str[6]; /*< Frequency band as human readable string. Radio link dependent. Terminated by NULL if the string length is less than 6 chars and WITHOUT NULL termination if the length is exactly 6 chars - applications have to provide 6+1 bytes storage if the mode is stored as string. Use a zero-length string if not known.*/
+ uint8_t tx_receive_sensitivity; /*< Receive sensitivity of Tx in inverted dBm. 1..255 represents -1..-255 dBm, 0: unknown.*/
+ uint8_t rx_receive_sensitivity; /*< Receive sensitivity of Rx in inverted dBm. 1..255 represents -1..-255 dBm, 0: unknown.*/
+} mavlink_mlrs_radio_link_information_t;
+
+#define MAVLINK_MSG_ID_MLRS_RADIO_LINK_INFORMATION_LEN 28
+#define MAVLINK_MSG_ID_MLRS_RADIO_LINK_INFORMATION_MIN_LEN 28
+#define MAVLINK_MSG_ID_60046_LEN 28
+#define MAVLINK_MSG_ID_60046_MIN_LEN 28
+
+#define MAVLINK_MSG_ID_MLRS_RADIO_LINK_INFORMATION_CRC 171
+#define MAVLINK_MSG_ID_60046_CRC 171
+
+#define MAVLINK_MSG_MLRS_RADIO_LINK_INFORMATION_FIELD_MODE_STR_LEN 6
+#define MAVLINK_MSG_MLRS_RADIO_LINK_INFORMATION_FIELD_BAND_STR_LEN 6
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_MLRS_RADIO_LINK_INFORMATION { \
+ 60046, \
+ "MLRS_RADIO_LINK_INFORMATION", \
+ 14, \
+ { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_mlrs_radio_link_information_t, target_system) }, \
+ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_mlrs_radio_link_information_t, target_component) }, \
+ { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_mlrs_radio_link_information_t, type) }, \
+ { "mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_mlrs_radio_link_information_t, mode) }, \
+ { "tx_power", NULL, MAVLINK_TYPE_INT8_T, 0, 12, offsetof(mavlink_mlrs_radio_link_information_t, tx_power) }, \
+ { "rx_power", NULL, MAVLINK_TYPE_INT8_T, 0, 13, offsetof(mavlink_mlrs_radio_link_information_t, rx_power) }, \
+ { "tx_frame_rate", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mlrs_radio_link_information_t, tx_frame_rate) }, \
+ { "rx_frame_rate", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_mlrs_radio_link_information_t, rx_frame_rate) }, \
+ { "mode_str", NULL, MAVLINK_TYPE_CHAR, 6, 14, offsetof(mavlink_mlrs_radio_link_information_t, mode_str) }, \
+ { "band_str", NULL, MAVLINK_TYPE_CHAR, 6, 20, offsetof(mavlink_mlrs_radio_link_information_t, band_str) }, \
+ { "tx_ser_data_rate", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_mlrs_radio_link_information_t, tx_ser_data_rate) }, \
+ { "rx_ser_data_rate", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_mlrs_radio_link_information_t, rx_ser_data_rate) }, \
+ { "tx_receive_sensitivity", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_mlrs_radio_link_information_t, tx_receive_sensitivity) }, \
+ { "rx_receive_sensitivity", NULL, MAVLINK_TYPE_UINT8_T, 0, 27, offsetof(mavlink_mlrs_radio_link_information_t, rx_receive_sensitivity) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_MLRS_RADIO_LINK_INFORMATION { \
+ "MLRS_RADIO_LINK_INFORMATION", \
+ 14, \
+ { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_mlrs_radio_link_information_t, target_system) }, \
+ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_mlrs_radio_link_information_t, target_component) }, \
+ { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_mlrs_radio_link_information_t, type) }, \
+ { "mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_mlrs_radio_link_information_t, mode) }, \
+ { "tx_power", NULL, MAVLINK_TYPE_INT8_T, 0, 12, offsetof(mavlink_mlrs_radio_link_information_t, tx_power) }, \
+ { "rx_power", NULL, MAVLINK_TYPE_INT8_T, 0, 13, offsetof(mavlink_mlrs_radio_link_information_t, rx_power) }, \
+ { "tx_frame_rate", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mlrs_radio_link_information_t, tx_frame_rate) }, \
+ { "rx_frame_rate", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_mlrs_radio_link_information_t, rx_frame_rate) }, \
+ { "mode_str", NULL, MAVLINK_TYPE_CHAR, 6, 14, offsetof(mavlink_mlrs_radio_link_information_t, mode_str) }, \
+ { "band_str", NULL, MAVLINK_TYPE_CHAR, 6, 20, offsetof(mavlink_mlrs_radio_link_information_t, band_str) }, \
+ { "tx_ser_data_rate", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_mlrs_radio_link_information_t, tx_ser_data_rate) }, \
+ { "rx_ser_data_rate", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_mlrs_radio_link_information_t, rx_ser_data_rate) }, \
+ { "tx_receive_sensitivity", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_mlrs_radio_link_information_t, tx_receive_sensitivity) }, \
+ { "rx_receive_sensitivity", NULL, MAVLINK_TYPE_UINT8_T, 0, 27, offsetof(mavlink_mlrs_radio_link_information_t, rx_receive_sensitivity) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a mlrs_radio_link_information 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 target_system System ID (ID of target system, normally flight controller).
+ * @param target_component Component ID (normally 0 for broadcast).
+ * @param type Radio link type. 0: unknown/generic type.
+ * @param mode Operation mode. Radio link dependent. UINT8_MAX: ignore/unknown.
+ * @param tx_power [dBm] Tx transmit power in dBm. INT8_MAX: unknown.
+ * @param rx_power [dBm] Rx transmit power in dBm. INT8_MAX: unknown.
+ * @param tx_frame_rate [Hz] Frame rate in Hz (frames per second) for Tx to Rx transmission. 0: unknown.
+ * @param rx_frame_rate [Hz] Frame rate in Hz (frames per second) for Rx to Tx transmission. Normally equal to tx_packet_rate. 0: unknown.
+ * @param mode_str Operation mode as human readable string. Radio link dependent. Terminated by NULL if the string length is less than 6 chars and WITHOUT NULL termination if the length is exactly 6 chars - applications have to provide 6+1 bytes storage if the mode is stored as string. Use a zero-length string if not known.
+ * @param band_str Frequency band as human readable string. Radio link dependent. Terminated by NULL if the string length is less than 6 chars and WITHOUT NULL termination if the length is exactly 6 chars - applications have to provide 6+1 bytes storage if the mode is stored as string. Use a zero-length string if not known.
+ * @param tx_ser_data_rate Maximum data rate of serial stream in bytes/s for Tx to Rx transmission. 0: unknown. UINT16_MAX: data rate is 64 KBytes/s or larger.
+ * @param rx_ser_data_rate Maximum data rate of serial stream in bytes/s for Rx to Tx transmission. 0: unknown. UINT16_MAX: data rate is 64 KBytes/s or larger.
+ * @param tx_receive_sensitivity Receive sensitivity of Tx in inverted dBm. 1..255 represents -1..-255 dBm, 0: unknown.
+ * @param rx_receive_sensitivity Receive sensitivity of Rx in inverted dBm. 1..255 represents -1..-255 dBm, 0: unknown.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_mlrs_radio_link_information_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint8_t target_system, uint8_t target_component, uint8_t type, uint8_t mode, int8_t tx_power, int8_t rx_power, uint16_t tx_frame_rate, uint16_t rx_frame_rate, const char *mode_str, const char *band_str, uint16_t tx_ser_data_rate, uint16_t rx_ser_data_rate, uint8_t tx_receive_sensitivity, uint8_t rx_receive_sensitivity)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_MLRS_RADIO_LINK_INFORMATION_LEN];
+ _mav_put_uint16_t(buf, 0, tx_frame_rate);
+ _mav_put_uint16_t(buf, 2, rx_frame_rate);
+ _mav_put_uint16_t(buf, 4, tx_ser_data_rate);
+ _mav_put_uint16_t(buf, 6, rx_ser_data_rate);
+ _mav_put_uint8_t(buf, 8, target_system);
+ _mav_put_uint8_t(buf, 9, target_component);
+ _mav_put_uint8_t(buf, 10, type);
+ _mav_put_uint8_t(buf, 11, mode);
+ _mav_put_int8_t(buf, 12, tx_power);
+ _mav_put_int8_t(buf, 13, rx_power);
+ _mav_put_uint8_t(buf, 26, tx_receive_sensitivity);
+ _mav_put_uint8_t(buf, 27, rx_receive_sensitivity);
+ _mav_put_char_array(buf, 14, mode_str, 6);
+ _mav_put_char_array(buf, 20, band_str, 6);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MLRS_RADIO_LINK_INFORMATION_LEN);
+#else
+ mavlink_mlrs_radio_link_information_t packet;
+ packet.tx_frame_rate = tx_frame_rate;
+ packet.rx_frame_rate = rx_frame_rate;
+ packet.tx_ser_data_rate = tx_ser_data_rate;
+ packet.rx_ser_data_rate = rx_ser_data_rate;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.type = type;
+ packet.mode = mode;
+ packet.tx_power = tx_power;
+ packet.rx_power = rx_power;
+ packet.tx_receive_sensitivity = tx_receive_sensitivity;
+ packet.rx_receive_sensitivity = rx_receive_sensitivity;
+ mav_array_assign_char(packet.mode_str, mode_str, 6);
+ mav_array_assign_char(packet.band_str, band_str, 6);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MLRS_RADIO_LINK_INFORMATION_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_MLRS_RADIO_LINK_INFORMATION;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MLRS_RADIO_LINK_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_MLRS_RADIO_LINK_INFORMATION_LEN, MAVLINK_MSG_ID_MLRS_RADIO_LINK_INFORMATION_CRC);
+}
+
+/**
+ * @brief Pack a mlrs_radio_link_information 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 target_system System ID (ID of target system, normally flight controller).
+ * @param target_component Component ID (normally 0 for broadcast).
+ * @param type Radio link type. 0: unknown/generic type.
+ * @param mode Operation mode. Radio link dependent. UINT8_MAX: ignore/unknown.
+ * @param tx_power [dBm] Tx transmit power in dBm. INT8_MAX: unknown.
+ * @param rx_power [dBm] Rx transmit power in dBm. INT8_MAX: unknown.
+ * @param tx_frame_rate [Hz] Frame rate in Hz (frames per second) for Tx to Rx transmission. 0: unknown.
+ * @param rx_frame_rate [Hz] Frame rate in Hz (frames per second) for Rx to Tx transmission. Normally equal to tx_packet_rate. 0: unknown.
+ * @param mode_str Operation mode as human readable string. Radio link dependent. Terminated by NULL if the string length is less than 6 chars and WITHOUT NULL termination if the length is exactly 6 chars - applications have to provide 6+1 bytes storage if the mode is stored as string. Use a zero-length string if not known.
+ * @param band_str Frequency band as human readable string. Radio link dependent. Terminated by NULL if the string length is less than 6 chars and WITHOUT NULL termination if the length is exactly 6 chars - applications have to provide 6+1 bytes storage if the mode is stored as string. Use a zero-length string if not known.
+ * @param tx_ser_data_rate Maximum data rate of serial stream in bytes/s for Tx to Rx transmission. 0: unknown. UINT16_MAX: data rate is 64 KBytes/s or larger.
+ * @param rx_ser_data_rate Maximum data rate of serial stream in bytes/s for Rx to Tx transmission. 0: unknown. UINT16_MAX: data rate is 64 KBytes/s or larger.
+ * @param tx_receive_sensitivity Receive sensitivity of Tx in inverted dBm. 1..255 represents -1..-255 dBm, 0: unknown.
+ * @param rx_receive_sensitivity Receive sensitivity of Rx in inverted dBm. 1..255 represents -1..-255 dBm, 0: unknown.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_mlrs_radio_link_information_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ uint8_t target_system, uint8_t target_component, uint8_t type, uint8_t mode, int8_t tx_power, int8_t rx_power, uint16_t tx_frame_rate, uint16_t rx_frame_rate, const char *mode_str, const char *band_str, uint16_t tx_ser_data_rate, uint16_t rx_ser_data_rate, uint8_t tx_receive_sensitivity, uint8_t rx_receive_sensitivity)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_MLRS_RADIO_LINK_INFORMATION_LEN];
+ _mav_put_uint16_t(buf, 0, tx_frame_rate);
+ _mav_put_uint16_t(buf, 2, rx_frame_rate);
+ _mav_put_uint16_t(buf, 4, tx_ser_data_rate);
+ _mav_put_uint16_t(buf, 6, rx_ser_data_rate);
+ _mav_put_uint8_t(buf, 8, target_system);
+ _mav_put_uint8_t(buf, 9, target_component);
+ _mav_put_uint8_t(buf, 10, type);
+ _mav_put_uint8_t(buf, 11, mode);
+ _mav_put_int8_t(buf, 12, tx_power);
+ _mav_put_int8_t(buf, 13, rx_power);
+ _mav_put_uint8_t(buf, 26, tx_receive_sensitivity);
+ _mav_put_uint8_t(buf, 27, rx_receive_sensitivity);
+ _mav_put_char_array(buf, 14, mode_str, 6);
+ _mav_put_char_array(buf, 20, band_str, 6);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MLRS_RADIO_LINK_INFORMATION_LEN);
+#else
+ mavlink_mlrs_radio_link_information_t packet;
+ packet.tx_frame_rate = tx_frame_rate;
+ packet.rx_frame_rate = rx_frame_rate;
+ packet.tx_ser_data_rate = tx_ser_data_rate;
+ packet.rx_ser_data_rate = rx_ser_data_rate;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.type = type;
+ packet.mode = mode;
+ packet.tx_power = tx_power;
+ packet.rx_power = rx_power;
+ packet.tx_receive_sensitivity = tx_receive_sensitivity;
+ packet.rx_receive_sensitivity = rx_receive_sensitivity;
+ mav_array_memcpy(packet.mode_str, mode_str, sizeof(char)*6);
+ mav_array_memcpy(packet.band_str, band_str, sizeof(char)*6);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MLRS_RADIO_LINK_INFORMATION_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_MLRS_RADIO_LINK_INFORMATION;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_MLRS_RADIO_LINK_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_MLRS_RADIO_LINK_INFORMATION_LEN, MAVLINK_MSG_ID_MLRS_RADIO_LINK_INFORMATION_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_MLRS_RADIO_LINK_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_MLRS_RADIO_LINK_INFORMATION_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a mlrs_radio_link_information 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 target_system System ID (ID of target system, normally flight controller).
+ * @param target_component Component ID (normally 0 for broadcast).
+ * @param type Radio link type. 0: unknown/generic type.
+ * @param mode Operation mode. Radio link dependent. UINT8_MAX: ignore/unknown.
+ * @param tx_power [dBm] Tx transmit power in dBm. INT8_MAX: unknown.
+ * @param rx_power [dBm] Rx transmit power in dBm. INT8_MAX: unknown.
+ * @param tx_frame_rate [Hz] Frame rate in Hz (frames per second) for Tx to Rx transmission. 0: unknown.
+ * @param rx_frame_rate [Hz] Frame rate in Hz (frames per second) for Rx to Tx transmission. Normally equal to tx_packet_rate. 0: unknown.
+ * @param mode_str Operation mode as human readable string. Radio link dependent. Terminated by NULL if the string length is less than 6 chars and WITHOUT NULL termination if the length is exactly 6 chars - applications have to provide 6+1 bytes storage if the mode is stored as string. Use a zero-length string if not known.
+ * @param band_str Frequency band as human readable string. Radio link dependent. Terminated by NULL if the string length is less than 6 chars and WITHOUT NULL termination if the length is exactly 6 chars - applications have to provide 6+1 bytes storage if the mode is stored as string. Use a zero-length string if not known.
+ * @param tx_ser_data_rate Maximum data rate of serial stream in bytes/s for Tx to Rx transmission. 0: unknown. UINT16_MAX: data rate is 64 KBytes/s or larger.
+ * @param rx_ser_data_rate Maximum data rate of serial stream in bytes/s for Rx to Tx transmission. 0: unknown. UINT16_MAX: data rate is 64 KBytes/s or larger.
+ * @param tx_receive_sensitivity Receive sensitivity of Tx in inverted dBm. 1..255 represents -1..-255 dBm, 0: unknown.
+ * @param rx_receive_sensitivity Receive sensitivity of Rx in inverted dBm. 1..255 represents -1..-255 dBm, 0: unknown.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_mlrs_radio_link_information_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint8_t target_system,uint8_t target_component,uint8_t type,uint8_t mode,int8_t tx_power,int8_t rx_power,uint16_t tx_frame_rate,uint16_t rx_frame_rate,const char *mode_str,const char *band_str,uint16_t tx_ser_data_rate,uint16_t rx_ser_data_rate,uint8_t tx_receive_sensitivity,uint8_t rx_receive_sensitivity)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_MLRS_RADIO_LINK_INFORMATION_LEN];
+ _mav_put_uint16_t(buf, 0, tx_frame_rate);
+ _mav_put_uint16_t(buf, 2, rx_frame_rate);
+ _mav_put_uint16_t(buf, 4, tx_ser_data_rate);
+ _mav_put_uint16_t(buf, 6, rx_ser_data_rate);
+ _mav_put_uint8_t(buf, 8, target_system);
+ _mav_put_uint8_t(buf, 9, target_component);
+ _mav_put_uint8_t(buf, 10, type);
+ _mav_put_uint8_t(buf, 11, mode);
+ _mav_put_int8_t(buf, 12, tx_power);
+ _mav_put_int8_t(buf, 13, rx_power);
+ _mav_put_uint8_t(buf, 26, tx_receive_sensitivity);
+ _mav_put_uint8_t(buf, 27, rx_receive_sensitivity);
+ _mav_put_char_array(buf, 14, mode_str, 6);
+ _mav_put_char_array(buf, 20, band_str, 6);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MLRS_RADIO_LINK_INFORMATION_LEN);
+#else
+ mavlink_mlrs_radio_link_information_t packet;
+ packet.tx_frame_rate = tx_frame_rate;
+ packet.rx_frame_rate = rx_frame_rate;
+ packet.tx_ser_data_rate = tx_ser_data_rate;
+ packet.rx_ser_data_rate = rx_ser_data_rate;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.type = type;
+ packet.mode = mode;
+ packet.tx_power = tx_power;
+ packet.rx_power = rx_power;
+ packet.tx_receive_sensitivity = tx_receive_sensitivity;
+ packet.rx_receive_sensitivity = rx_receive_sensitivity;
+ mav_array_assign_char(packet.mode_str, mode_str, 6);
+ mav_array_assign_char(packet.band_str, band_str, 6);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MLRS_RADIO_LINK_INFORMATION_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_MLRS_RADIO_LINK_INFORMATION;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MLRS_RADIO_LINK_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_MLRS_RADIO_LINK_INFORMATION_LEN, MAVLINK_MSG_ID_MLRS_RADIO_LINK_INFORMATION_CRC);
+}
+
+/**
+ * @brief Encode a mlrs_radio_link_information 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 mlrs_radio_link_information C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_mlrs_radio_link_information_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mlrs_radio_link_information_t* mlrs_radio_link_information)
+{
+ return mavlink_msg_mlrs_radio_link_information_pack(system_id, component_id, msg, mlrs_radio_link_information->target_system, mlrs_radio_link_information->target_component, mlrs_radio_link_information->type, mlrs_radio_link_information->mode, mlrs_radio_link_information->tx_power, mlrs_radio_link_information->rx_power, mlrs_radio_link_information->tx_frame_rate, mlrs_radio_link_information->rx_frame_rate, mlrs_radio_link_information->mode_str, mlrs_radio_link_information->band_str, mlrs_radio_link_information->tx_ser_data_rate, mlrs_radio_link_information->rx_ser_data_rate, mlrs_radio_link_information->tx_receive_sensitivity, mlrs_radio_link_information->rx_receive_sensitivity);
+}
+
+/**
+ * @brief Encode a mlrs_radio_link_information 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 mlrs_radio_link_information C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_mlrs_radio_link_information_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mlrs_radio_link_information_t* mlrs_radio_link_information)
+{
+ return mavlink_msg_mlrs_radio_link_information_pack_chan(system_id, component_id, chan, msg, mlrs_radio_link_information->target_system, mlrs_radio_link_information->target_component, mlrs_radio_link_information->type, mlrs_radio_link_information->mode, mlrs_radio_link_information->tx_power, mlrs_radio_link_information->rx_power, mlrs_radio_link_information->tx_frame_rate, mlrs_radio_link_information->rx_frame_rate, mlrs_radio_link_information->mode_str, mlrs_radio_link_information->band_str, mlrs_radio_link_information->tx_ser_data_rate, mlrs_radio_link_information->rx_ser_data_rate, mlrs_radio_link_information->tx_receive_sensitivity, mlrs_radio_link_information->rx_receive_sensitivity);
+}
+
+/**
+ * @brief Encode a mlrs_radio_link_information 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 mlrs_radio_link_information C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_mlrs_radio_link_information_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_mlrs_radio_link_information_t* mlrs_radio_link_information)
+{
+ return mavlink_msg_mlrs_radio_link_information_pack_status(system_id, component_id, _status, msg, mlrs_radio_link_information->target_system, mlrs_radio_link_information->target_component, mlrs_radio_link_information->type, mlrs_radio_link_information->mode, mlrs_radio_link_information->tx_power, mlrs_radio_link_information->rx_power, mlrs_radio_link_information->tx_frame_rate, mlrs_radio_link_information->rx_frame_rate, mlrs_radio_link_information->mode_str, mlrs_radio_link_information->band_str, mlrs_radio_link_information->tx_ser_data_rate, mlrs_radio_link_information->rx_ser_data_rate, mlrs_radio_link_information->tx_receive_sensitivity, mlrs_radio_link_information->rx_receive_sensitivity);
+}
+
+/**
+ * @brief Send a mlrs_radio_link_information message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param target_system System ID (ID of target system, normally flight controller).
+ * @param target_component Component ID (normally 0 for broadcast).
+ * @param type Radio link type. 0: unknown/generic type.
+ * @param mode Operation mode. Radio link dependent. UINT8_MAX: ignore/unknown.
+ * @param tx_power [dBm] Tx transmit power in dBm. INT8_MAX: unknown.
+ * @param rx_power [dBm] Rx transmit power in dBm. INT8_MAX: unknown.
+ * @param tx_frame_rate [Hz] Frame rate in Hz (frames per second) for Tx to Rx transmission. 0: unknown.
+ * @param rx_frame_rate [Hz] Frame rate in Hz (frames per second) for Rx to Tx transmission. Normally equal to tx_packet_rate. 0: unknown.
+ * @param mode_str Operation mode as human readable string. Radio link dependent. Terminated by NULL if the string length is less than 6 chars and WITHOUT NULL termination if the length is exactly 6 chars - applications have to provide 6+1 bytes storage if the mode is stored as string. Use a zero-length string if not known.
+ * @param band_str Frequency band as human readable string. Radio link dependent. Terminated by NULL if the string length is less than 6 chars and WITHOUT NULL termination if the length is exactly 6 chars - applications have to provide 6+1 bytes storage if the mode is stored as string. Use a zero-length string if not known.
+ * @param tx_ser_data_rate Maximum data rate of serial stream in bytes/s for Tx to Rx transmission. 0: unknown. UINT16_MAX: data rate is 64 KBytes/s or larger.
+ * @param rx_ser_data_rate Maximum data rate of serial stream in bytes/s for Rx to Tx transmission. 0: unknown. UINT16_MAX: data rate is 64 KBytes/s or larger.
+ * @param tx_receive_sensitivity Receive sensitivity of Tx in inverted dBm. 1..255 represents -1..-255 dBm, 0: unknown.
+ * @param rx_receive_sensitivity Receive sensitivity of Rx in inverted dBm. 1..255 represents -1..-255 dBm, 0: unknown.
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_mlrs_radio_link_information_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t type, uint8_t mode, int8_t tx_power, int8_t rx_power, uint16_t tx_frame_rate, uint16_t rx_frame_rate, const char *mode_str, const char *band_str, uint16_t tx_ser_data_rate, uint16_t rx_ser_data_rate, uint8_t tx_receive_sensitivity, uint8_t rx_receive_sensitivity)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_MLRS_RADIO_LINK_INFORMATION_LEN];
+ _mav_put_uint16_t(buf, 0, tx_frame_rate);
+ _mav_put_uint16_t(buf, 2, rx_frame_rate);
+ _mav_put_uint16_t(buf, 4, tx_ser_data_rate);
+ _mav_put_uint16_t(buf, 6, rx_ser_data_rate);
+ _mav_put_uint8_t(buf, 8, target_system);
+ _mav_put_uint8_t(buf, 9, target_component);
+ _mav_put_uint8_t(buf, 10, type);
+ _mav_put_uint8_t(buf, 11, mode);
+ _mav_put_int8_t(buf, 12, tx_power);
+ _mav_put_int8_t(buf, 13, rx_power);
+ _mav_put_uint8_t(buf, 26, tx_receive_sensitivity);
+ _mav_put_uint8_t(buf, 27, rx_receive_sensitivity);
+ _mav_put_char_array(buf, 14, mode_str, 6);
+ _mav_put_char_array(buf, 20, band_str, 6);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MLRS_RADIO_LINK_INFORMATION, buf, MAVLINK_MSG_ID_MLRS_RADIO_LINK_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_MLRS_RADIO_LINK_INFORMATION_LEN, MAVLINK_MSG_ID_MLRS_RADIO_LINK_INFORMATION_CRC);
+#else
+ mavlink_mlrs_radio_link_information_t packet;
+ packet.tx_frame_rate = tx_frame_rate;
+ packet.rx_frame_rate = rx_frame_rate;
+ packet.tx_ser_data_rate = tx_ser_data_rate;
+ packet.rx_ser_data_rate = rx_ser_data_rate;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.type = type;
+ packet.mode = mode;
+ packet.tx_power = tx_power;
+ packet.rx_power = rx_power;
+ packet.tx_receive_sensitivity = tx_receive_sensitivity;
+ packet.rx_receive_sensitivity = rx_receive_sensitivity;
+ mav_array_assign_char(packet.mode_str, mode_str, 6);
+ mav_array_assign_char(packet.band_str, band_str, 6);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MLRS_RADIO_LINK_INFORMATION, (const char *)&packet, MAVLINK_MSG_ID_MLRS_RADIO_LINK_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_MLRS_RADIO_LINK_INFORMATION_LEN, MAVLINK_MSG_ID_MLRS_RADIO_LINK_INFORMATION_CRC);
+#endif
+}
+
+/**
+ * @brief Send a mlrs_radio_link_information message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_mlrs_radio_link_information_send_struct(mavlink_channel_t chan, const mavlink_mlrs_radio_link_information_t* mlrs_radio_link_information)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_mlrs_radio_link_information_send(chan, mlrs_radio_link_information->target_system, mlrs_radio_link_information->target_component, mlrs_radio_link_information->type, mlrs_radio_link_information->mode, mlrs_radio_link_information->tx_power, mlrs_radio_link_information->rx_power, mlrs_radio_link_information->tx_frame_rate, mlrs_radio_link_information->rx_frame_rate, mlrs_radio_link_information->mode_str, mlrs_radio_link_information->band_str, mlrs_radio_link_information->tx_ser_data_rate, mlrs_radio_link_information->rx_ser_data_rate, mlrs_radio_link_information->tx_receive_sensitivity, mlrs_radio_link_information->rx_receive_sensitivity);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MLRS_RADIO_LINK_INFORMATION, (const char *)mlrs_radio_link_information, MAVLINK_MSG_ID_MLRS_RADIO_LINK_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_MLRS_RADIO_LINK_INFORMATION_LEN, MAVLINK_MSG_ID_MLRS_RADIO_LINK_INFORMATION_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_MLRS_RADIO_LINK_INFORMATION_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_mlrs_radio_link_information_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t type, uint8_t mode, int8_t tx_power, int8_t rx_power, uint16_t tx_frame_rate, uint16_t rx_frame_rate, const char *mode_str, const char *band_str, uint16_t tx_ser_data_rate, uint16_t rx_ser_data_rate, uint8_t tx_receive_sensitivity, uint8_t rx_receive_sensitivity)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint16_t(buf, 0, tx_frame_rate);
+ _mav_put_uint16_t(buf, 2, rx_frame_rate);
+ _mav_put_uint16_t(buf, 4, tx_ser_data_rate);
+ _mav_put_uint16_t(buf, 6, rx_ser_data_rate);
+ _mav_put_uint8_t(buf, 8, target_system);
+ _mav_put_uint8_t(buf, 9, target_component);
+ _mav_put_uint8_t(buf, 10, type);
+ _mav_put_uint8_t(buf, 11, mode);
+ _mav_put_int8_t(buf, 12, tx_power);
+ _mav_put_int8_t(buf, 13, rx_power);
+ _mav_put_uint8_t(buf, 26, tx_receive_sensitivity);
+ _mav_put_uint8_t(buf, 27, rx_receive_sensitivity);
+ _mav_put_char_array(buf, 14, mode_str, 6);
+ _mav_put_char_array(buf, 20, band_str, 6);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MLRS_RADIO_LINK_INFORMATION, buf, MAVLINK_MSG_ID_MLRS_RADIO_LINK_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_MLRS_RADIO_LINK_INFORMATION_LEN, MAVLINK_MSG_ID_MLRS_RADIO_LINK_INFORMATION_CRC);
+#else
+ mavlink_mlrs_radio_link_information_t *packet = (mavlink_mlrs_radio_link_information_t *)msgbuf;
+ packet->tx_frame_rate = tx_frame_rate;
+ packet->rx_frame_rate = rx_frame_rate;
+ packet->tx_ser_data_rate = tx_ser_data_rate;
+ packet->rx_ser_data_rate = rx_ser_data_rate;
+ packet->target_system = target_system;
+ packet->target_component = target_component;
+ packet->type = type;
+ packet->mode = mode;
+ packet->tx_power = tx_power;
+ packet->rx_power = rx_power;
+ packet->tx_receive_sensitivity = tx_receive_sensitivity;
+ packet->rx_receive_sensitivity = rx_receive_sensitivity;
+ mav_array_assign_char(packet->mode_str, mode_str, 6);
+ mav_array_assign_char(packet->band_str, band_str, 6);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MLRS_RADIO_LINK_INFORMATION, (const char *)packet, MAVLINK_MSG_ID_MLRS_RADIO_LINK_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_MLRS_RADIO_LINK_INFORMATION_LEN, MAVLINK_MSG_ID_MLRS_RADIO_LINK_INFORMATION_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE MLRS_RADIO_LINK_INFORMATION UNPACKING
+
+
+/**
+ * @brief Get field target_system from mlrs_radio_link_information message
+ *
+ * @return System ID (ID of target system, normally flight controller).
+ */
+static inline uint8_t mavlink_msg_mlrs_radio_link_information_get_target_system(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 8);
+}
+
+/**
+ * @brief Get field target_component from mlrs_radio_link_information message
+ *
+ * @return Component ID (normally 0 for broadcast).
+ */
+static inline uint8_t mavlink_msg_mlrs_radio_link_information_get_target_component(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 9);
+}
+
+/**
+ * @brief Get field type from mlrs_radio_link_information message
+ *
+ * @return Radio link type. 0: unknown/generic type.
+ */
+static inline uint8_t mavlink_msg_mlrs_radio_link_information_get_type(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 10);
+}
+
+/**
+ * @brief Get field mode from mlrs_radio_link_information message
+ *
+ * @return Operation mode. Radio link dependent. UINT8_MAX: ignore/unknown.
+ */
+static inline uint8_t mavlink_msg_mlrs_radio_link_information_get_mode(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 11);
+}
+
+/**
+ * @brief Get field tx_power from mlrs_radio_link_information message
+ *
+ * @return [dBm] Tx transmit power in dBm. INT8_MAX: unknown.
+ */
+static inline int8_t mavlink_msg_mlrs_radio_link_information_get_tx_power(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_int8_t(msg, 12);
+}
+
+/**
+ * @brief Get field rx_power from mlrs_radio_link_information message
+ *
+ * @return [dBm] Rx transmit power in dBm. INT8_MAX: unknown.
+ */
+static inline int8_t mavlink_msg_mlrs_radio_link_information_get_rx_power(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_int8_t(msg, 13);
+}
+
+/**
+ * @brief Get field tx_frame_rate from mlrs_radio_link_information message
+ *
+ * @return [Hz] Frame rate in Hz (frames per second) for Tx to Rx transmission. 0: unknown.
+ */
+static inline uint16_t mavlink_msg_mlrs_radio_link_information_get_tx_frame_rate(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 0);
+}
+
+/**
+ * @brief Get field rx_frame_rate from mlrs_radio_link_information message
+ *
+ * @return [Hz] Frame rate in Hz (frames per second) for Rx to Tx transmission. Normally equal to tx_packet_rate. 0: unknown.
+ */
+static inline uint16_t mavlink_msg_mlrs_radio_link_information_get_rx_frame_rate(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 2);
+}
+
+/**
+ * @brief Get field mode_str from mlrs_radio_link_information message
+ *
+ * @return Operation mode as human readable string. Radio link dependent. Terminated by NULL if the string length is less than 6 chars and WITHOUT NULL termination if the length is exactly 6 chars - applications have to provide 6+1 bytes storage if the mode is stored as string. Use a zero-length string if not known.
+ */
+static inline uint16_t mavlink_msg_mlrs_radio_link_information_get_mode_str(const mavlink_message_t* msg, char *mode_str)
+{
+ return _MAV_RETURN_char_array(msg, mode_str, 6, 14);
+}
+
+/**
+ * @brief Get field band_str from mlrs_radio_link_information message
+ *
+ * @return Frequency band as human readable string. Radio link dependent. Terminated by NULL if the string length is less than 6 chars and WITHOUT NULL termination if the length is exactly 6 chars - applications have to provide 6+1 bytes storage if the mode is stored as string. Use a zero-length string if not known.
+ */
+static inline uint16_t mavlink_msg_mlrs_radio_link_information_get_band_str(const mavlink_message_t* msg, char *band_str)
+{
+ return _MAV_RETURN_char_array(msg, band_str, 6, 20);
+}
+
+/**
+ * @brief Get field tx_ser_data_rate from mlrs_radio_link_information message
+ *
+ * @return Maximum data rate of serial stream in bytes/s for Tx to Rx transmission. 0: unknown. UINT16_MAX: data rate is 64 KBytes/s or larger.
+ */
+static inline uint16_t mavlink_msg_mlrs_radio_link_information_get_tx_ser_data_rate(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 4);
+}
+
+/**
+ * @brief Get field rx_ser_data_rate from mlrs_radio_link_information message
+ *
+ * @return Maximum data rate of serial stream in bytes/s for Rx to Tx transmission. 0: unknown. UINT16_MAX: data rate is 64 KBytes/s or larger.
+ */
+static inline uint16_t mavlink_msg_mlrs_radio_link_information_get_rx_ser_data_rate(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 6);
+}
+
+/**
+ * @brief Get field tx_receive_sensitivity from mlrs_radio_link_information message
+ *
+ * @return Receive sensitivity of Tx in inverted dBm. 1..255 represents -1..-255 dBm, 0: unknown.
+ */
+static inline uint8_t mavlink_msg_mlrs_radio_link_information_get_tx_receive_sensitivity(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 26);
+}
+
+/**
+ * @brief Get field rx_receive_sensitivity from mlrs_radio_link_information message
+ *
+ * @return Receive sensitivity of Rx in inverted dBm. 1..255 represents -1..-255 dBm, 0: unknown.
+ */
+static inline uint8_t mavlink_msg_mlrs_radio_link_information_get_rx_receive_sensitivity(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 27);
+}
+
+/**
+ * @brief Decode a mlrs_radio_link_information message into a struct
+ *
+ * @param msg The message to decode
+ * @param mlrs_radio_link_information C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_mlrs_radio_link_information_decode(const mavlink_message_t* msg, mavlink_mlrs_radio_link_information_t* mlrs_radio_link_information)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mlrs_radio_link_information->tx_frame_rate = mavlink_msg_mlrs_radio_link_information_get_tx_frame_rate(msg);
+ mlrs_radio_link_information->rx_frame_rate = mavlink_msg_mlrs_radio_link_information_get_rx_frame_rate(msg);
+ mlrs_radio_link_information->tx_ser_data_rate = mavlink_msg_mlrs_radio_link_information_get_tx_ser_data_rate(msg);
+ mlrs_radio_link_information->rx_ser_data_rate = mavlink_msg_mlrs_radio_link_information_get_rx_ser_data_rate(msg);
+ mlrs_radio_link_information->target_system = mavlink_msg_mlrs_radio_link_information_get_target_system(msg);
+ mlrs_radio_link_information->target_component = mavlink_msg_mlrs_radio_link_information_get_target_component(msg);
+ mlrs_radio_link_information->type = mavlink_msg_mlrs_radio_link_information_get_type(msg);
+ mlrs_radio_link_information->mode = mavlink_msg_mlrs_radio_link_information_get_mode(msg);
+ mlrs_radio_link_information->tx_power = mavlink_msg_mlrs_radio_link_information_get_tx_power(msg);
+ mlrs_radio_link_information->rx_power = mavlink_msg_mlrs_radio_link_information_get_rx_power(msg);
+ mavlink_msg_mlrs_radio_link_information_get_mode_str(msg, mlrs_radio_link_information->mode_str);
+ mavlink_msg_mlrs_radio_link_information_get_band_str(msg, mlrs_radio_link_information->band_str);
+ mlrs_radio_link_information->tx_receive_sensitivity = mavlink_msg_mlrs_radio_link_information_get_tx_receive_sensitivity(msg);
+ mlrs_radio_link_information->rx_receive_sensitivity = mavlink_msg_mlrs_radio_link_information_get_rx_receive_sensitivity(msg);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_MLRS_RADIO_LINK_INFORMATION_LEN? msg->len : MAVLINK_MSG_ID_MLRS_RADIO_LINK_INFORMATION_LEN;
+ memset(mlrs_radio_link_information, 0, MAVLINK_MSG_ID_MLRS_RADIO_LINK_INFORMATION_LEN);
+ memcpy(mlrs_radio_link_information, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/storm32/mavlink_msg_mlrs_radio_link_stats.h b/lib/main/MAVLink/storm32/mavlink_msg_mlrs_radio_link_stats.h
new file mode 100644
index 00000000000..06f7c4a693e
--- /dev/null
+++ b/lib/main/MAVLink/storm32/mavlink_msg_mlrs_radio_link_stats.h
@@ -0,0 +1,680 @@
+#pragma once
+// MESSAGE MLRS_RADIO_LINK_STATS PACKING
+
+#define MAVLINK_MSG_ID_MLRS_RADIO_LINK_STATS 60045
+
+MAVPACKED(
+typedef struct __mavlink_mlrs_radio_link_stats_t {
+ uint16_t flags; /*< Radio link statistics flags.*/
+ uint8_t target_system; /*< System ID (ID of target system, normally flight controller).*/
+ uint8_t target_component; /*< Component ID (normally 0 for broadcast).*/
+ uint8_t rx_LQ_rc; /*< [c%] Link quality of RC data stream from Tx to Rx. Values: 1..100, 0: no link connection, UINT8_MAX: unknown.*/
+ uint8_t rx_LQ_ser; /*< [c%] Link quality of serial MAVLink data stream from Tx to Rx. Values: 1..100, 0: no link connection, UINT8_MAX: unknown.*/
+ uint8_t rx_rssi1; /*< Rssi of antenna 1. 0: no reception, UINT8_MAX: unknown.*/
+ int8_t rx_snr1; /*< Noise on antenna 1. Radio link dependent. INT8_MAX: unknown.*/
+ uint8_t tx_LQ_ser; /*< [c%] Link quality of serial MAVLink data stream from Rx to Tx. Values: 1..100, 0: no link connection, UINT8_MAX: unknown.*/
+ uint8_t tx_rssi1; /*< Rssi of antenna 1. 0: no reception. UINT8_MAX: unknown.*/
+ int8_t tx_snr1; /*< Noise on antenna 1. Radio link dependent. INT8_MAX: unknown.*/
+ uint8_t rx_rssi2; /*< Rssi of antenna 2. 0: no reception, UINT8_MAX: use rx_rssi1 if it is known else unknown.*/
+ int8_t rx_snr2; /*< Noise on antenna 2. Radio link dependent. INT8_MAX: use rx_snr1 if it is known else unknown.*/
+ uint8_t tx_rssi2; /*< Rssi of antenna 2. 0: no reception. UINT8_MAX: use tx_rssi1 if it is known else unknown.*/
+ int8_t tx_snr2; /*< Noise on antenna 2. Radio link dependent. INT8_MAX: use tx_snr1 if it is known else unknown.*/
+ float frequency1; /*< [Hz] Frequency on antenna1 in Hz. 0: unknown.*/
+ float frequency2; /*< [Hz] Frequency on antenna2 in Hz. 0: unknown.*/
+}) mavlink_mlrs_radio_link_stats_t;
+
+#define MAVLINK_MSG_ID_MLRS_RADIO_LINK_STATS_LEN 23
+#define MAVLINK_MSG_ID_MLRS_RADIO_LINK_STATS_MIN_LEN 15
+#define MAVLINK_MSG_ID_60045_LEN 23
+#define MAVLINK_MSG_ID_60045_MIN_LEN 15
+
+#define MAVLINK_MSG_ID_MLRS_RADIO_LINK_STATS_CRC 14
+#define MAVLINK_MSG_ID_60045_CRC 14
+
+
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_MLRS_RADIO_LINK_STATS { \
+ 60045, \
+ "MLRS_RADIO_LINK_STATS", \
+ 16, \
+ { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mlrs_radio_link_stats_t, target_system) }, \
+ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_mlrs_radio_link_stats_t, target_component) }, \
+ { "flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mlrs_radio_link_stats_t, flags) }, \
+ { "rx_LQ_rc", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_mlrs_radio_link_stats_t, rx_LQ_rc) }, \
+ { "rx_LQ_ser", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_mlrs_radio_link_stats_t, rx_LQ_ser) }, \
+ { "rx_rssi1", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_mlrs_radio_link_stats_t, rx_rssi1) }, \
+ { "rx_snr1", NULL, MAVLINK_TYPE_INT8_T, 0, 7, offsetof(mavlink_mlrs_radio_link_stats_t, rx_snr1) }, \
+ { "tx_LQ_ser", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_mlrs_radio_link_stats_t, tx_LQ_ser) }, \
+ { "tx_rssi1", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_mlrs_radio_link_stats_t, tx_rssi1) }, \
+ { "tx_snr1", NULL, MAVLINK_TYPE_INT8_T, 0, 10, offsetof(mavlink_mlrs_radio_link_stats_t, tx_snr1) }, \
+ { "rx_rssi2", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_mlrs_radio_link_stats_t, rx_rssi2) }, \
+ { "rx_snr2", NULL, MAVLINK_TYPE_INT8_T, 0, 12, offsetof(mavlink_mlrs_radio_link_stats_t, rx_snr2) }, \
+ { "tx_rssi2", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_mlrs_radio_link_stats_t, tx_rssi2) }, \
+ { "tx_snr2", NULL, MAVLINK_TYPE_INT8_T, 0, 14, offsetof(mavlink_mlrs_radio_link_stats_t, tx_snr2) }, \
+ { "frequency1", NULL, MAVLINK_TYPE_FLOAT, 0, 15, offsetof(mavlink_mlrs_radio_link_stats_t, frequency1) }, \
+ { "frequency2", NULL, MAVLINK_TYPE_FLOAT, 0, 19, offsetof(mavlink_mlrs_radio_link_stats_t, frequency2) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_MLRS_RADIO_LINK_STATS { \
+ "MLRS_RADIO_LINK_STATS", \
+ 16, \
+ { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mlrs_radio_link_stats_t, target_system) }, \
+ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_mlrs_radio_link_stats_t, target_component) }, \
+ { "flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mlrs_radio_link_stats_t, flags) }, \
+ { "rx_LQ_rc", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_mlrs_radio_link_stats_t, rx_LQ_rc) }, \
+ { "rx_LQ_ser", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_mlrs_radio_link_stats_t, rx_LQ_ser) }, \
+ { "rx_rssi1", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_mlrs_radio_link_stats_t, rx_rssi1) }, \
+ { "rx_snr1", NULL, MAVLINK_TYPE_INT8_T, 0, 7, offsetof(mavlink_mlrs_radio_link_stats_t, rx_snr1) }, \
+ { "tx_LQ_ser", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_mlrs_radio_link_stats_t, tx_LQ_ser) }, \
+ { "tx_rssi1", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_mlrs_radio_link_stats_t, tx_rssi1) }, \
+ { "tx_snr1", NULL, MAVLINK_TYPE_INT8_T, 0, 10, offsetof(mavlink_mlrs_radio_link_stats_t, tx_snr1) }, \
+ { "rx_rssi2", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_mlrs_radio_link_stats_t, rx_rssi2) }, \
+ { "rx_snr2", NULL, MAVLINK_TYPE_INT8_T, 0, 12, offsetof(mavlink_mlrs_radio_link_stats_t, rx_snr2) }, \
+ { "tx_rssi2", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_mlrs_radio_link_stats_t, tx_rssi2) }, \
+ { "tx_snr2", NULL, MAVLINK_TYPE_INT8_T, 0, 14, offsetof(mavlink_mlrs_radio_link_stats_t, tx_snr2) }, \
+ { "frequency1", NULL, MAVLINK_TYPE_FLOAT, 0, 15, offsetof(mavlink_mlrs_radio_link_stats_t, frequency1) }, \
+ { "frequency2", NULL, MAVLINK_TYPE_FLOAT, 0, 19, offsetof(mavlink_mlrs_radio_link_stats_t, frequency2) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a mlrs_radio_link_stats 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 target_system System ID (ID of target system, normally flight controller).
+ * @param target_component Component ID (normally 0 for broadcast).
+ * @param flags Radio link statistics flags.
+ * @param rx_LQ_rc [c%] Link quality of RC data stream from Tx to Rx. Values: 1..100, 0: no link connection, UINT8_MAX: unknown.
+ * @param rx_LQ_ser [c%] Link quality of serial MAVLink data stream from Tx to Rx. Values: 1..100, 0: no link connection, UINT8_MAX: unknown.
+ * @param rx_rssi1 Rssi of antenna 1. 0: no reception, UINT8_MAX: unknown.
+ * @param rx_snr1 Noise on antenna 1. Radio link dependent. INT8_MAX: unknown.
+ * @param tx_LQ_ser [c%] Link quality of serial MAVLink data stream from Rx to Tx. Values: 1..100, 0: no link connection, UINT8_MAX: unknown.
+ * @param tx_rssi1 Rssi of antenna 1. 0: no reception. UINT8_MAX: unknown.
+ * @param tx_snr1 Noise on antenna 1. Radio link dependent. INT8_MAX: unknown.
+ * @param rx_rssi2 Rssi of antenna 2. 0: no reception, UINT8_MAX: use rx_rssi1 if it is known else unknown.
+ * @param rx_snr2 Noise on antenna 2. Radio link dependent. INT8_MAX: use rx_snr1 if it is known else unknown.
+ * @param tx_rssi2 Rssi of antenna 2. 0: no reception. UINT8_MAX: use tx_rssi1 if it is known else unknown.
+ * @param tx_snr2 Noise on antenna 2. Radio link dependent. INT8_MAX: use tx_snr1 if it is known else unknown.
+ * @param frequency1 [Hz] Frequency on antenna1 in Hz. 0: unknown.
+ * @param frequency2 [Hz] Frequency on antenna2 in Hz. 0: unknown.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_mlrs_radio_link_stats_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint8_t target_system, uint8_t target_component, uint16_t flags, uint8_t rx_LQ_rc, uint8_t rx_LQ_ser, uint8_t rx_rssi1, int8_t rx_snr1, uint8_t tx_LQ_ser, uint8_t tx_rssi1, int8_t tx_snr1, uint8_t rx_rssi2, int8_t rx_snr2, uint8_t tx_rssi2, int8_t tx_snr2, float frequency1, float frequency2)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_MLRS_RADIO_LINK_STATS_LEN];
+ _mav_put_uint16_t(buf, 0, flags);
+ _mav_put_uint8_t(buf, 2, target_system);
+ _mav_put_uint8_t(buf, 3, target_component);
+ _mav_put_uint8_t(buf, 4, rx_LQ_rc);
+ _mav_put_uint8_t(buf, 5, rx_LQ_ser);
+ _mav_put_uint8_t(buf, 6, rx_rssi1);
+ _mav_put_int8_t(buf, 7, rx_snr1);
+ _mav_put_uint8_t(buf, 8, tx_LQ_ser);
+ _mav_put_uint8_t(buf, 9, tx_rssi1);
+ _mav_put_int8_t(buf, 10, tx_snr1);
+ _mav_put_uint8_t(buf, 11, rx_rssi2);
+ _mav_put_int8_t(buf, 12, rx_snr2);
+ _mav_put_uint8_t(buf, 13, tx_rssi2);
+ _mav_put_int8_t(buf, 14, tx_snr2);
+ _mav_put_float(buf, 15, frequency1);
+ _mav_put_float(buf, 19, frequency2);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MLRS_RADIO_LINK_STATS_LEN);
+#else
+ mavlink_mlrs_radio_link_stats_t packet;
+ packet.flags = flags;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.rx_LQ_rc = rx_LQ_rc;
+ packet.rx_LQ_ser = rx_LQ_ser;
+ packet.rx_rssi1 = rx_rssi1;
+ packet.rx_snr1 = rx_snr1;
+ packet.tx_LQ_ser = tx_LQ_ser;
+ packet.tx_rssi1 = tx_rssi1;
+ packet.tx_snr1 = tx_snr1;
+ packet.rx_rssi2 = rx_rssi2;
+ packet.rx_snr2 = rx_snr2;
+ packet.tx_rssi2 = tx_rssi2;
+ packet.tx_snr2 = tx_snr2;
+ packet.frequency1 = frequency1;
+ packet.frequency2 = frequency2;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MLRS_RADIO_LINK_STATS_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_MLRS_RADIO_LINK_STATS;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MLRS_RADIO_LINK_STATS_MIN_LEN, MAVLINK_MSG_ID_MLRS_RADIO_LINK_STATS_LEN, MAVLINK_MSG_ID_MLRS_RADIO_LINK_STATS_CRC);
+}
+
+/**
+ * @brief Pack a mlrs_radio_link_stats 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 target_system System ID (ID of target system, normally flight controller).
+ * @param target_component Component ID (normally 0 for broadcast).
+ * @param flags Radio link statistics flags.
+ * @param rx_LQ_rc [c%] Link quality of RC data stream from Tx to Rx. Values: 1..100, 0: no link connection, UINT8_MAX: unknown.
+ * @param rx_LQ_ser [c%] Link quality of serial MAVLink data stream from Tx to Rx. Values: 1..100, 0: no link connection, UINT8_MAX: unknown.
+ * @param rx_rssi1 Rssi of antenna 1. 0: no reception, UINT8_MAX: unknown.
+ * @param rx_snr1 Noise on antenna 1. Radio link dependent. INT8_MAX: unknown.
+ * @param tx_LQ_ser [c%] Link quality of serial MAVLink data stream from Rx to Tx. Values: 1..100, 0: no link connection, UINT8_MAX: unknown.
+ * @param tx_rssi1 Rssi of antenna 1. 0: no reception. UINT8_MAX: unknown.
+ * @param tx_snr1 Noise on antenna 1. Radio link dependent. INT8_MAX: unknown.
+ * @param rx_rssi2 Rssi of antenna 2. 0: no reception, UINT8_MAX: use rx_rssi1 if it is known else unknown.
+ * @param rx_snr2 Noise on antenna 2. Radio link dependent. INT8_MAX: use rx_snr1 if it is known else unknown.
+ * @param tx_rssi2 Rssi of antenna 2. 0: no reception. UINT8_MAX: use tx_rssi1 if it is known else unknown.
+ * @param tx_snr2 Noise on antenna 2. Radio link dependent. INT8_MAX: use tx_snr1 if it is known else unknown.
+ * @param frequency1 [Hz] Frequency on antenna1 in Hz. 0: unknown.
+ * @param frequency2 [Hz] Frequency on antenna2 in Hz. 0: unknown.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_mlrs_radio_link_stats_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ uint8_t target_system, uint8_t target_component, uint16_t flags, uint8_t rx_LQ_rc, uint8_t rx_LQ_ser, uint8_t rx_rssi1, int8_t rx_snr1, uint8_t tx_LQ_ser, uint8_t tx_rssi1, int8_t tx_snr1, uint8_t rx_rssi2, int8_t rx_snr2, uint8_t tx_rssi2, int8_t tx_snr2, float frequency1, float frequency2)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_MLRS_RADIO_LINK_STATS_LEN];
+ _mav_put_uint16_t(buf, 0, flags);
+ _mav_put_uint8_t(buf, 2, target_system);
+ _mav_put_uint8_t(buf, 3, target_component);
+ _mav_put_uint8_t(buf, 4, rx_LQ_rc);
+ _mav_put_uint8_t(buf, 5, rx_LQ_ser);
+ _mav_put_uint8_t(buf, 6, rx_rssi1);
+ _mav_put_int8_t(buf, 7, rx_snr1);
+ _mav_put_uint8_t(buf, 8, tx_LQ_ser);
+ _mav_put_uint8_t(buf, 9, tx_rssi1);
+ _mav_put_int8_t(buf, 10, tx_snr1);
+ _mav_put_uint8_t(buf, 11, rx_rssi2);
+ _mav_put_int8_t(buf, 12, rx_snr2);
+ _mav_put_uint8_t(buf, 13, tx_rssi2);
+ _mav_put_int8_t(buf, 14, tx_snr2);
+ _mav_put_float(buf, 15, frequency1);
+ _mav_put_float(buf, 19, frequency2);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MLRS_RADIO_LINK_STATS_LEN);
+#else
+ mavlink_mlrs_radio_link_stats_t packet;
+ packet.flags = flags;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.rx_LQ_rc = rx_LQ_rc;
+ packet.rx_LQ_ser = rx_LQ_ser;
+ packet.rx_rssi1 = rx_rssi1;
+ packet.rx_snr1 = rx_snr1;
+ packet.tx_LQ_ser = tx_LQ_ser;
+ packet.tx_rssi1 = tx_rssi1;
+ packet.tx_snr1 = tx_snr1;
+ packet.rx_rssi2 = rx_rssi2;
+ packet.rx_snr2 = rx_snr2;
+ packet.tx_rssi2 = tx_rssi2;
+ packet.tx_snr2 = tx_snr2;
+ packet.frequency1 = frequency1;
+ packet.frequency2 = frequency2;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MLRS_RADIO_LINK_STATS_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_MLRS_RADIO_LINK_STATS;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_MLRS_RADIO_LINK_STATS_MIN_LEN, MAVLINK_MSG_ID_MLRS_RADIO_LINK_STATS_LEN, MAVLINK_MSG_ID_MLRS_RADIO_LINK_STATS_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_MLRS_RADIO_LINK_STATS_MIN_LEN, MAVLINK_MSG_ID_MLRS_RADIO_LINK_STATS_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a mlrs_radio_link_stats 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 target_system System ID (ID of target system, normally flight controller).
+ * @param target_component Component ID (normally 0 for broadcast).
+ * @param flags Radio link statistics flags.
+ * @param rx_LQ_rc [c%] Link quality of RC data stream from Tx to Rx. Values: 1..100, 0: no link connection, UINT8_MAX: unknown.
+ * @param rx_LQ_ser [c%] Link quality of serial MAVLink data stream from Tx to Rx. Values: 1..100, 0: no link connection, UINT8_MAX: unknown.
+ * @param rx_rssi1 Rssi of antenna 1. 0: no reception, UINT8_MAX: unknown.
+ * @param rx_snr1 Noise on antenna 1. Radio link dependent. INT8_MAX: unknown.
+ * @param tx_LQ_ser [c%] Link quality of serial MAVLink data stream from Rx to Tx. Values: 1..100, 0: no link connection, UINT8_MAX: unknown.
+ * @param tx_rssi1 Rssi of antenna 1. 0: no reception. UINT8_MAX: unknown.
+ * @param tx_snr1 Noise on antenna 1. Radio link dependent. INT8_MAX: unknown.
+ * @param rx_rssi2 Rssi of antenna 2. 0: no reception, UINT8_MAX: use rx_rssi1 if it is known else unknown.
+ * @param rx_snr2 Noise on antenna 2. Radio link dependent. INT8_MAX: use rx_snr1 if it is known else unknown.
+ * @param tx_rssi2 Rssi of antenna 2. 0: no reception. UINT8_MAX: use tx_rssi1 if it is known else unknown.
+ * @param tx_snr2 Noise on antenna 2. Radio link dependent. INT8_MAX: use tx_snr1 if it is known else unknown.
+ * @param frequency1 [Hz] Frequency on antenna1 in Hz. 0: unknown.
+ * @param frequency2 [Hz] Frequency on antenna2 in Hz. 0: unknown.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_mlrs_radio_link_stats_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint8_t target_system,uint8_t target_component,uint16_t flags,uint8_t rx_LQ_rc,uint8_t rx_LQ_ser,uint8_t rx_rssi1,int8_t rx_snr1,uint8_t tx_LQ_ser,uint8_t tx_rssi1,int8_t tx_snr1,uint8_t rx_rssi2,int8_t rx_snr2,uint8_t tx_rssi2,int8_t tx_snr2,float frequency1,float frequency2)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_MLRS_RADIO_LINK_STATS_LEN];
+ _mav_put_uint16_t(buf, 0, flags);
+ _mav_put_uint8_t(buf, 2, target_system);
+ _mav_put_uint8_t(buf, 3, target_component);
+ _mav_put_uint8_t(buf, 4, rx_LQ_rc);
+ _mav_put_uint8_t(buf, 5, rx_LQ_ser);
+ _mav_put_uint8_t(buf, 6, rx_rssi1);
+ _mav_put_int8_t(buf, 7, rx_snr1);
+ _mav_put_uint8_t(buf, 8, tx_LQ_ser);
+ _mav_put_uint8_t(buf, 9, tx_rssi1);
+ _mav_put_int8_t(buf, 10, tx_snr1);
+ _mav_put_uint8_t(buf, 11, rx_rssi2);
+ _mav_put_int8_t(buf, 12, rx_snr2);
+ _mav_put_uint8_t(buf, 13, tx_rssi2);
+ _mav_put_int8_t(buf, 14, tx_snr2);
+ _mav_put_float(buf, 15, frequency1);
+ _mav_put_float(buf, 19, frequency2);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MLRS_RADIO_LINK_STATS_LEN);
+#else
+ mavlink_mlrs_radio_link_stats_t packet;
+ packet.flags = flags;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.rx_LQ_rc = rx_LQ_rc;
+ packet.rx_LQ_ser = rx_LQ_ser;
+ packet.rx_rssi1 = rx_rssi1;
+ packet.rx_snr1 = rx_snr1;
+ packet.tx_LQ_ser = tx_LQ_ser;
+ packet.tx_rssi1 = tx_rssi1;
+ packet.tx_snr1 = tx_snr1;
+ packet.rx_rssi2 = rx_rssi2;
+ packet.rx_snr2 = rx_snr2;
+ packet.tx_rssi2 = tx_rssi2;
+ packet.tx_snr2 = tx_snr2;
+ packet.frequency1 = frequency1;
+ packet.frequency2 = frequency2;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MLRS_RADIO_LINK_STATS_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_MLRS_RADIO_LINK_STATS;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MLRS_RADIO_LINK_STATS_MIN_LEN, MAVLINK_MSG_ID_MLRS_RADIO_LINK_STATS_LEN, MAVLINK_MSG_ID_MLRS_RADIO_LINK_STATS_CRC);
+}
+
+/**
+ * @brief Encode a mlrs_radio_link_stats 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 mlrs_radio_link_stats C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_mlrs_radio_link_stats_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mlrs_radio_link_stats_t* mlrs_radio_link_stats)
+{
+ return mavlink_msg_mlrs_radio_link_stats_pack(system_id, component_id, msg, mlrs_radio_link_stats->target_system, mlrs_radio_link_stats->target_component, mlrs_radio_link_stats->flags, mlrs_radio_link_stats->rx_LQ_rc, mlrs_radio_link_stats->rx_LQ_ser, mlrs_radio_link_stats->rx_rssi1, mlrs_radio_link_stats->rx_snr1, mlrs_radio_link_stats->tx_LQ_ser, mlrs_radio_link_stats->tx_rssi1, mlrs_radio_link_stats->tx_snr1, mlrs_radio_link_stats->rx_rssi2, mlrs_radio_link_stats->rx_snr2, mlrs_radio_link_stats->tx_rssi2, mlrs_radio_link_stats->tx_snr2, mlrs_radio_link_stats->frequency1, mlrs_radio_link_stats->frequency2);
+}
+
+/**
+ * @brief Encode a mlrs_radio_link_stats 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 mlrs_radio_link_stats C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_mlrs_radio_link_stats_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mlrs_radio_link_stats_t* mlrs_radio_link_stats)
+{
+ return mavlink_msg_mlrs_radio_link_stats_pack_chan(system_id, component_id, chan, msg, mlrs_radio_link_stats->target_system, mlrs_radio_link_stats->target_component, mlrs_radio_link_stats->flags, mlrs_radio_link_stats->rx_LQ_rc, mlrs_radio_link_stats->rx_LQ_ser, mlrs_radio_link_stats->rx_rssi1, mlrs_radio_link_stats->rx_snr1, mlrs_radio_link_stats->tx_LQ_ser, mlrs_radio_link_stats->tx_rssi1, mlrs_radio_link_stats->tx_snr1, mlrs_radio_link_stats->rx_rssi2, mlrs_radio_link_stats->rx_snr2, mlrs_radio_link_stats->tx_rssi2, mlrs_radio_link_stats->tx_snr2, mlrs_radio_link_stats->frequency1, mlrs_radio_link_stats->frequency2);
+}
+
+/**
+ * @brief Encode a mlrs_radio_link_stats 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 mlrs_radio_link_stats C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_mlrs_radio_link_stats_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_mlrs_radio_link_stats_t* mlrs_radio_link_stats)
+{
+ return mavlink_msg_mlrs_radio_link_stats_pack_status(system_id, component_id, _status, msg, mlrs_radio_link_stats->target_system, mlrs_radio_link_stats->target_component, mlrs_radio_link_stats->flags, mlrs_radio_link_stats->rx_LQ_rc, mlrs_radio_link_stats->rx_LQ_ser, mlrs_radio_link_stats->rx_rssi1, mlrs_radio_link_stats->rx_snr1, mlrs_radio_link_stats->tx_LQ_ser, mlrs_radio_link_stats->tx_rssi1, mlrs_radio_link_stats->tx_snr1, mlrs_radio_link_stats->rx_rssi2, mlrs_radio_link_stats->rx_snr2, mlrs_radio_link_stats->tx_rssi2, mlrs_radio_link_stats->tx_snr2, mlrs_radio_link_stats->frequency1, mlrs_radio_link_stats->frequency2);
+}
+
+/**
+ * @brief Send a mlrs_radio_link_stats message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param target_system System ID (ID of target system, normally flight controller).
+ * @param target_component Component ID (normally 0 for broadcast).
+ * @param flags Radio link statistics flags.
+ * @param rx_LQ_rc [c%] Link quality of RC data stream from Tx to Rx. Values: 1..100, 0: no link connection, UINT8_MAX: unknown.
+ * @param rx_LQ_ser [c%] Link quality of serial MAVLink data stream from Tx to Rx. Values: 1..100, 0: no link connection, UINT8_MAX: unknown.
+ * @param rx_rssi1 Rssi of antenna 1. 0: no reception, UINT8_MAX: unknown.
+ * @param rx_snr1 Noise on antenna 1. Radio link dependent. INT8_MAX: unknown.
+ * @param tx_LQ_ser [c%] Link quality of serial MAVLink data stream from Rx to Tx. Values: 1..100, 0: no link connection, UINT8_MAX: unknown.
+ * @param tx_rssi1 Rssi of antenna 1. 0: no reception. UINT8_MAX: unknown.
+ * @param tx_snr1 Noise on antenna 1. Radio link dependent. INT8_MAX: unknown.
+ * @param rx_rssi2 Rssi of antenna 2. 0: no reception, UINT8_MAX: use rx_rssi1 if it is known else unknown.
+ * @param rx_snr2 Noise on antenna 2. Radio link dependent. INT8_MAX: use rx_snr1 if it is known else unknown.
+ * @param tx_rssi2 Rssi of antenna 2. 0: no reception. UINT8_MAX: use tx_rssi1 if it is known else unknown.
+ * @param tx_snr2 Noise on antenna 2. Radio link dependent. INT8_MAX: use tx_snr1 if it is known else unknown.
+ * @param frequency1 [Hz] Frequency on antenna1 in Hz. 0: unknown.
+ * @param frequency2 [Hz] Frequency on antenna2 in Hz. 0: unknown.
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_mlrs_radio_link_stats_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t flags, uint8_t rx_LQ_rc, uint8_t rx_LQ_ser, uint8_t rx_rssi1, int8_t rx_snr1, uint8_t tx_LQ_ser, uint8_t tx_rssi1, int8_t tx_snr1, uint8_t rx_rssi2, int8_t rx_snr2, uint8_t tx_rssi2, int8_t tx_snr2, float frequency1, float frequency2)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_MLRS_RADIO_LINK_STATS_LEN];
+ _mav_put_uint16_t(buf, 0, flags);
+ _mav_put_uint8_t(buf, 2, target_system);
+ _mav_put_uint8_t(buf, 3, target_component);
+ _mav_put_uint8_t(buf, 4, rx_LQ_rc);
+ _mav_put_uint8_t(buf, 5, rx_LQ_ser);
+ _mav_put_uint8_t(buf, 6, rx_rssi1);
+ _mav_put_int8_t(buf, 7, rx_snr1);
+ _mav_put_uint8_t(buf, 8, tx_LQ_ser);
+ _mav_put_uint8_t(buf, 9, tx_rssi1);
+ _mav_put_int8_t(buf, 10, tx_snr1);
+ _mav_put_uint8_t(buf, 11, rx_rssi2);
+ _mav_put_int8_t(buf, 12, rx_snr2);
+ _mav_put_uint8_t(buf, 13, tx_rssi2);
+ _mav_put_int8_t(buf, 14, tx_snr2);
+ _mav_put_float(buf, 15, frequency1);
+ _mav_put_float(buf, 19, frequency2);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MLRS_RADIO_LINK_STATS, buf, MAVLINK_MSG_ID_MLRS_RADIO_LINK_STATS_MIN_LEN, MAVLINK_MSG_ID_MLRS_RADIO_LINK_STATS_LEN, MAVLINK_MSG_ID_MLRS_RADIO_LINK_STATS_CRC);
+#else
+ mavlink_mlrs_radio_link_stats_t packet;
+ packet.flags = flags;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.rx_LQ_rc = rx_LQ_rc;
+ packet.rx_LQ_ser = rx_LQ_ser;
+ packet.rx_rssi1 = rx_rssi1;
+ packet.rx_snr1 = rx_snr1;
+ packet.tx_LQ_ser = tx_LQ_ser;
+ packet.tx_rssi1 = tx_rssi1;
+ packet.tx_snr1 = tx_snr1;
+ packet.rx_rssi2 = rx_rssi2;
+ packet.rx_snr2 = rx_snr2;
+ packet.tx_rssi2 = tx_rssi2;
+ packet.tx_snr2 = tx_snr2;
+ packet.frequency1 = frequency1;
+ packet.frequency2 = frequency2;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MLRS_RADIO_LINK_STATS, (const char *)&packet, MAVLINK_MSG_ID_MLRS_RADIO_LINK_STATS_MIN_LEN, MAVLINK_MSG_ID_MLRS_RADIO_LINK_STATS_LEN, MAVLINK_MSG_ID_MLRS_RADIO_LINK_STATS_CRC);
+#endif
+}
+
+/**
+ * @brief Send a mlrs_radio_link_stats message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_mlrs_radio_link_stats_send_struct(mavlink_channel_t chan, const mavlink_mlrs_radio_link_stats_t* mlrs_radio_link_stats)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_mlrs_radio_link_stats_send(chan, mlrs_radio_link_stats->target_system, mlrs_radio_link_stats->target_component, mlrs_radio_link_stats->flags, mlrs_radio_link_stats->rx_LQ_rc, mlrs_radio_link_stats->rx_LQ_ser, mlrs_radio_link_stats->rx_rssi1, mlrs_radio_link_stats->rx_snr1, mlrs_radio_link_stats->tx_LQ_ser, mlrs_radio_link_stats->tx_rssi1, mlrs_radio_link_stats->tx_snr1, mlrs_radio_link_stats->rx_rssi2, mlrs_radio_link_stats->rx_snr2, mlrs_radio_link_stats->tx_rssi2, mlrs_radio_link_stats->tx_snr2, mlrs_radio_link_stats->frequency1, mlrs_radio_link_stats->frequency2);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MLRS_RADIO_LINK_STATS, (const char *)mlrs_radio_link_stats, MAVLINK_MSG_ID_MLRS_RADIO_LINK_STATS_MIN_LEN, MAVLINK_MSG_ID_MLRS_RADIO_LINK_STATS_LEN, MAVLINK_MSG_ID_MLRS_RADIO_LINK_STATS_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_MLRS_RADIO_LINK_STATS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_mlrs_radio_link_stats_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t flags, uint8_t rx_LQ_rc, uint8_t rx_LQ_ser, uint8_t rx_rssi1, int8_t rx_snr1, uint8_t tx_LQ_ser, uint8_t tx_rssi1, int8_t tx_snr1, uint8_t rx_rssi2, int8_t rx_snr2, uint8_t tx_rssi2, int8_t tx_snr2, float frequency1, float frequency2)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint16_t(buf, 0, flags);
+ _mav_put_uint8_t(buf, 2, target_system);
+ _mav_put_uint8_t(buf, 3, target_component);
+ _mav_put_uint8_t(buf, 4, rx_LQ_rc);
+ _mav_put_uint8_t(buf, 5, rx_LQ_ser);
+ _mav_put_uint8_t(buf, 6, rx_rssi1);
+ _mav_put_int8_t(buf, 7, rx_snr1);
+ _mav_put_uint8_t(buf, 8, tx_LQ_ser);
+ _mav_put_uint8_t(buf, 9, tx_rssi1);
+ _mav_put_int8_t(buf, 10, tx_snr1);
+ _mav_put_uint8_t(buf, 11, rx_rssi2);
+ _mav_put_int8_t(buf, 12, rx_snr2);
+ _mav_put_uint8_t(buf, 13, tx_rssi2);
+ _mav_put_int8_t(buf, 14, tx_snr2);
+ _mav_put_float(buf, 15, frequency1);
+ _mav_put_float(buf, 19, frequency2);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MLRS_RADIO_LINK_STATS, buf, MAVLINK_MSG_ID_MLRS_RADIO_LINK_STATS_MIN_LEN, MAVLINK_MSG_ID_MLRS_RADIO_LINK_STATS_LEN, MAVLINK_MSG_ID_MLRS_RADIO_LINK_STATS_CRC);
+#else
+ mavlink_mlrs_radio_link_stats_t *packet = (mavlink_mlrs_radio_link_stats_t *)msgbuf;
+ packet->flags = flags;
+ packet->target_system = target_system;
+ packet->target_component = target_component;
+ packet->rx_LQ_rc = rx_LQ_rc;
+ packet->rx_LQ_ser = rx_LQ_ser;
+ packet->rx_rssi1 = rx_rssi1;
+ packet->rx_snr1 = rx_snr1;
+ packet->tx_LQ_ser = tx_LQ_ser;
+ packet->tx_rssi1 = tx_rssi1;
+ packet->tx_snr1 = tx_snr1;
+ packet->rx_rssi2 = rx_rssi2;
+ packet->rx_snr2 = rx_snr2;
+ packet->tx_rssi2 = tx_rssi2;
+ packet->tx_snr2 = tx_snr2;
+ packet->frequency1 = frequency1;
+ packet->frequency2 = frequency2;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MLRS_RADIO_LINK_STATS, (const char *)packet, MAVLINK_MSG_ID_MLRS_RADIO_LINK_STATS_MIN_LEN, MAVLINK_MSG_ID_MLRS_RADIO_LINK_STATS_LEN, MAVLINK_MSG_ID_MLRS_RADIO_LINK_STATS_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE MLRS_RADIO_LINK_STATS UNPACKING
+
+
+/**
+ * @brief Get field target_system from mlrs_radio_link_stats message
+ *
+ * @return System ID (ID of target system, normally flight controller).
+ */
+static inline uint8_t mavlink_msg_mlrs_radio_link_stats_get_target_system(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 2);
+}
+
+/**
+ * @brief Get field target_component from mlrs_radio_link_stats message
+ *
+ * @return Component ID (normally 0 for broadcast).
+ */
+static inline uint8_t mavlink_msg_mlrs_radio_link_stats_get_target_component(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 3);
+}
+
+/**
+ * @brief Get field flags from mlrs_radio_link_stats message
+ *
+ * @return Radio link statistics flags.
+ */
+static inline uint16_t mavlink_msg_mlrs_radio_link_stats_get_flags(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 0);
+}
+
+/**
+ * @brief Get field rx_LQ_rc from mlrs_radio_link_stats message
+ *
+ * @return [c%] Link quality of RC data stream from Tx to Rx. Values: 1..100, 0: no link connection, UINT8_MAX: unknown.
+ */
+static inline uint8_t mavlink_msg_mlrs_radio_link_stats_get_rx_LQ_rc(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 4);
+}
+
+/**
+ * @brief Get field rx_LQ_ser from mlrs_radio_link_stats message
+ *
+ * @return [c%] Link quality of serial MAVLink data stream from Tx to Rx. Values: 1..100, 0: no link connection, UINT8_MAX: unknown.
+ */
+static inline uint8_t mavlink_msg_mlrs_radio_link_stats_get_rx_LQ_ser(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 5);
+}
+
+/**
+ * @brief Get field rx_rssi1 from mlrs_radio_link_stats message
+ *
+ * @return Rssi of antenna 1. 0: no reception, UINT8_MAX: unknown.
+ */
+static inline uint8_t mavlink_msg_mlrs_radio_link_stats_get_rx_rssi1(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 6);
+}
+
+/**
+ * @brief Get field rx_snr1 from mlrs_radio_link_stats message
+ *
+ * @return Noise on antenna 1. Radio link dependent. INT8_MAX: unknown.
+ */
+static inline int8_t mavlink_msg_mlrs_radio_link_stats_get_rx_snr1(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_int8_t(msg, 7);
+}
+
+/**
+ * @brief Get field tx_LQ_ser from mlrs_radio_link_stats message
+ *
+ * @return [c%] Link quality of serial MAVLink data stream from Rx to Tx. Values: 1..100, 0: no link connection, UINT8_MAX: unknown.
+ */
+static inline uint8_t mavlink_msg_mlrs_radio_link_stats_get_tx_LQ_ser(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 8);
+}
+
+/**
+ * @brief Get field tx_rssi1 from mlrs_radio_link_stats message
+ *
+ * @return Rssi of antenna 1. 0: no reception. UINT8_MAX: unknown.
+ */
+static inline uint8_t mavlink_msg_mlrs_radio_link_stats_get_tx_rssi1(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 9);
+}
+
+/**
+ * @brief Get field tx_snr1 from mlrs_radio_link_stats message
+ *
+ * @return Noise on antenna 1. Radio link dependent. INT8_MAX: unknown.
+ */
+static inline int8_t mavlink_msg_mlrs_radio_link_stats_get_tx_snr1(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_int8_t(msg, 10);
+}
+
+/**
+ * @brief Get field rx_rssi2 from mlrs_radio_link_stats message
+ *
+ * @return Rssi of antenna 2. 0: no reception, UINT8_MAX: use rx_rssi1 if it is known else unknown.
+ */
+static inline uint8_t mavlink_msg_mlrs_radio_link_stats_get_rx_rssi2(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 11);
+}
+
+/**
+ * @brief Get field rx_snr2 from mlrs_radio_link_stats message
+ *
+ * @return Noise on antenna 2. Radio link dependent. INT8_MAX: use rx_snr1 if it is known else unknown.
+ */
+static inline int8_t mavlink_msg_mlrs_radio_link_stats_get_rx_snr2(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_int8_t(msg, 12);
+}
+
+/**
+ * @brief Get field tx_rssi2 from mlrs_radio_link_stats message
+ *
+ * @return Rssi of antenna 2. 0: no reception. UINT8_MAX: use tx_rssi1 if it is known else unknown.
+ */
+static inline uint8_t mavlink_msg_mlrs_radio_link_stats_get_tx_rssi2(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 13);
+}
+
+/**
+ * @brief Get field tx_snr2 from mlrs_radio_link_stats message
+ *
+ * @return Noise on antenna 2. Radio link dependent. INT8_MAX: use tx_snr1 if it is known else unknown.
+ */
+static inline int8_t mavlink_msg_mlrs_radio_link_stats_get_tx_snr2(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_int8_t(msg, 14);
+}
+
+/**
+ * @brief Get field frequency1 from mlrs_radio_link_stats message
+ *
+ * @return [Hz] Frequency on antenna1 in Hz. 0: unknown.
+ */
+static inline float mavlink_msg_mlrs_radio_link_stats_get_frequency1(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 15);
+}
+
+/**
+ * @brief Get field frequency2 from mlrs_radio_link_stats message
+ *
+ * @return [Hz] Frequency on antenna2 in Hz. 0: unknown.
+ */
+static inline float mavlink_msg_mlrs_radio_link_stats_get_frequency2(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 19);
+}
+
+/**
+ * @brief Decode a mlrs_radio_link_stats message into a struct
+ *
+ * @param msg The message to decode
+ * @param mlrs_radio_link_stats C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_mlrs_radio_link_stats_decode(const mavlink_message_t* msg, mavlink_mlrs_radio_link_stats_t* mlrs_radio_link_stats)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mlrs_radio_link_stats->flags = mavlink_msg_mlrs_radio_link_stats_get_flags(msg);
+ mlrs_radio_link_stats->target_system = mavlink_msg_mlrs_radio_link_stats_get_target_system(msg);
+ mlrs_radio_link_stats->target_component = mavlink_msg_mlrs_radio_link_stats_get_target_component(msg);
+ mlrs_radio_link_stats->rx_LQ_rc = mavlink_msg_mlrs_radio_link_stats_get_rx_LQ_rc(msg);
+ mlrs_radio_link_stats->rx_LQ_ser = mavlink_msg_mlrs_radio_link_stats_get_rx_LQ_ser(msg);
+ mlrs_radio_link_stats->rx_rssi1 = mavlink_msg_mlrs_radio_link_stats_get_rx_rssi1(msg);
+ mlrs_radio_link_stats->rx_snr1 = mavlink_msg_mlrs_radio_link_stats_get_rx_snr1(msg);
+ mlrs_radio_link_stats->tx_LQ_ser = mavlink_msg_mlrs_radio_link_stats_get_tx_LQ_ser(msg);
+ mlrs_radio_link_stats->tx_rssi1 = mavlink_msg_mlrs_radio_link_stats_get_tx_rssi1(msg);
+ mlrs_radio_link_stats->tx_snr1 = mavlink_msg_mlrs_radio_link_stats_get_tx_snr1(msg);
+ mlrs_radio_link_stats->rx_rssi2 = mavlink_msg_mlrs_radio_link_stats_get_rx_rssi2(msg);
+ mlrs_radio_link_stats->rx_snr2 = mavlink_msg_mlrs_radio_link_stats_get_rx_snr2(msg);
+ mlrs_radio_link_stats->tx_rssi2 = mavlink_msg_mlrs_radio_link_stats_get_tx_rssi2(msg);
+ mlrs_radio_link_stats->tx_snr2 = mavlink_msg_mlrs_radio_link_stats_get_tx_snr2(msg);
+ mlrs_radio_link_stats->frequency1 = mavlink_msg_mlrs_radio_link_stats_get_frequency1(msg);
+ mlrs_radio_link_stats->frequency2 = mavlink_msg_mlrs_radio_link_stats_get_frequency2(msg);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_MLRS_RADIO_LINK_STATS_LEN? msg->len : MAVLINK_MSG_ID_MLRS_RADIO_LINK_STATS_LEN;
+ memset(mlrs_radio_link_stats, 0, MAVLINK_MSG_ID_MLRS_RADIO_LINK_STATS_LEN);
+ memcpy(mlrs_radio_link_stats, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/storm32/mavlink_msg_param_value_array.h b/lib/main/MAVLink/storm32/mavlink_msg_param_value_array.h
new file mode 100644
index 00000000000..fd44a81ac59
--- /dev/null
+++ b/lib/main/MAVLink/storm32/mavlink_msg_param_value_array.h
@@ -0,0 +1,362 @@
+#pragma once
+// MESSAGE PARAM_VALUE_ARRAY PACKING
+
+#define MAVLINK_MSG_ID_PARAM_VALUE_ARRAY 60041
+
+
+typedef struct __mavlink_param_value_array_t {
+ uint16_t param_count; /*< Total number of onboard parameters.*/
+ uint16_t param_index_first; /*< Index of the first onboard parameter in this array.*/
+ uint16_t flags; /*< Flags.*/
+ uint8_t param_array_len; /*< Number of onboard parameters in this array.*/
+ uint8_t packet_buf[248]; /*< Parameters buffer. Contains a series of variable length parameter blocks, one per parameter, with format as specified elsewhere.*/
+} mavlink_param_value_array_t;
+
+#define MAVLINK_MSG_ID_PARAM_VALUE_ARRAY_LEN 255
+#define MAVLINK_MSG_ID_PARAM_VALUE_ARRAY_MIN_LEN 255
+#define MAVLINK_MSG_ID_60041_LEN 255
+#define MAVLINK_MSG_ID_60041_MIN_LEN 255
+
+#define MAVLINK_MSG_ID_PARAM_VALUE_ARRAY_CRC 191
+#define MAVLINK_MSG_ID_60041_CRC 191
+
+#define MAVLINK_MSG_PARAM_VALUE_ARRAY_FIELD_PACKET_BUF_LEN 248
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_PARAM_VALUE_ARRAY { \
+ 60041, \
+ "PARAM_VALUE_ARRAY", \
+ 5, \
+ { { "param_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_param_value_array_t, param_count) }, \
+ { "param_index_first", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_param_value_array_t, param_index_first) }, \
+ { "param_array_len", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_param_value_array_t, param_array_len) }, \
+ { "flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_param_value_array_t, flags) }, \
+ { "packet_buf", NULL, MAVLINK_TYPE_UINT8_T, 248, 7, offsetof(mavlink_param_value_array_t, packet_buf) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_PARAM_VALUE_ARRAY { \
+ "PARAM_VALUE_ARRAY", \
+ 5, \
+ { { "param_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_param_value_array_t, param_count) }, \
+ { "param_index_first", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_param_value_array_t, param_index_first) }, \
+ { "param_array_len", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_param_value_array_t, param_array_len) }, \
+ { "flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_param_value_array_t, flags) }, \
+ { "packet_buf", NULL, MAVLINK_TYPE_UINT8_T, 248, 7, offsetof(mavlink_param_value_array_t, packet_buf) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a param_value_array 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 param_count Total number of onboard parameters.
+ * @param param_index_first Index of the first onboard parameter in this array.
+ * @param param_array_len Number of onboard parameters in this array.
+ * @param flags Flags.
+ * @param packet_buf Parameters buffer. Contains a series of variable length parameter blocks, one per parameter, with format as specified elsewhere.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_param_value_array_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint16_t param_count, uint16_t param_index_first, uint8_t param_array_len, uint16_t flags, const uint8_t *packet_buf)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_PARAM_VALUE_ARRAY_LEN];
+ _mav_put_uint16_t(buf, 0, param_count);
+ _mav_put_uint16_t(buf, 2, param_index_first);
+ _mav_put_uint16_t(buf, 4, flags);
+ _mav_put_uint8_t(buf, 6, param_array_len);
+ _mav_put_uint8_t_array(buf, 7, packet_buf, 248);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PARAM_VALUE_ARRAY_LEN);
+#else
+ mavlink_param_value_array_t packet;
+ packet.param_count = param_count;
+ packet.param_index_first = param_index_first;
+ packet.flags = flags;
+ packet.param_array_len = param_array_len;
+ mav_array_assign_uint8_t(packet.packet_buf, packet_buf, 248);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PARAM_VALUE_ARRAY_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_PARAM_VALUE_ARRAY;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PARAM_VALUE_ARRAY_MIN_LEN, MAVLINK_MSG_ID_PARAM_VALUE_ARRAY_LEN, MAVLINK_MSG_ID_PARAM_VALUE_ARRAY_CRC);
+}
+
+/**
+ * @brief Pack a param_value_array 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 param_count Total number of onboard parameters.
+ * @param param_index_first Index of the first onboard parameter in this array.
+ * @param param_array_len Number of onboard parameters in this array.
+ * @param flags Flags.
+ * @param packet_buf Parameters buffer. Contains a series of variable length parameter blocks, one per parameter, with format as specified elsewhere.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_param_value_array_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ uint16_t param_count, uint16_t param_index_first, uint8_t param_array_len, uint16_t flags, const uint8_t *packet_buf)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_PARAM_VALUE_ARRAY_LEN];
+ _mav_put_uint16_t(buf, 0, param_count);
+ _mav_put_uint16_t(buf, 2, param_index_first);
+ _mav_put_uint16_t(buf, 4, flags);
+ _mav_put_uint8_t(buf, 6, param_array_len);
+ _mav_put_uint8_t_array(buf, 7, packet_buf, 248);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PARAM_VALUE_ARRAY_LEN);
+#else
+ mavlink_param_value_array_t packet;
+ packet.param_count = param_count;
+ packet.param_index_first = param_index_first;
+ packet.flags = flags;
+ packet.param_array_len = param_array_len;
+ mav_array_memcpy(packet.packet_buf, packet_buf, sizeof(uint8_t)*248);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PARAM_VALUE_ARRAY_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_PARAM_VALUE_ARRAY;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_PARAM_VALUE_ARRAY_MIN_LEN, MAVLINK_MSG_ID_PARAM_VALUE_ARRAY_LEN, MAVLINK_MSG_ID_PARAM_VALUE_ARRAY_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_PARAM_VALUE_ARRAY_MIN_LEN, MAVLINK_MSG_ID_PARAM_VALUE_ARRAY_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a param_value_array 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 param_count Total number of onboard parameters.
+ * @param param_index_first Index of the first onboard parameter in this array.
+ * @param param_array_len Number of onboard parameters in this array.
+ * @param flags Flags.
+ * @param packet_buf Parameters buffer. Contains a series of variable length parameter blocks, one per parameter, with format as specified elsewhere.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_param_value_array_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint16_t param_count,uint16_t param_index_first,uint8_t param_array_len,uint16_t flags,const uint8_t *packet_buf)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_PARAM_VALUE_ARRAY_LEN];
+ _mav_put_uint16_t(buf, 0, param_count);
+ _mav_put_uint16_t(buf, 2, param_index_first);
+ _mav_put_uint16_t(buf, 4, flags);
+ _mav_put_uint8_t(buf, 6, param_array_len);
+ _mav_put_uint8_t_array(buf, 7, packet_buf, 248);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PARAM_VALUE_ARRAY_LEN);
+#else
+ mavlink_param_value_array_t packet;
+ packet.param_count = param_count;
+ packet.param_index_first = param_index_first;
+ packet.flags = flags;
+ packet.param_array_len = param_array_len;
+ mav_array_assign_uint8_t(packet.packet_buf, packet_buf, 248);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PARAM_VALUE_ARRAY_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_PARAM_VALUE_ARRAY;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PARAM_VALUE_ARRAY_MIN_LEN, MAVLINK_MSG_ID_PARAM_VALUE_ARRAY_LEN, MAVLINK_MSG_ID_PARAM_VALUE_ARRAY_CRC);
+}
+
+/**
+ * @brief Encode a param_value_array 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 param_value_array C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_param_value_array_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_param_value_array_t* param_value_array)
+{
+ return mavlink_msg_param_value_array_pack(system_id, component_id, msg, param_value_array->param_count, param_value_array->param_index_first, param_value_array->param_array_len, param_value_array->flags, param_value_array->packet_buf);
+}
+
+/**
+ * @brief Encode a param_value_array 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 param_value_array C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_param_value_array_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_param_value_array_t* param_value_array)
+{
+ return mavlink_msg_param_value_array_pack_chan(system_id, component_id, chan, msg, param_value_array->param_count, param_value_array->param_index_first, param_value_array->param_array_len, param_value_array->flags, param_value_array->packet_buf);
+}
+
+/**
+ * @brief Encode a param_value_array 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 param_value_array C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_param_value_array_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_param_value_array_t* param_value_array)
+{
+ return mavlink_msg_param_value_array_pack_status(system_id, component_id, _status, msg, param_value_array->param_count, param_value_array->param_index_first, param_value_array->param_array_len, param_value_array->flags, param_value_array->packet_buf);
+}
+
+/**
+ * @brief Send a param_value_array message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param param_count Total number of onboard parameters.
+ * @param param_index_first Index of the first onboard parameter in this array.
+ * @param param_array_len Number of onboard parameters in this array.
+ * @param flags Flags.
+ * @param packet_buf Parameters buffer. Contains a series of variable length parameter blocks, one per parameter, with format as specified elsewhere.
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_param_value_array_send(mavlink_channel_t chan, uint16_t param_count, uint16_t param_index_first, uint8_t param_array_len, uint16_t flags, const uint8_t *packet_buf)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_PARAM_VALUE_ARRAY_LEN];
+ _mav_put_uint16_t(buf, 0, param_count);
+ _mav_put_uint16_t(buf, 2, param_index_first);
+ _mav_put_uint16_t(buf, 4, flags);
+ _mav_put_uint8_t(buf, 6, param_array_len);
+ _mav_put_uint8_t_array(buf, 7, packet_buf, 248);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_VALUE_ARRAY, buf, MAVLINK_MSG_ID_PARAM_VALUE_ARRAY_MIN_LEN, MAVLINK_MSG_ID_PARAM_VALUE_ARRAY_LEN, MAVLINK_MSG_ID_PARAM_VALUE_ARRAY_CRC);
+#else
+ mavlink_param_value_array_t packet;
+ packet.param_count = param_count;
+ packet.param_index_first = param_index_first;
+ packet.flags = flags;
+ packet.param_array_len = param_array_len;
+ mav_array_assign_uint8_t(packet.packet_buf, packet_buf, 248);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_VALUE_ARRAY, (const char *)&packet, MAVLINK_MSG_ID_PARAM_VALUE_ARRAY_MIN_LEN, MAVLINK_MSG_ID_PARAM_VALUE_ARRAY_LEN, MAVLINK_MSG_ID_PARAM_VALUE_ARRAY_CRC);
+#endif
+}
+
+/**
+ * @brief Send a param_value_array message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_param_value_array_send_struct(mavlink_channel_t chan, const mavlink_param_value_array_t* param_value_array)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_param_value_array_send(chan, param_value_array->param_count, param_value_array->param_index_first, param_value_array->param_array_len, param_value_array->flags, param_value_array->packet_buf);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_VALUE_ARRAY, (const char *)param_value_array, MAVLINK_MSG_ID_PARAM_VALUE_ARRAY_MIN_LEN, MAVLINK_MSG_ID_PARAM_VALUE_ARRAY_LEN, MAVLINK_MSG_ID_PARAM_VALUE_ARRAY_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_PARAM_VALUE_ARRAY_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_param_value_array_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t param_count, uint16_t param_index_first, uint8_t param_array_len, uint16_t flags, const uint8_t *packet_buf)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint16_t(buf, 0, param_count);
+ _mav_put_uint16_t(buf, 2, param_index_first);
+ _mav_put_uint16_t(buf, 4, flags);
+ _mav_put_uint8_t(buf, 6, param_array_len);
+ _mav_put_uint8_t_array(buf, 7, packet_buf, 248);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_VALUE_ARRAY, buf, MAVLINK_MSG_ID_PARAM_VALUE_ARRAY_MIN_LEN, MAVLINK_MSG_ID_PARAM_VALUE_ARRAY_LEN, MAVLINK_MSG_ID_PARAM_VALUE_ARRAY_CRC);
+#else
+ mavlink_param_value_array_t *packet = (mavlink_param_value_array_t *)msgbuf;
+ packet->param_count = param_count;
+ packet->param_index_first = param_index_first;
+ packet->flags = flags;
+ packet->param_array_len = param_array_len;
+ mav_array_assign_uint8_t(packet->packet_buf, packet_buf, 248);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_VALUE_ARRAY, (const char *)packet, MAVLINK_MSG_ID_PARAM_VALUE_ARRAY_MIN_LEN, MAVLINK_MSG_ID_PARAM_VALUE_ARRAY_LEN, MAVLINK_MSG_ID_PARAM_VALUE_ARRAY_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE PARAM_VALUE_ARRAY UNPACKING
+
+
+/**
+ * @brief Get field param_count from param_value_array message
+ *
+ * @return Total number of onboard parameters.
+ */
+static inline uint16_t mavlink_msg_param_value_array_get_param_count(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 0);
+}
+
+/**
+ * @brief Get field param_index_first from param_value_array message
+ *
+ * @return Index of the first onboard parameter in this array.
+ */
+static inline uint16_t mavlink_msg_param_value_array_get_param_index_first(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 2);
+}
+
+/**
+ * @brief Get field param_array_len from param_value_array message
+ *
+ * @return Number of onboard parameters in this array.
+ */
+static inline uint8_t mavlink_msg_param_value_array_get_param_array_len(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 6);
+}
+
+/**
+ * @brief Get field flags from param_value_array message
+ *
+ * @return Flags.
+ */
+static inline uint16_t mavlink_msg_param_value_array_get_flags(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 4);
+}
+
+/**
+ * @brief Get field packet_buf from param_value_array message
+ *
+ * @return Parameters buffer. Contains a series of variable length parameter blocks, one per parameter, with format as specified elsewhere.
+ */
+static inline uint16_t mavlink_msg_param_value_array_get_packet_buf(const mavlink_message_t* msg, uint8_t *packet_buf)
+{
+ return _MAV_RETURN_uint8_t_array(msg, packet_buf, 248, 7);
+}
+
+/**
+ * @brief Decode a param_value_array message into a struct
+ *
+ * @param msg The message to decode
+ * @param param_value_array C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_param_value_array_decode(const mavlink_message_t* msg, mavlink_param_value_array_t* param_value_array)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ param_value_array->param_count = mavlink_msg_param_value_array_get_param_count(msg);
+ param_value_array->param_index_first = mavlink_msg_param_value_array_get_param_index_first(msg);
+ param_value_array->flags = mavlink_msg_param_value_array_get_flags(msg);
+ param_value_array->param_array_len = mavlink_msg_param_value_array_get_param_array_len(msg);
+ mavlink_msg_param_value_array_get_packet_buf(msg, param_value_array->packet_buf);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_PARAM_VALUE_ARRAY_LEN? msg->len : MAVLINK_MSG_ID_PARAM_VALUE_ARRAY_LEN;
+ memset(param_value_array, 0, MAVLINK_MSG_ID_PARAM_VALUE_ARRAY_LEN);
+ memcpy(param_value_array, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/storm32/mavlink_msg_qshot_status.h b/lib/main/MAVLink/storm32/mavlink_msg_qshot_status.h
new file mode 100644
index 00000000000..23cab1e987a
--- /dev/null
+++ b/lib/main/MAVLink/storm32/mavlink_msg_qshot_status.h
@@ -0,0 +1,288 @@
+#pragma once
+// MESSAGE QSHOT_STATUS PACKING
+
+#define MAVLINK_MSG_ID_QSHOT_STATUS 60020
+
+
+typedef struct __mavlink_qshot_status_t {
+ uint16_t mode; /*< Current shot mode.*/
+ uint16_t shot_state; /*< Current state in the shot. States are specific to the selected shot mode.*/
+} mavlink_qshot_status_t;
+
+#define MAVLINK_MSG_ID_QSHOT_STATUS_LEN 4
+#define MAVLINK_MSG_ID_QSHOT_STATUS_MIN_LEN 4
+#define MAVLINK_MSG_ID_60020_LEN 4
+#define MAVLINK_MSG_ID_60020_MIN_LEN 4
+
+#define MAVLINK_MSG_ID_QSHOT_STATUS_CRC 202
+#define MAVLINK_MSG_ID_60020_CRC 202
+
+
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_QSHOT_STATUS { \
+ 60020, \
+ "QSHOT_STATUS", \
+ 2, \
+ { { "mode", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_qshot_status_t, mode) }, \
+ { "shot_state", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_qshot_status_t, shot_state) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_QSHOT_STATUS { \
+ "QSHOT_STATUS", \
+ 2, \
+ { { "mode", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_qshot_status_t, mode) }, \
+ { "shot_state", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_qshot_status_t, shot_state) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a qshot_status 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 mode Current shot mode.
+ * @param shot_state Current state in the shot. States are specific to the selected shot mode.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_qshot_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint16_t mode, uint16_t shot_state)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_QSHOT_STATUS_LEN];
+ _mav_put_uint16_t(buf, 0, mode);
+ _mav_put_uint16_t(buf, 2, shot_state);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_QSHOT_STATUS_LEN);
+#else
+ mavlink_qshot_status_t packet;
+ packet.mode = mode;
+ packet.shot_state = shot_state;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_QSHOT_STATUS_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_QSHOT_STATUS;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_QSHOT_STATUS_MIN_LEN, MAVLINK_MSG_ID_QSHOT_STATUS_LEN, MAVLINK_MSG_ID_QSHOT_STATUS_CRC);
+}
+
+/**
+ * @brief Pack a qshot_status 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 mode Current shot mode.
+ * @param shot_state Current state in the shot. States are specific to the selected shot mode.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_qshot_status_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ uint16_t mode, uint16_t shot_state)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_QSHOT_STATUS_LEN];
+ _mav_put_uint16_t(buf, 0, mode);
+ _mav_put_uint16_t(buf, 2, shot_state);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_QSHOT_STATUS_LEN);
+#else
+ mavlink_qshot_status_t packet;
+ packet.mode = mode;
+ packet.shot_state = shot_state;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_QSHOT_STATUS_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_QSHOT_STATUS;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_QSHOT_STATUS_MIN_LEN, MAVLINK_MSG_ID_QSHOT_STATUS_LEN, MAVLINK_MSG_ID_QSHOT_STATUS_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_QSHOT_STATUS_MIN_LEN, MAVLINK_MSG_ID_QSHOT_STATUS_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a qshot_status 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 mode Current shot mode.
+ * @param shot_state Current state in the shot. States are specific to the selected shot mode.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_qshot_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint16_t mode,uint16_t shot_state)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_QSHOT_STATUS_LEN];
+ _mav_put_uint16_t(buf, 0, mode);
+ _mav_put_uint16_t(buf, 2, shot_state);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_QSHOT_STATUS_LEN);
+#else
+ mavlink_qshot_status_t packet;
+ packet.mode = mode;
+ packet.shot_state = shot_state;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_QSHOT_STATUS_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_QSHOT_STATUS;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_QSHOT_STATUS_MIN_LEN, MAVLINK_MSG_ID_QSHOT_STATUS_LEN, MAVLINK_MSG_ID_QSHOT_STATUS_CRC);
+}
+
+/**
+ * @brief Encode a qshot_status 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 qshot_status C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_qshot_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_qshot_status_t* qshot_status)
+{
+ return mavlink_msg_qshot_status_pack(system_id, component_id, msg, qshot_status->mode, qshot_status->shot_state);
+}
+
+/**
+ * @brief Encode a qshot_status 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 qshot_status C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_qshot_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_qshot_status_t* qshot_status)
+{
+ return mavlink_msg_qshot_status_pack_chan(system_id, component_id, chan, msg, qshot_status->mode, qshot_status->shot_state);
+}
+
+/**
+ * @brief Encode a qshot_status 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 qshot_status C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_qshot_status_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_qshot_status_t* qshot_status)
+{
+ return mavlink_msg_qshot_status_pack_status(system_id, component_id, _status, msg, qshot_status->mode, qshot_status->shot_state);
+}
+
+/**
+ * @brief Send a qshot_status message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param mode Current shot mode.
+ * @param shot_state Current state in the shot. States are specific to the selected shot mode.
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_qshot_status_send(mavlink_channel_t chan, uint16_t mode, uint16_t shot_state)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_QSHOT_STATUS_LEN];
+ _mav_put_uint16_t(buf, 0, mode);
+ _mav_put_uint16_t(buf, 2, shot_state);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_QSHOT_STATUS, buf, MAVLINK_MSG_ID_QSHOT_STATUS_MIN_LEN, MAVLINK_MSG_ID_QSHOT_STATUS_LEN, MAVLINK_MSG_ID_QSHOT_STATUS_CRC);
+#else
+ mavlink_qshot_status_t packet;
+ packet.mode = mode;
+ packet.shot_state = shot_state;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_QSHOT_STATUS, (const char *)&packet, MAVLINK_MSG_ID_QSHOT_STATUS_MIN_LEN, MAVLINK_MSG_ID_QSHOT_STATUS_LEN, MAVLINK_MSG_ID_QSHOT_STATUS_CRC);
+#endif
+}
+
+/**
+ * @brief Send a qshot_status message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_qshot_status_send_struct(mavlink_channel_t chan, const mavlink_qshot_status_t* qshot_status)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_qshot_status_send(chan, qshot_status->mode, qshot_status->shot_state);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_QSHOT_STATUS, (const char *)qshot_status, MAVLINK_MSG_ID_QSHOT_STATUS_MIN_LEN, MAVLINK_MSG_ID_QSHOT_STATUS_LEN, MAVLINK_MSG_ID_QSHOT_STATUS_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_QSHOT_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_qshot_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t mode, uint16_t shot_state)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint16_t(buf, 0, mode);
+ _mav_put_uint16_t(buf, 2, shot_state);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_QSHOT_STATUS, buf, MAVLINK_MSG_ID_QSHOT_STATUS_MIN_LEN, MAVLINK_MSG_ID_QSHOT_STATUS_LEN, MAVLINK_MSG_ID_QSHOT_STATUS_CRC);
+#else
+ mavlink_qshot_status_t *packet = (mavlink_qshot_status_t *)msgbuf;
+ packet->mode = mode;
+ packet->shot_state = shot_state;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_QSHOT_STATUS, (const char *)packet, MAVLINK_MSG_ID_QSHOT_STATUS_MIN_LEN, MAVLINK_MSG_ID_QSHOT_STATUS_LEN, MAVLINK_MSG_ID_QSHOT_STATUS_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE QSHOT_STATUS UNPACKING
+
+
+/**
+ * @brief Get field mode from qshot_status message
+ *
+ * @return Current shot mode.
+ */
+static inline uint16_t mavlink_msg_qshot_status_get_mode(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 0);
+}
+
+/**
+ * @brief Get field shot_state from qshot_status message
+ *
+ * @return Current state in the shot. States are specific to the selected shot mode.
+ */
+static inline uint16_t mavlink_msg_qshot_status_get_shot_state(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 2);
+}
+
+/**
+ * @brief Decode a qshot_status message into a struct
+ *
+ * @param msg The message to decode
+ * @param qshot_status C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_qshot_status_decode(const mavlink_message_t* msg, mavlink_qshot_status_t* qshot_status)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ qshot_status->mode = mavlink_msg_qshot_status_get_mode(msg);
+ qshot_status->shot_state = mavlink_msg_qshot_status_get_shot_state(msg);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_QSHOT_STATUS_LEN? msg->len : MAVLINK_MSG_ID_QSHOT_STATUS_LEN;
+ memset(qshot_status, 0, MAVLINK_MSG_ID_QSHOT_STATUS_LEN);
+ memcpy(qshot_status, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/storm32/mavlink_msg_storm32_gimbal_manager_control.h b/lib/main/MAVLink/storm32/mavlink_msg_storm32_gimbal_manager_control.h
new file mode 100644
index 00000000000..02cd7277f16
--- /dev/null
+++ b/lib/main/MAVLink/storm32/mavlink_msg_storm32_gimbal_manager_control.h
@@ -0,0 +1,502 @@
+#pragma once
+// MESSAGE STORM32_GIMBAL_MANAGER_CONTROL PACKING
+
+#define MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL 60012
+
+
+typedef struct __mavlink_storm32_gimbal_manager_control_t {
+ float q[4]; /*< Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation). Set first element to NaN to be ignored. The frame is determined by the GIMBAL_DEVICE_FLAGS_YAW_IN_xxx_FRAME flags.*/
+ float angular_velocity_x; /*< [rad/s] X component of angular velocity (positive: roll to the right). NaN to be ignored.*/
+ float angular_velocity_y; /*< [rad/s] Y component of angular velocity (positive: tilt up). NaN to be ignored.*/
+ float angular_velocity_z; /*< [rad/s] Z component of angular velocity (positive: pan to the right). NaN to be ignored. The frame is determined by the GIMBAL_DEVICE_FLAGS_YAW_IN_xxx_FRAME flags.*/
+ uint16_t device_flags; /*< Gimbal device flags to be applied (UINT16_MAX to be ignored). Same flags as used in GIMBAL_DEVICE_SET_ATTITUDE.*/
+ uint16_t manager_flags; /*< Gimbal manager flags to be applied (0 to be ignored).*/
+ uint8_t target_system; /*< System ID*/
+ uint8_t target_component; /*< Component ID*/
+ uint8_t gimbal_id; /*< Gimbal ID of the gimbal manager to address (component ID or 1-6 for non-MAVLink gimbal, 0 for all gimbals). Send command multiple times for more than one but not all gimbals.*/
+ uint8_t client; /*< Client which is contacting the gimbal manager (must be set).*/
+} mavlink_storm32_gimbal_manager_control_t;
+
+#define MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_LEN 36
+#define MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_MIN_LEN 36
+#define MAVLINK_MSG_ID_60012_LEN 36
+#define MAVLINK_MSG_ID_60012_MIN_LEN 36
+
+#define MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_CRC 99
+#define MAVLINK_MSG_ID_60012_CRC 99
+
+#define MAVLINK_MSG_STORM32_GIMBAL_MANAGER_CONTROL_FIELD_Q_LEN 4
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_STORM32_GIMBAL_MANAGER_CONTROL { \
+ 60012, \
+ "STORM32_GIMBAL_MANAGER_CONTROL", \
+ 10, \
+ { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_storm32_gimbal_manager_control_t, target_system) }, \
+ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_storm32_gimbal_manager_control_t, target_component) }, \
+ { "gimbal_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_storm32_gimbal_manager_control_t, gimbal_id) }, \
+ { "client", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_storm32_gimbal_manager_control_t, client) }, \
+ { "device_flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_storm32_gimbal_manager_control_t, device_flags) }, \
+ { "manager_flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_storm32_gimbal_manager_control_t, manager_flags) }, \
+ { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 0, offsetof(mavlink_storm32_gimbal_manager_control_t, q) }, \
+ { "angular_velocity_x", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_storm32_gimbal_manager_control_t, angular_velocity_x) }, \
+ { "angular_velocity_y", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_storm32_gimbal_manager_control_t, angular_velocity_y) }, \
+ { "angular_velocity_z", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_storm32_gimbal_manager_control_t, angular_velocity_z) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_STORM32_GIMBAL_MANAGER_CONTROL { \
+ "STORM32_GIMBAL_MANAGER_CONTROL", \
+ 10, \
+ { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_storm32_gimbal_manager_control_t, target_system) }, \
+ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_storm32_gimbal_manager_control_t, target_component) }, \
+ { "gimbal_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_storm32_gimbal_manager_control_t, gimbal_id) }, \
+ { "client", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_storm32_gimbal_manager_control_t, client) }, \
+ { "device_flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_storm32_gimbal_manager_control_t, device_flags) }, \
+ { "manager_flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_storm32_gimbal_manager_control_t, manager_flags) }, \
+ { "q", NULL, MAVLINK_TYPE_FLOAT, 4, 0, offsetof(mavlink_storm32_gimbal_manager_control_t, q) }, \
+ { "angular_velocity_x", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_storm32_gimbal_manager_control_t, angular_velocity_x) }, \
+ { "angular_velocity_y", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_storm32_gimbal_manager_control_t, angular_velocity_y) }, \
+ { "angular_velocity_z", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_storm32_gimbal_manager_control_t, angular_velocity_z) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a storm32_gimbal_manager_control 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 target_system System ID
+ * @param target_component Component ID
+ * @param gimbal_id Gimbal ID of the gimbal manager to address (component ID or 1-6 for non-MAVLink gimbal, 0 for all gimbals). Send command multiple times for more than one but not all gimbals.
+ * @param client Client which is contacting the gimbal manager (must be set).
+ * @param device_flags Gimbal device flags to be applied (UINT16_MAX to be ignored). Same flags as used in GIMBAL_DEVICE_SET_ATTITUDE.
+ * @param manager_flags Gimbal manager flags to be applied (0 to be ignored).
+ * @param q Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation). Set first element to NaN to be ignored. The frame is determined by the GIMBAL_DEVICE_FLAGS_YAW_IN_xxx_FRAME flags.
+ * @param angular_velocity_x [rad/s] X component of angular velocity (positive: roll to the right). NaN to be ignored.
+ * @param angular_velocity_y [rad/s] Y component of angular velocity (positive: tilt up). NaN to be ignored.
+ * @param angular_velocity_z [rad/s] Z component of angular velocity (positive: pan to the right). NaN to be ignored. The frame is determined by the GIMBAL_DEVICE_FLAGS_YAW_IN_xxx_FRAME flags.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_storm32_gimbal_manager_control_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint8_t target_system, uint8_t target_component, uint8_t gimbal_id, uint8_t client, uint16_t device_flags, uint16_t manager_flags, const float *q, float angular_velocity_x, float angular_velocity_y, float angular_velocity_z)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_LEN];
+ _mav_put_float(buf, 16, angular_velocity_x);
+ _mav_put_float(buf, 20, angular_velocity_y);
+ _mav_put_float(buf, 24, angular_velocity_z);
+ _mav_put_uint16_t(buf, 28, device_flags);
+ _mav_put_uint16_t(buf, 30, manager_flags);
+ _mav_put_uint8_t(buf, 32, target_system);
+ _mav_put_uint8_t(buf, 33, target_component);
+ _mav_put_uint8_t(buf, 34, gimbal_id);
+ _mav_put_uint8_t(buf, 35, client);
+ _mav_put_float_array(buf, 0, q, 4);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_LEN);
+#else
+ mavlink_storm32_gimbal_manager_control_t packet;
+ packet.angular_velocity_x = angular_velocity_x;
+ packet.angular_velocity_y = angular_velocity_y;
+ packet.angular_velocity_z = angular_velocity_z;
+ packet.device_flags = device_flags;
+ packet.manager_flags = manager_flags;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.gimbal_id = gimbal_id;
+ packet.client = client;
+ mav_array_assign_float(packet.q, q, 4);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_MIN_LEN, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_LEN, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_CRC);
+}
+
+/**
+ * @brief Pack a storm32_gimbal_manager_control 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 target_system System ID
+ * @param target_component Component ID
+ * @param gimbal_id Gimbal ID of the gimbal manager to address (component ID or 1-6 for non-MAVLink gimbal, 0 for all gimbals). Send command multiple times for more than one but not all gimbals.
+ * @param client Client which is contacting the gimbal manager (must be set).
+ * @param device_flags Gimbal device flags to be applied (UINT16_MAX to be ignored). Same flags as used in GIMBAL_DEVICE_SET_ATTITUDE.
+ * @param manager_flags Gimbal manager flags to be applied (0 to be ignored).
+ * @param q Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation). Set first element to NaN to be ignored. The frame is determined by the GIMBAL_DEVICE_FLAGS_YAW_IN_xxx_FRAME flags.
+ * @param angular_velocity_x [rad/s] X component of angular velocity (positive: roll to the right). NaN to be ignored.
+ * @param angular_velocity_y [rad/s] Y component of angular velocity (positive: tilt up). NaN to be ignored.
+ * @param angular_velocity_z [rad/s] Z component of angular velocity (positive: pan to the right). NaN to be ignored. The frame is determined by the GIMBAL_DEVICE_FLAGS_YAW_IN_xxx_FRAME flags.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_storm32_gimbal_manager_control_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ uint8_t target_system, uint8_t target_component, uint8_t gimbal_id, uint8_t client, uint16_t device_flags, uint16_t manager_flags, const float *q, float angular_velocity_x, float angular_velocity_y, float angular_velocity_z)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_LEN];
+ _mav_put_float(buf, 16, angular_velocity_x);
+ _mav_put_float(buf, 20, angular_velocity_y);
+ _mav_put_float(buf, 24, angular_velocity_z);
+ _mav_put_uint16_t(buf, 28, device_flags);
+ _mav_put_uint16_t(buf, 30, manager_flags);
+ _mav_put_uint8_t(buf, 32, target_system);
+ _mav_put_uint8_t(buf, 33, target_component);
+ _mav_put_uint8_t(buf, 34, gimbal_id);
+ _mav_put_uint8_t(buf, 35, client);
+ _mav_put_float_array(buf, 0, q, 4);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_LEN);
+#else
+ mavlink_storm32_gimbal_manager_control_t packet;
+ packet.angular_velocity_x = angular_velocity_x;
+ packet.angular_velocity_y = angular_velocity_y;
+ packet.angular_velocity_z = angular_velocity_z;
+ packet.device_flags = device_flags;
+ packet.manager_flags = manager_flags;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.gimbal_id = gimbal_id;
+ packet.client = client;
+ mav_array_memcpy(packet.q, q, sizeof(float)*4);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_MIN_LEN, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_LEN, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_MIN_LEN, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a storm32_gimbal_manager_control 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 target_system System ID
+ * @param target_component Component ID
+ * @param gimbal_id Gimbal ID of the gimbal manager to address (component ID or 1-6 for non-MAVLink gimbal, 0 for all gimbals). Send command multiple times for more than one but not all gimbals.
+ * @param client Client which is contacting the gimbal manager (must be set).
+ * @param device_flags Gimbal device flags to be applied (UINT16_MAX to be ignored). Same flags as used in GIMBAL_DEVICE_SET_ATTITUDE.
+ * @param manager_flags Gimbal manager flags to be applied (0 to be ignored).
+ * @param q Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation). Set first element to NaN to be ignored. The frame is determined by the GIMBAL_DEVICE_FLAGS_YAW_IN_xxx_FRAME flags.
+ * @param angular_velocity_x [rad/s] X component of angular velocity (positive: roll to the right). NaN to be ignored.
+ * @param angular_velocity_y [rad/s] Y component of angular velocity (positive: tilt up). NaN to be ignored.
+ * @param angular_velocity_z [rad/s] Z component of angular velocity (positive: pan to the right). NaN to be ignored. The frame is determined by the GIMBAL_DEVICE_FLAGS_YAW_IN_xxx_FRAME flags.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_storm32_gimbal_manager_control_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint8_t target_system,uint8_t target_component,uint8_t gimbal_id,uint8_t client,uint16_t device_flags,uint16_t manager_flags,const float *q,float angular_velocity_x,float angular_velocity_y,float angular_velocity_z)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_LEN];
+ _mav_put_float(buf, 16, angular_velocity_x);
+ _mav_put_float(buf, 20, angular_velocity_y);
+ _mav_put_float(buf, 24, angular_velocity_z);
+ _mav_put_uint16_t(buf, 28, device_flags);
+ _mav_put_uint16_t(buf, 30, manager_flags);
+ _mav_put_uint8_t(buf, 32, target_system);
+ _mav_put_uint8_t(buf, 33, target_component);
+ _mav_put_uint8_t(buf, 34, gimbal_id);
+ _mav_put_uint8_t(buf, 35, client);
+ _mav_put_float_array(buf, 0, q, 4);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_LEN);
+#else
+ mavlink_storm32_gimbal_manager_control_t packet;
+ packet.angular_velocity_x = angular_velocity_x;
+ packet.angular_velocity_y = angular_velocity_y;
+ packet.angular_velocity_z = angular_velocity_z;
+ packet.device_flags = device_flags;
+ packet.manager_flags = manager_flags;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.gimbal_id = gimbal_id;
+ packet.client = client;
+ mav_array_assign_float(packet.q, q, 4);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_MIN_LEN, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_LEN, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_CRC);
+}
+
+/**
+ * @brief Encode a storm32_gimbal_manager_control 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 storm32_gimbal_manager_control C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_storm32_gimbal_manager_control_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_storm32_gimbal_manager_control_t* storm32_gimbal_manager_control)
+{
+ return mavlink_msg_storm32_gimbal_manager_control_pack(system_id, component_id, msg, storm32_gimbal_manager_control->target_system, storm32_gimbal_manager_control->target_component, storm32_gimbal_manager_control->gimbal_id, storm32_gimbal_manager_control->client, storm32_gimbal_manager_control->device_flags, storm32_gimbal_manager_control->manager_flags, storm32_gimbal_manager_control->q, storm32_gimbal_manager_control->angular_velocity_x, storm32_gimbal_manager_control->angular_velocity_y, storm32_gimbal_manager_control->angular_velocity_z);
+}
+
+/**
+ * @brief Encode a storm32_gimbal_manager_control 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 storm32_gimbal_manager_control C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_storm32_gimbal_manager_control_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_storm32_gimbal_manager_control_t* storm32_gimbal_manager_control)
+{
+ return mavlink_msg_storm32_gimbal_manager_control_pack_chan(system_id, component_id, chan, msg, storm32_gimbal_manager_control->target_system, storm32_gimbal_manager_control->target_component, storm32_gimbal_manager_control->gimbal_id, storm32_gimbal_manager_control->client, storm32_gimbal_manager_control->device_flags, storm32_gimbal_manager_control->manager_flags, storm32_gimbal_manager_control->q, storm32_gimbal_manager_control->angular_velocity_x, storm32_gimbal_manager_control->angular_velocity_y, storm32_gimbal_manager_control->angular_velocity_z);
+}
+
+/**
+ * @brief Encode a storm32_gimbal_manager_control 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 storm32_gimbal_manager_control C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_storm32_gimbal_manager_control_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_storm32_gimbal_manager_control_t* storm32_gimbal_manager_control)
+{
+ return mavlink_msg_storm32_gimbal_manager_control_pack_status(system_id, component_id, _status, msg, storm32_gimbal_manager_control->target_system, storm32_gimbal_manager_control->target_component, storm32_gimbal_manager_control->gimbal_id, storm32_gimbal_manager_control->client, storm32_gimbal_manager_control->device_flags, storm32_gimbal_manager_control->manager_flags, storm32_gimbal_manager_control->q, storm32_gimbal_manager_control->angular_velocity_x, storm32_gimbal_manager_control->angular_velocity_y, storm32_gimbal_manager_control->angular_velocity_z);
+}
+
+/**
+ * @brief Send a storm32_gimbal_manager_control message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param target_system System ID
+ * @param target_component Component ID
+ * @param gimbal_id Gimbal ID of the gimbal manager to address (component ID or 1-6 for non-MAVLink gimbal, 0 for all gimbals). Send command multiple times for more than one but not all gimbals.
+ * @param client Client which is contacting the gimbal manager (must be set).
+ * @param device_flags Gimbal device flags to be applied (UINT16_MAX to be ignored). Same flags as used in GIMBAL_DEVICE_SET_ATTITUDE.
+ * @param manager_flags Gimbal manager flags to be applied (0 to be ignored).
+ * @param q Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation). Set first element to NaN to be ignored. The frame is determined by the GIMBAL_DEVICE_FLAGS_YAW_IN_xxx_FRAME flags.
+ * @param angular_velocity_x [rad/s] X component of angular velocity (positive: roll to the right). NaN to be ignored.
+ * @param angular_velocity_y [rad/s] Y component of angular velocity (positive: tilt up). NaN to be ignored.
+ * @param angular_velocity_z [rad/s] Z component of angular velocity (positive: pan to the right). NaN to be ignored. The frame is determined by the GIMBAL_DEVICE_FLAGS_YAW_IN_xxx_FRAME flags.
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_storm32_gimbal_manager_control_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t gimbal_id, uint8_t client, uint16_t device_flags, uint16_t manager_flags, const float *q, float angular_velocity_x, float angular_velocity_y, float angular_velocity_z)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_LEN];
+ _mav_put_float(buf, 16, angular_velocity_x);
+ _mav_put_float(buf, 20, angular_velocity_y);
+ _mav_put_float(buf, 24, angular_velocity_z);
+ _mav_put_uint16_t(buf, 28, device_flags);
+ _mav_put_uint16_t(buf, 30, manager_flags);
+ _mav_put_uint8_t(buf, 32, target_system);
+ _mav_put_uint8_t(buf, 33, target_component);
+ _mav_put_uint8_t(buf, 34, gimbal_id);
+ _mav_put_uint8_t(buf, 35, client);
+ _mav_put_float_array(buf, 0, q, 4);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL, buf, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_MIN_LEN, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_LEN, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_CRC);
+#else
+ mavlink_storm32_gimbal_manager_control_t packet;
+ packet.angular_velocity_x = angular_velocity_x;
+ packet.angular_velocity_y = angular_velocity_y;
+ packet.angular_velocity_z = angular_velocity_z;
+ packet.device_flags = device_flags;
+ packet.manager_flags = manager_flags;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.gimbal_id = gimbal_id;
+ packet.client = client;
+ mav_array_assign_float(packet.q, q, 4);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL, (const char *)&packet, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_MIN_LEN, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_LEN, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_CRC);
+#endif
+}
+
+/**
+ * @brief Send a storm32_gimbal_manager_control message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_storm32_gimbal_manager_control_send_struct(mavlink_channel_t chan, const mavlink_storm32_gimbal_manager_control_t* storm32_gimbal_manager_control)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_storm32_gimbal_manager_control_send(chan, storm32_gimbal_manager_control->target_system, storm32_gimbal_manager_control->target_component, storm32_gimbal_manager_control->gimbal_id, storm32_gimbal_manager_control->client, storm32_gimbal_manager_control->device_flags, storm32_gimbal_manager_control->manager_flags, storm32_gimbal_manager_control->q, storm32_gimbal_manager_control->angular_velocity_x, storm32_gimbal_manager_control->angular_velocity_y, storm32_gimbal_manager_control->angular_velocity_z);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL, (const char *)storm32_gimbal_manager_control, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_MIN_LEN, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_LEN, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_storm32_gimbal_manager_control_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t gimbal_id, uint8_t client, uint16_t device_flags, uint16_t manager_flags, const float *q, float angular_velocity_x, float angular_velocity_y, float angular_velocity_z)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_float(buf, 16, angular_velocity_x);
+ _mav_put_float(buf, 20, angular_velocity_y);
+ _mav_put_float(buf, 24, angular_velocity_z);
+ _mav_put_uint16_t(buf, 28, device_flags);
+ _mav_put_uint16_t(buf, 30, manager_flags);
+ _mav_put_uint8_t(buf, 32, target_system);
+ _mav_put_uint8_t(buf, 33, target_component);
+ _mav_put_uint8_t(buf, 34, gimbal_id);
+ _mav_put_uint8_t(buf, 35, client);
+ _mav_put_float_array(buf, 0, q, 4);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL, buf, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_MIN_LEN, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_LEN, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_CRC);
+#else
+ mavlink_storm32_gimbal_manager_control_t *packet = (mavlink_storm32_gimbal_manager_control_t *)msgbuf;
+ packet->angular_velocity_x = angular_velocity_x;
+ packet->angular_velocity_y = angular_velocity_y;
+ packet->angular_velocity_z = angular_velocity_z;
+ packet->device_flags = device_flags;
+ packet->manager_flags = manager_flags;
+ packet->target_system = target_system;
+ packet->target_component = target_component;
+ packet->gimbal_id = gimbal_id;
+ packet->client = client;
+ mav_array_assign_float(packet->q, q, 4);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL, (const char *)packet, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_MIN_LEN, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_LEN, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE STORM32_GIMBAL_MANAGER_CONTROL UNPACKING
+
+
+/**
+ * @brief Get field target_system from storm32_gimbal_manager_control message
+ *
+ * @return System ID
+ */
+static inline uint8_t mavlink_msg_storm32_gimbal_manager_control_get_target_system(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 32);
+}
+
+/**
+ * @brief Get field target_component from storm32_gimbal_manager_control message
+ *
+ * @return Component ID
+ */
+static inline uint8_t mavlink_msg_storm32_gimbal_manager_control_get_target_component(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 33);
+}
+
+/**
+ * @brief Get field gimbal_id from storm32_gimbal_manager_control message
+ *
+ * @return Gimbal ID of the gimbal manager to address (component ID or 1-6 for non-MAVLink gimbal, 0 for all gimbals). Send command multiple times for more than one but not all gimbals.
+ */
+static inline uint8_t mavlink_msg_storm32_gimbal_manager_control_get_gimbal_id(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 34);
+}
+
+/**
+ * @brief Get field client from storm32_gimbal_manager_control message
+ *
+ * @return Client which is contacting the gimbal manager (must be set).
+ */
+static inline uint8_t mavlink_msg_storm32_gimbal_manager_control_get_client(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 35);
+}
+
+/**
+ * @brief Get field device_flags from storm32_gimbal_manager_control message
+ *
+ * @return Gimbal device flags to be applied (UINT16_MAX to be ignored). Same flags as used in GIMBAL_DEVICE_SET_ATTITUDE.
+ */
+static inline uint16_t mavlink_msg_storm32_gimbal_manager_control_get_device_flags(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 28);
+}
+
+/**
+ * @brief Get field manager_flags from storm32_gimbal_manager_control message
+ *
+ * @return Gimbal manager flags to be applied (0 to be ignored).
+ */
+static inline uint16_t mavlink_msg_storm32_gimbal_manager_control_get_manager_flags(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 30);
+}
+
+/**
+ * @brief Get field q from storm32_gimbal_manager_control message
+ *
+ * @return Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation). Set first element to NaN to be ignored. The frame is determined by the GIMBAL_DEVICE_FLAGS_YAW_IN_xxx_FRAME flags.
+ */
+static inline uint16_t mavlink_msg_storm32_gimbal_manager_control_get_q(const mavlink_message_t* msg, float *q)
+{
+ return _MAV_RETURN_float_array(msg, q, 4, 0);
+}
+
+/**
+ * @brief Get field angular_velocity_x from storm32_gimbal_manager_control message
+ *
+ * @return [rad/s] X component of angular velocity (positive: roll to the right). NaN to be ignored.
+ */
+static inline float mavlink_msg_storm32_gimbal_manager_control_get_angular_velocity_x(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 16);
+}
+
+/**
+ * @brief Get field angular_velocity_y from storm32_gimbal_manager_control message
+ *
+ * @return [rad/s] Y component of angular velocity (positive: tilt up). NaN to be ignored.
+ */
+static inline float mavlink_msg_storm32_gimbal_manager_control_get_angular_velocity_y(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 20);
+}
+
+/**
+ * @brief Get field angular_velocity_z from storm32_gimbal_manager_control message
+ *
+ * @return [rad/s] Z component of angular velocity (positive: pan to the right). NaN to be ignored. The frame is determined by the GIMBAL_DEVICE_FLAGS_YAW_IN_xxx_FRAME flags.
+ */
+static inline float mavlink_msg_storm32_gimbal_manager_control_get_angular_velocity_z(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 24);
+}
+
+/**
+ * @brief Decode a storm32_gimbal_manager_control message into a struct
+ *
+ * @param msg The message to decode
+ * @param storm32_gimbal_manager_control C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_storm32_gimbal_manager_control_decode(const mavlink_message_t* msg, mavlink_storm32_gimbal_manager_control_t* storm32_gimbal_manager_control)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_storm32_gimbal_manager_control_get_q(msg, storm32_gimbal_manager_control->q);
+ storm32_gimbal_manager_control->angular_velocity_x = mavlink_msg_storm32_gimbal_manager_control_get_angular_velocity_x(msg);
+ storm32_gimbal_manager_control->angular_velocity_y = mavlink_msg_storm32_gimbal_manager_control_get_angular_velocity_y(msg);
+ storm32_gimbal_manager_control->angular_velocity_z = mavlink_msg_storm32_gimbal_manager_control_get_angular_velocity_z(msg);
+ storm32_gimbal_manager_control->device_flags = mavlink_msg_storm32_gimbal_manager_control_get_device_flags(msg);
+ storm32_gimbal_manager_control->manager_flags = mavlink_msg_storm32_gimbal_manager_control_get_manager_flags(msg);
+ storm32_gimbal_manager_control->target_system = mavlink_msg_storm32_gimbal_manager_control_get_target_system(msg);
+ storm32_gimbal_manager_control->target_component = mavlink_msg_storm32_gimbal_manager_control_get_target_component(msg);
+ storm32_gimbal_manager_control->gimbal_id = mavlink_msg_storm32_gimbal_manager_control_get_gimbal_id(msg);
+ storm32_gimbal_manager_control->client = mavlink_msg_storm32_gimbal_manager_control_get_client(msg);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_LEN? msg->len : MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_LEN;
+ memset(storm32_gimbal_manager_control, 0, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_LEN);
+ memcpy(storm32_gimbal_manager_control, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/storm32/mavlink_msg_storm32_gimbal_manager_control_pitchyaw.h b/lib/main/MAVLink/storm32/mavlink_msg_storm32_gimbal_manager_control_pitchyaw.h
new file mode 100644
index 00000000000..1681e00b67c
--- /dev/null
+++ b/lib/main/MAVLink/storm32/mavlink_msg_storm32_gimbal_manager_control_pitchyaw.h
@@ -0,0 +1,512 @@
+#pragma once
+// MESSAGE STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW PACKING
+
+#define MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW 60013
+
+
+typedef struct __mavlink_storm32_gimbal_manager_control_pitchyaw_t {
+ float pitch; /*< [rad] Pitch/tilt angle (positive: tilt up). NaN to be ignored.*/
+ float yaw; /*< [rad] Yaw/pan angle (positive: pan the right). NaN to be ignored. The frame is determined by the GIMBAL_DEVICE_FLAGS_YAW_IN_xxx_FRAME flags.*/
+ float pitch_rate; /*< [rad/s] Pitch/tilt angular rate (positive: tilt up). NaN to be ignored.*/
+ float yaw_rate; /*< [rad/s] Yaw/pan angular rate (positive: pan to the right). NaN to be ignored. The frame is determined by the GIMBAL_DEVICE_FLAGS_YAW_IN_xxx_FRAME flags.*/
+ uint16_t device_flags; /*< Gimbal device flags to be applied (UINT16_MAX to be ignored). Same flags as used in GIMBAL_DEVICE_SET_ATTITUDE.*/
+ uint16_t manager_flags; /*< Gimbal manager flags to be applied (0 to be ignored).*/
+ uint8_t target_system; /*< System ID*/
+ uint8_t target_component; /*< Component ID*/
+ uint8_t gimbal_id; /*< Gimbal ID of the gimbal manager to address (component ID or 1-6 for non-MAVLink gimbal, 0 for all gimbals). Send command multiple times for more than one but not all gimbals.*/
+ uint8_t client; /*< Client which is contacting the gimbal manager (must be set).*/
+} mavlink_storm32_gimbal_manager_control_pitchyaw_t;
+
+#define MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_LEN 24
+#define MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_MIN_LEN 24
+#define MAVLINK_MSG_ID_60013_LEN 24
+#define MAVLINK_MSG_ID_60013_MIN_LEN 24
+
+#define MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_CRC 129
+#define MAVLINK_MSG_ID_60013_CRC 129
+
+
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW { \
+ 60013, \
+ "STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW", \
+ 10, \
+ { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_storm32_gimbal_manager_control_pitchyaw_t, target_system) }, \
+ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 21, offsetof(mavlink_storm32_gimbal_manager_control_pitchyaw_t, target_component) }, \
+ { "gimbal_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 22, offsetof(mavlink_storm32_gimbal_manager_control_pitchyaw_t, gimbal_id) }, \
+ { "client", NULL, MAVLINK_TYPE_UINT8_T, 0, 23, offsetof(mavlink_storm32_gimbal_manager_control_pitchyaw_t, client) }, \
+ { "device_flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_storm32_gimbal_manager_control_pitchyaw_t, device_flags) }, \
+ { "manager_flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_storm32_gimbal_manager_control_pitchyaw_t, manager_flags) }, \
+ { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_storm32_gimbal_manager_control_pitchyaw_t, pitch) }, \
+ { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_storm32_gimbal_manager_control_pitchyaw_t, yaw) }, \
+ { "pitch_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_storm32_gimbal_manager_control_pitchyaw_t, pitch_rate) }, \
+ { "yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_storm32_gimbal_manager_control_pitchyaw_t, yaw_rate) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW { \
+ "STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW", \
+ 10, \
+ { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_storm32_gimbal_manager_control_pitchyaw_t, target_system) }, \
+ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 21, offsetof(mavlink_storm32_gimbal_manager_control_pitchyaw_t, target_component) }, \
+ { "gimbal_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 22, offsetof(mavlink_storm32_gimbal_manager_control_pitchyaw_t, gimbal_id) }, \
+ { "client", NULL, MAVLINK_TYPE_UINT8_T, 0, 23, offsetof(mavlink_storm32_gimbal_manager_control_pitchyaw_t, client) }, \
+ { "device_flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_storm32_gimbal_manager_control_pitchyaw_t, device_flags) }, \
+ { "manager_flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_storm32_gimbal_manager_control_pitchyaw_t, manager_flags) }, \
+ { "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_storm32_gimbal_manager_control_pitchyaw_t, pitch) }, \
+ { "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_storm32_gimbal_manager_control_pitchyaw_t, yaw) }, \
+ { "pitch_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_storm32_gimbal_manager_control_pitchyaw_t, pitch_rate) }, \
+ { "yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_storm32_gimbal_manager_control_pitchyaw_t, yaw_rate) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a storm32_gimbal_manager_control_pitchyaw 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 target_system System ID
+ * @param target_component Component ID
+ * @param gimbal_id Gimbal ID of the gimbal manager to address (component ID or 1-6 for non-MAVLink gimbal, 0 for all gimbals). Send command multiple times for more than one but not all gimbals.
+ * @param client Client which is contacting the gimbal manager (must be set).
+ * @param device_flags Gimbal device flags to be applied (UINT16_MAX to be ignored). Same flags as used in GIMBAL_DEVICE_SET_ATTITUDE.
+ * @param manager_flags Gimbal manager flags to be applied (0 to be ignored).
+ * @param pitch [rad] Pitch/tilt angle (positive: tilt up). NaN to be ignored.
+ * @param yaw [rad] Yaw/pan angle (positive: pan the right). NaN to be ignored. The frame is determined by the GIMBAL_DEVICE_FLAGS_YAW_IN_xxx_FRAME flags.
+ * @param pitch_rate [rad/s] Pitch/tilt angular rate (positive: tilt up). NaN to be ignored.
+ * @param yaw_rate [rad/s] Yaw/pan angular rate (positive: pan to the right). NaN to be ignored. The frame is determined by the GIMBAL_DEVICE_FLAGS_YAW_IN_xxx_FRAME flags.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_storm32_gimbal_manager_control_pitchyaw_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint8_t target_system, uint8_t target_component, uint8_t gimbal_id, uint8_t client, uint16_t device_flags, uint16_t manager_flags, float pitch, float yaw, float pitch_rate, float yaw_rate)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_LEN];
+ _mav_put_float(buf, 0, pitch);
+ _mav_put_float(buf, 4, yaw);
+ _mav_put_float(buf, 8, pitch_rate);
+ _mav_put_float(buf, 12, yaw_rate);
+ _mav_put_uint16_t(buf, 16, device_flags);
+ _mav_put_uint16_t(buf, 18, manager_flags);
+ _mav_put_uint8_t(buf, 20, target_system);
+ _mav_put_uint8_t(buf, 21, target_component);
+ _mav_put_uint8_t(buf, 22, gimbal_id);
+ _mav_put_uint8_t(buf, 23, client);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_LEN);
+#else
+ mavlink_storm32_gimbal_manager_control_pitchyaw_t packet;
+ packet.pitch = pitch;
+ packet.yaw = yaw;
+ packet.pitch_rate = pitch_rate;
+ packet.yaw_rate = yaw_rate;
+ packet.device_flags = device_flags;
+ packet.manager_flags = manager_flags;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.gimbal_id = gimbal_id;
+ packet.client = client;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_MIN_LEN, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_LEN, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_CRC);
+}
+
+/**
+ * @brief Pack a storm32_gimbal_manager_control_pitchyaw 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 target_system System ID
+ * @param target_component Component ID
+ * @param gimbal_id Gimbal ID of the gimbal manager to address (component ID or 1-6 for non-MAVLink gimbal, 0 for all gimbals). Send command multiple times for more than one but not all gimbals.
+ * @param client Client which is contacting the gimbal manager (must be set).
+ * @param device_flags Gimbal device flags to be applied (UINT16_MAX to be ignored). Same flags as used in GIMBAL_DEVICE_SET_ATTITUDE.
+ * @param manager_flags Gimbal manager flags to be applied (0 to be ignored).
+ * @param pitch [rad] Pitch/tilt angle (positive: tilt up). NaN to be ignored.
+ * @param yaw [rad] Yaw/pan angle (positive: pan the right). NaN to be ignored. The frame is determined by the GIMBAL_DEVICE_FLAGS_YAW_IN_xxx_FRAME flags.
+ * @param pitch_rate [rad/s] Pitch/tilt angular rate (positive: tilt up). NaN to be ignored.
+ * @param yaw_rate [rad/s] Yaw/pan angular rate (positive: pan to the right). NaN to be ignored. The frame is determined by the GIMBAL_DEVICE_FLAGS_YAW_IN_xxx_FRAME flags.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_storm32_gimbal_manager_control_pitchyaw_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ uint8_t target_system, uint8_t target_component, uint8_t gimbal_id, uint8_t client, uint16_t device_flags, uint16_t manager_flags, float pitch, float yaw, float pitch_rate, float yaw_rate)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_LEN];
+ _mav_put_float(buf, 0, pitch);
+ _mav_put_float(buf, 4, yaw);
+ _mav_put_float(buf, 8, pitch_rate);
+ _mav_put_float(buf, 12, yaw_rate);
+ _mav_put_uint16_t(buf, 16, device_flags);
+ _mav_put_uint16_t(buf, 18, manager_flags);
+ _mav_put_uint8_t(buf, 20, target_system);
+ _mav_put_uint8_t(buf, 21, target_component);
+ _mav_put_uint8_t(buf, 22, gimbal_id);
+ _mav_put_uint8_t(buf, 23, client);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_LEN);
+#else
+ mavlink_storm32_gimbal_manager_control_pitchyaw_t packet;
+ packet.pitch = pitch;
+ packet.yaw = yaw;
+ packet.pitch_rate = pitch_rate;
+ packet.yaw_rate = yaw_rate;
+ packet.device_flags = device_flags;
+ packet.manager_flags = manager_flags;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.gimbal_id = gimbal_id;
+ packet.client = client;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_MIN_LEN, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_LEN, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_MIN_LEN, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a storm32_gimbal_manager_control_pitchyaw 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 target_system System ID
+ * @param target_component Component ID
+ * @param gimbal_id Gimbal ID of the gimbal manager to address (component ID or 1-6 for non-MAVLink gimbal, 0 for all gimbals). Send command multiple times for more than one but not all gimbals.
+ * @param client Client which is contacting the gimbal manager (must be set).
+ * @param device_flags Gimbal device flags to be applied (UINT16_MAX to be ignored). Same flags as used in GIMBAL_DEVICE_SET_ATTITUDE.
+ * @param manager_flags Gimbal manager flags to be applied (0 to be ignored).
+ * @param pitch [rad] Pitch/tilt angle (positive: tilt up). NaN to be ignored.
+ * @param yaw [rad] Yaw/pan angle (positive: pan the right). NaN to be ignored. The frame is determined by the GIMBAL_DEVICE_FLAGS_YAW_IN_xxx_FRAME flags.
+ * @param pitch_rate [rad/s] Pitch/tilt angular rate (positive: tilt up). NaN to be ignored.
+ * @param yaw_rate [rad/s] Yaw/pan angular rate (positive: pan to the right). NaN to be ignored. The frame is determined by the GIMBAL_DEVICE_FLAGS_YAW_IN_xxx_FRAME flags.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_storm32_gimbal_manager_control_pitchyaw_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint8_t target_system,uint8_t target_component,uint8_t gimbal_id,uint8_t client,uint16_t device_flags,uint16_t manager_flags,float pitch,float yaw,float pitch_rate,float yaw_rate)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_LEN];
+ _mav_put_float(buf, 0, pitch);
+ _mav_put_float(buf, 4, yaw);
+ _mav_put_float(buf, 8, pitch_rate);
+ _mav_put_float(buf, 12, yaw_rate);
+ _mav_put_uint16_t(buf, 16, device_flags);
+ _mav_put_uint16_t(buf, 18, manager_flags);
+ _mav_put_uint8_t(buf, 20, target_system);
+ _mav_put_uint8_t(buf, 21, target_component);
+ _mav_put_uint8_t(buf, 22, gimbal_id);
+ _mav_put_uint8_t(buf, 23, client);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_LEN);
+#else
+ mavlink_storm32_gimbal_manager_control_pitchyaw_t packet;
+ packet.pitch = pitch;
+ packet.yaw = yaw;
+ packet.pitch_rate = pitch_rate;
+ packet.yaw_rate = yaw_rate;
+ packet.device_flags = device_flags;
+ packet.manager_flags = manager_flags;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.gimbal_id = gimbal_id;
+ packet.client = client;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_MIN_LEN, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_LEN, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_CRC);
+}
+
+/**
+ * @brief Encode a storm32_gimbal_manager_control_pitchyaw 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 storm32_gimbal_manager_control_pitchyaw C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_storm32_gimbal_manager_control_pitchyaw_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_storm32_gimbal_manager_control_pitchyaw_t* storm32_gimbal_manager_control_pitchyaw)
+{
+ return mavlink_msg_storm32_gimbal_manager_control_pitchyaw_pack(system_id, component_id, msg, storm32_gimbal_manager_control_pitchyaw->target_system, storm32_gimbal_manager_control_pitchyaw->target_component, storm32_gimbal_manager_control_pitchyaw->gimbal_id, storm32_gimbal_manager_control_pitchyaw->client, storm32_gimbal_manager_control_pitchyaw->device_flags, storm32_gimbal_manager_control_pitchyaw->manager_flags, storm32_gimbal_manager_control_pitchyaw->pitch, storm32_gimbal_manager_control_pitchyaw->yaw, storm32_gimbal_manager_control_pitchyaw->pitch_rate, storm32_gimbal_manager_control_pitchyaw->yaw_rate);
+}
+
+/**
+ * @brief Encode a storm32_gimbal_manager_control_pitchyaw 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 storm32_gimbal_manager_control_pitchyaw C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_storm32_gimbal_manager_control_pitchyaw_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_storm32_gimbal_manager_control_pitchyaw_t* storm32_gimbal_manager_control_pitchyaw)
+{
+ return mavlink_msg_storm32_gimbal_manager_control_pitchyaw_pack_chan(system_id, component_id, chan, msg, storm32_gimbal_manager_control_pitchyaw->target_system, storm32_gimbal_manager_control_pitchyaw->target_component, storm32_gimbal_manager_control_pitchyaw->gimbal_id, storm32_gimbal_manager_control_pitchyaw->client, storm32_gimbal_manager_control_pitchyaw->device_flags, storm32_gimbal_manager_control_pitchyaw->manager_flags, storm32_gimbal_manager_control_pitchyaw->pitch, storm32_gimbal_manager_control_pitchyaw->yaw, storm32_gimbal_manager_control_pitchyaw->pitch_rate, storm32_gimbal_manager_control_pitchyaw->yaw_rate);
+}
+
+/**
+ * @brief Encode a storm32_gimbal_manager_control_pitchyaw 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 storm32_gimbal_manager_control_pitchyaw C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_storm32_gimbal_manager_control_pitchyaw_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_storm32_gimbal_manager_control_pitchyaw_t* storm32_gimbal_manager_control_pitchyaw)
+{
+ return mavlink_msg_storm32_gimbal_manager_control_pitchyaw_pack_status(system_id, component_id, _status, msg, storm32_gimbal_manager_control_pitchyaw->target_system, storm32_gimbal_manager_control_pitchyaw->target_component, storm32_gimbal_manager_control_pitchyaw->gimbal_id, storm32_gimbal_manager_control_pitchyaw->client, storm32_gimbal_manager_control_pitchyaw->device_flags, storm32_gimbal_manager_control_pitchyaw->manager_flags, storm32_gimbal_manager_control_pitchyaw->pitch, storm32_gimbal_manager_control_pitchyaw->yaw, storm32_gimbal_manager_control_pitchyaw->pitch_rate, storm32_gimbal_manager_control_pitchyaw->yaw_rate);
+}
+
+/**
+ * @brief Send a storm32_gimbal_manager_control_pitchyaw message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param target_system System ID
+ * @param target_component Component ID
+ * @param gimbal_id Gimbal ID of the gimbal manager to address (component ID or 1-6 for non-MAVLink gimbal, 0 for all gimbals). Send command multiple times for more than one but not all gimbals.
+ * @param client Client which is contacting the gimbal manager (must be set).
+ * @param device_flags Gimbal device flags to be applied (UINT16_MAX to be ignored). Same flags as used in GIMBAL_DEVICE_SET_ATTITUDE.
+ * @param manager_flags Gimbal manager flags to be applied (0 to be ignored).
+ * @param pitch [rad] Pitch/tilt angle (positive: tilt up). NaN to be ignored.
+ * @param yaw [rad] Yaw/pan angle (positive: pan the right). NaN to be ignored. The frame is determined by the GIMBAL_DEVICE_FLAGS_YAW_IN_xxx_FRAME flags.
+ * @param pitch_rate [rad/s] Pitch/tilt angular rate (positive: tilt up). NaN to be ignored.
+ * @param yaw_rate [rad/s] Yaw/pan angular rate (positive: pan to the right). NaN to be ignored. The frame is determined by the GIMBAL_DEVICE_FLAGS_YAW_IN_xxx_FRAME flags.
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_storm32_gimbal_manager_control_pitchyaw_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t gimbal_id, uint8_t client, uint16_t device_flags, uint16_t manager_flags, float pitch, float yaw, float pitch_rate, float yaw_rate)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_LEN];
+ _mav_put_float(buf, 0, pitch);
+ _mav_put_float(buf, 4, yaw);
+ _mav_put_float(buf, 8, pitch_rate);
+ _mav_put_float(buf, 12, yaw_rate);
+ _mav_put_uint16_t(buf, 16, device_flags);
+ _mav_put_uint16_t(buf, 18, manager_flags);
+ _mav_put_uint8_t(buf, 20, target_system);
+ _mav_put_uint8_t(buf, 21, target_component);
+ _mav_put_uint8_t(buf, 22, gimbal_id);
+ _mav_put_uint8_t(buf, 23, client);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW, buf, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_MIN_LEN, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_LEN, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_CRC);
+#else
+ mavlink_storm32_gimbal_manager_control_pitchyaw_t packet;
+ packet.pitch = pitch;
+ packet.yaw = yaw;
+ packet.pitch_rate = pitch_rate;
+ packet.yaw_rate = yaw_rate;
+ packet.device_flags = device_flags;
+ packet.manager_flags = manager_flags;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.gimbal_id = gimbal_id;
+ packet.client = client;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW, (const char *)&packet, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_MIN_LEN, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_LEN, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_CRC);
+#endif
+}
+
+/**
+ * @brief Send a storm32_gimbal_manager_control_pitchyaw message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_storm32_gimbal_manager_control_pitchyaw_send_struct(mavlink_channel_t chan, const mavlink_storm32_gimbal_manager_control_pitchyaw_t* storm32_gimbal_manager_control_pitchyaw)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_storm32_gimbal_manager_control_pitchyaw_send(chan, storm32_gimbal_manager_control_pitchyaw->target_system, storm32_gimbal_manager_control_pitchyaw->target_component, storm32_gimbal_manager_control_pitchyaw->gimbal_id, storm32_gimbal_manager_control_pitchyaw->client, storm32_gimbal_manager_control_pitchyaw->device_flags, storm32_gimbal_manager_control_pitchyaw->manager_flags, storm32_gimbal_manager_control_pitchyaw->pitch, storm32_gimbal_manager_control_pitchyaw->yaw, storm32_gimbal_manager_control_pitchyaw->pitch_rate, storm32_gimbal_manager_control_pitchyaw->yaw_rate);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW, (const char *)storm32_gimbal_manager_control_pitchyaw, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_MIN_LEN, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_LEN, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_storm32_gimbal_manager_control_pitchyaw_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t gimbal_id, uint8_t client, uint16_t device_flags, uint16_t manager_flags, float pitch, float yaw, float pitch_rate, float yaw_rate)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_float(buf, 0, pitch);
+ _mav_put_float(buf, 4, yaw);
+ _mav_put_float(buf, 8, pitch_rate);
+ _mav_put_float(buf, 12, yaw_rate);
+ _mav_put_uint16_t(buf, 16, device_flags);
+ _mav_put_uint16_t(buf, 18, manager_flags);
+ _mav_put_uint8_t(buf, 20, target_system);
+ _mav_put_uint8_t(buf, 21, target_component);
+ _mav_put_uint8_t(buf, 22, gimbal_id);
+ _mav_put_uint8_t(buf, 23, client);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW, buf, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_MIN_LEN, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_LEN, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_CRC);
+#else
+ mavlink_storm32_gimbal_manager_control_pitchyaw_t *packet = (mavlink_storm32_gimbal_manager_control_pitchyaw_t *)msgbuf;
+ packet->pitch = pitch;
+ packet->yaw = yaw;
+ packet->pitch_rate = pitch_rate;
+ packet->yaw_rate = yaw_rate;
+ packet->device_flags = device_flags;
+ packet->manager_flags = manager_flags;
+ packet->target_system = target_system;
+ packet->target_component = target_component;
+ packet->gimbal_id = gimbal_id;
+ packet->client = client;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW, (const char *)packet, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_MIN_LEN, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_LEN, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW UNPACKING
+
+
+/**
+ * @brief Get field target_system from storm32_gimbal_manager_control_pitchyaw message
+ *
+ * @return System ID
+ */
+static inline uint8_t mavlink_msg_storm32_gimbal_manager_control_pitchyaw_get_target_system(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 20);
+}
+
+/**
+ * @brief Get field target_component from storm32_gimbal_manager_control_pitchyaw message
+ *
+ * @return Component ID
+ */
+static inline uint8_t mavlink_msg_storm32_gimbal_manager_control_pitchyaw_get_target_component(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 21);
+}
+
+/**
+ * @brief Get field gimbal_id from storm32_gimbal_manager_control_pitchyaw message
+ *
+ * @return Gimbal ID of the gimbal manager to address (component ID or 1-6 for non-MAVLink gimbal, 0 for all gimbals). Send command multiple times for more than one but not all gimbals.
+ */
+static inline uint8_t mavlink_msg_storm32_gimbal_manager_control_pitchyaw_get_gimbal_id(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 22);
+}
+
+/**
+ * @brief Get field client from storm32_gimbal_manager_control_pitchyaw message
+ *
+ * @return Client which is contacting the gimbal manager (must be set).
+ */
+static inline uint8_t mavlink_msg_storm32_gimbal_manager_control_pitchyaw_get_client(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 23);
+}
+
+/**
+ * @brief Get field device_flags from storm32_gimbal_manager_control_pitchyaw message
+ *
+ * @return Gimbal device flags to be applied (UINT16_MAX to be ignored). Same flags as used in GIMBAL_DEVICE_SET_ATTITUDE.
+ */
+static inline uint16_t mavlink_msg_storm32_gimbal_manager_control_pitchyaw_get_device_flags(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 16);
+}
+
+/**
+ * @brief Get field manager_flags from storm32_gimbal_manager_control_pitchyaw message
+ *
+ * @return Gimbal manager flags to be applied (0 to be ignored).
+ */
+static inline uint16_t mavlink_msg_storm32_gimbal_manager_control_pitchyaw_get_manager_flags(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 18);
+}
+
+/**
+ * @brief Get field pitch from storm32_gimbal_manager_control_pitchyaw message
+ *
+ * @return [rad] Pitch/tilt angle (positive: tilt up). NaN to be ignored.
+ */
+static inline float mavlink_msg_storm32_gimbal_manager_control_pitchyaw_get_pitch(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 0);
+}
+
+/**
+ * @brief Get field yaw from storm32_gimbal_manager_control_pitchyaw message
+ *
+ * @return [rad] Yaw/pan angle (positive: pan the right). NaN to be ignored. The frame is determined by the GIMBAL_DEVICE_FLAGS_YAW_IN_xxx_FRAME flags.
+ */
+static inline float mavlink_msg_storm32_gimbal_manager_control_pitchyaw_get_yaw(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 4);
+}
+
+/**
+ * @brief Get field pitch_rate from storm32_gimbal_manager_control_pitchyaw message
+ *
+ * @return [rad/s] Pitch/tilt angular rate (positive: tilt up). NaN to be ignored.
+ */
+static inline float mavlink_msg_storm32_gimbal_manager_control_pitchyaw_get_pitch_rate(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 8);
+}
+
+/**
+ * @brief Get field yaw_rate from storm32_gimbal_manager_control_pitchyaw message
+ *
+ * @return [rad/s] Yaw/pan angular rate (positive: pan to the right). NaN to be ignored. The frame is determined by the GIMBAL_DEVICE_FLAGS_YAW_IN_xxx_FRAME flags.
+ */
+static inline float mavlink_msg_storm32_gimbal_manager_control_pitchyaw_get_yaw_rate(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 12);
+}
+
+/**
+ * @brief Decode a storm32_gimbal_manager_control_pitchyaw message into a struct
+ *
+ * @param msg The message to decode
+ * @param storm32_gimbal_manager_control_pitchyaw C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_storm32_gimbal_manager_control_pitchyaw_decode(const mavlink_message_t* msg, mavlink_storm32_gimbal_manager_control_pitchyaw_t* storm32_gimbal_manager_control_pitchyaw)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ storm32_gimbal_manager_control_pitchyaw->pitch = mavlink_msg_storm32_gimbal_manager_control_pitchyaw_get_pitch(msg);
+ storm32_gimbal_manager_control_pitchyaw->yaw = mavlink_msg_storm32_gimbal_manager_control_pitchyaw_get_yaw(msg);
+ storm32_gimbal_manager_control_pitchyaw->pitch_rate = mavlink_msg_storm32_gimbal_manager_control_pitchyaw_get_pitch_rate(msg);
+ storm32_gimbal_manager_control_pitchyaw->yaw_rate = mavlink_msg_storm32_gimbal_manager_control_pitchyaw_get_yaw_rate(msg);
+ storm32_gimbal_manager_control_pitchyaw->device_flags = mavlink_msg_storm32_gimbal_manager_control_pitchyaw_get_device_flags(msg);
+ storm32_gimbal_manager_control_pitchyaw->manager_flags = mavlink_msg_storm32_gimbal_manager_control_pitchyaw_get_manager_flags(msg);
+ storm32_gimbal_manager_control_pitchyaw->target_system = mavlink_msg_storm32_gimbal_manager_control_pitchyaw_get_target_system(msg);
+ storm32_gimbal_manager_control_pitchyaw->target_component = mavlink_msg_storm32_gimbal_manager_control_pitchyaw_get_target_component(msg);
+ storm32_gimbal_manager_control_pitchyaw->gimbal_id = mavlink_msg_storm32_gimbal_manager_control_pitchyaw_get_gimbal_id(msg);
+ storm32_gimbal_manager_control_pitchyaw->client = mavlink_msg_storm32_gimbal_manager_control_pitchyaw_get_client(msg);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_LEN? msg->len : MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_LEN;
+ memset(storm32_gimbal_manager_control_pitchyaw, 0, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_LEN);
+ memcpy(storm32_gimbal_manager_control_pitchyaw, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/storm32/mavlink_msg_storm32_gimbal_manager_correct_roll.h b/lib/main/MAVLink/storm32/mavlink_msg_storm32_gimbal_manager_correct_roll.h
new file mode 100644
index 00000000000..a0455920bb9
--- /dev/null
+++ b/lib/main/MAVLink/storm32/mavlink_msg_storm32_gimbal_manager_correct_roll.h
@@ -0,0 +1,372 @@
+#pragma once
+// MESSAGE STORM32_GIMBAL_MANAGER_CORRECT_ROLL PACKING
+
+#define MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CORRECT_ROLL 60014
+
+
+typedef struct __mavlink_storm32_gimbal_manager_correct_roll_t {
+ float roll; /*< [rad] Roll angle (positive to roll to the right).*/
+ uint8_t target_system; /*< System ID*/
+ uint8_t target_component; /*< Component ID*/
+ uint8_t gimbal_id; /*< Gimbal ID of the gimbal manager to address (component ID or 1-6 for non-MAVLink gimbal, 0 for all gimbals). Send command multiple times for more than one but not all gimbals.*/
+ uint8_t client; /*< Client which is contacting the gimbal manager (must be set).*/
+} mavlink_storm32_gimbal_manager_correct_roll_t;
+
+#define MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CORRECT_ROLL_LEN 8
+#define MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CORRECT_ROLL_MIN_LEN 8
+#define MAVLINK_MSG_ID_60014_LEN 8
+#define MAVLINK_MSG_ID_60014_MIN_LEN 8
+
+#define MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CORRECT_ROLL_CRC 134
+#define MAVLINK_MSG_ID_60014_CRC 134
+
+
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_STORM32_GIMBAL_MANAGER_CORRECT_ROLL { \
+ 60014, \
+ "STORM32_GIMBAL_MANAGER_CORRECT_ROLL", \
+ 5, \
+ { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_storm32_gimbal_manager_correct_roll_t, target_system) }, \
+ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_storm32_gimbal_manager_correct_roll_t, target_component) }, \
+ { "gimbal_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_storm32_gimbal_manager_correct_roll_t, gimbal_id) }, \
+ { "client", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_storm32_gimbal_manager_correct_roll_t, client) }, \
+ { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_storm32_gimbal_manager_correct_roll_t, roll) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_STORM32_GIMBAL_MANAGER_CORRECT_ROLL { \
+ "STORM32_GIMBAL_MANAGER_CORRECT_ROLL", \
+ 5, \
+ { { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_storm32_gimbal_manager_correct_roll_t, target_system) }, \
+ { "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_storm32_gimbal_manager_correct_roll_t, target_component) }, \
+ { "gimbal_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_storm32_gimbal_manager_correct_roll_t, gimbal_id) }, \
+ { "client", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_storm32_gimbal_manager_correct_roll_t, client) }, \
+ { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_storm32_gimbal_manager_correct_roll_t, roll) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a storm32_gimbal_manager_correct_roll 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 target_system System ID
+ * @param target_component Component ID
+ * @param gimbal_id Gimbal ID of the gimbal manager to address (component ID or 1-6 for non-MAVLink gimbal, 0 for all gimbals). Send command multiple times for more than one but not all gimbals.
+ * @param client Client which is contacting the gimbal manager (must be set).
+ * @param roll [rad] Roll angle (positive to roll to the right).
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_storm32_gimbal_manager_correct_roll_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint8_t target_system, uint8_t target_component, uint8_t gimbal_id, uint8_t client, float roll)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CORRECT_ROLL_LEN];
+ _mav_put_float(buf, 0, roll);
+ _mav_put_uint8_t(buf, 4, target_system);
+ _mav_put_uint8_t(buf, 5, target_component);
+ _mav_put_uint8_t(buf, 6, gimbal_id);
+ _mav_put_uint8_t(buf, 7, client);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CORRECT_ROLL_LEN);
+#else
+ mavlink_storm32_gimbal_manager_correct_roll_t packet;
+ packet.roll = roll;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.gimbal_id = gimbal_id;
+ packet.client = client;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CORRECT_ROLL_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CORRECT_ROLL;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CORRECT_ROLL_MIN_LEN, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CORRECT_ROLL_LEN, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CORRECT_ROLL_CRC);
+}
+
+/**
+ * @brief Pack a storm32_gimbal_manager_correct_roll 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 target_system System ID
+ * @param target_component Component ID
+ * @param gimbal_id Gimbal ID of the gimbal manager to address (component ID or 1-6 for non-MAVLink gimbal, 0 for all gimbals). Send command multiple times for more than one but not all gimbals.
+ * @param client Client which is contacting the gimbal manager (must be set).
+ * @param roll [rad] Roll angle (positive to roll to the right).
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_storm32_gimbal_manager_correct_roll_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ uint8_t target_system, uint8_t target_component, uint8_t gimbal_id, uint8_t client, float roll)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CORRECT_ROLL_LEN];
+ _mav_put_float(buf, 0, roll);
+ _mav_put_uint8_t(buf, 4, target_system);
+ _mav_put_uint8_t(buf, 5, target_component);
+ _mav_put_uint8_t(buf, 6, gimbal_id);
+ _mav_put_uint8_t(buf, 7, client);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CORRECT_ROLL_LEN);
+#else
+ mavlink_storm32_gimbal_manager_correct_roll_t packet;
+ packet.roll = roll;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.gimbal_id = gimbal_id;
+ packet.client = client;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CORRECT_ROLL_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CORRECT_ROLL;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CORRECT_ROLL_MIN_LEN, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CORRECT_ROLL_LEN, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CORRECT_ROLL_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CORRECT_ROLL_MIN_LEN, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CORRECT_ROLL_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a storm32_gimbal_manager_correct_roll 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 target_system System ID
+ * @param target_component Component ID
+ * @param gimbal_id Gimbal ID of the gimbal manager to address (component ID or 1-6 for non-MAVLink gimbal, 0 for all gimbals). Send command multiple times for more than one but not all gimbals.
+ * @param client Client which is contacting the gimbal manager (must be set).
+ * @param roll [rad] Roll angle (positive to roll to the right).
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_storm32_gimbal_manager_correct_roll_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint8_t target_system,uint8_t target_component,uint8_t gimbal_id,uint8_t client,float roll)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CORRECT_ROLL_LEN];
+ _mav_put_float(buf, 0, roll);
+ _mav_put_uint8_t(buf, 4, target_system);
+ _mav_put_uint8_t(buf, 5, target_component);
+ _mav_put_uint8_t(buf, 6, gimbal_id);
+ _mav_put_uint8_t(buf, 7, client);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CORRECT_ROLL_LEN);
+#else
+ mavlink_storm32_gimbal_manager_correct_roll_t packet;
+ packet.roll = roll;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.gimbal_id = gimbal_id;
+ packet.client = client;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CORRECT_ROLL_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CORRECT_ROLL;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CORRECT_ROLL_MIN_LEN, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CORRECT_ROLL_LEN, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CORRECT_ROLL_CRC);
+}
+
+/**
+ * @brief Encode a storm32_gimbal_manager_correct_roll 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 storm32_gimbal_manager_correct_roll C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_storm32_gimbal_manager_correct_roll_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_storm32_gimbal_manager_correct_roll_t* storm32_gimbal_manager_correct_roll)
+{
+ return mavlink_msg_storm32_gimbal_manager_correct_roll_pack(system_id, component_id, msg, storm32_gimbal_manager_correct_roll->target_system, storm32_gimbal_manager_correct_roll->target_component, storm32_gimbal_manager_correct_roll->gimbal_id, storm32_gimbal_manager_correct_roll->client, storm32_gimbal_manager_correct_roll->roll);
+}
+
+/**
+ * @brief Encode a storm32_gimbal_manager_correct_roll 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 storm32_gimbal_manager_correct_roll C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_storm32_gimbal_manager_correct_roll_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_storm32_gimbal_manager_correct_roll_t* storm32_gimbal_manager_correct_roll)
+{
+ return mavlink_msg_storm32_gimbal_manager_correct_roll_pack_chan(system_id, component_id, chan, msg, storm32_gimbal_manager_correct_roll->target_system, storm32_gimbal_manager_correct_roll->target_component, storm32_gimbal_manager_correct_roll->gimbal_id, storm32_gimbal_manager_correct_roll->client, storm32_gimbal_manager_correct_roll->roll);
+}
+
+/**
+ * @brief Encode a storm32_gimbal_manager_correct_roll 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 storm32_gimbal_manager_correct_roll C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_storm32_gimbal_manager_correct_roll_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_storm32_gimbal_manager_correct_roll_t* storm32_gimbal_manager_correct_roll)
+{
+ return mavlink_msg_storm32_gimbal_manager_correct_roll_pack_status(system_id, component_id, _status, msg, storm32_gimbal_manager_correct_roll->target_system, storm32_gimbal_manager_correct_roll->target_component, storm32_gimbal_manager_correct_roll->gimbal_id, storm32_gimbal_manager_correct_roll->client, storm32_gimbal_manager_correct_roll->roll);
+}
+
+/**
+ * @brief Send a storm32_gimbal_manager_correct_roll message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param target_system System ID
+ * @param target_component Component ID
+ * @param gimbal_id Gimbal ID of the gimbal manager to address (component ID or 1-6 for non-MAVLink gimbal, 0 for all gimbals). Send command multiple times for more than one but not all gimbals.
+ * @param client Client which is contacting the gimbal manager (must be set).
+ * @param roll [rad] Roll angle (positive to roll to the right).
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_storm32_gimbal_manager_correct_roll_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t gimbal_id, uint8_t client, float roll)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CORRECT_ROLL_LEN];
+ _mav_put_float(buf, 0, roll);
+ _mav_put_uint8_t(buf, 4, target_system);
+ _mav_put_uint8_t(buf, 5, target_component);
+ _mav_put_uint8_t(buf, 6, gimbal_id);
+ _mav_put_uint8_t(buf, 7, client);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CORRECT_ROLL, buf, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CORRECT_ROLL_MIN_LEN, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CORRECT_ROLL_LEN, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CORRECT_ROLL_CRC);
+#else
+ mavlink_storm32_gimbal_manager_correct_roll_t packet;
+ packet.roll = roll;
+ packet.target_system = target_system;
+ packet.target_component = target_component;
+ packet.gimbal_id = gimbal_id;
+ packet.client = client;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CORRECT_ROLL, (const char *)&packet, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CORRECT_ROLL_MIN_LEN, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CORRECT_ROLL_LEN, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CORRECT_ROLL_CRC);
+#endif
+}
+
+/**
+ * @brief Send a storm32_gimbal_manager_correct_roll message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_storm32_gimbal_manager_correct_roll_send_struct(mavlink_channel_t chan, const mavlink_storm32_gimbal_manager_correct_roll_t* storm32_gimbal_manager_correct_roll)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_storm32_gimbal_manager_correct_roll_send(chan, storm32_gimbal_manager_correct_roll->target_system, storm32_gimbal_manager_correct_roll->target_component, storm32_gimbal_manager_correct_roll->gimbal_id, storm32_gimbal_manager_correct_roll->client, storm32_gimbal_manager_correct_roll->roll);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CORRECT_ROLL, (const char *)storm32_gimbal_manager_correct_roll, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CORRECT_ROLL_MIN_LEN, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CORRECT_ROLL_LEN, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CORRECT_ROLL_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CORRECT_ROLL_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_storm32_gimbal_manager_correct_roll_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t gimbal_id, uint8_t client, float roll)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_float(buf, 0, roll);
+ _mav_put_uint8_t(buf, 4, target_system);
+ _mav_put_uint8_t(buf, 5, target_component);
+ _mav_put_uint8_t(buf, 6, gimbal_id);
+ _mav_put_uint8_t(buf, 7, client);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CORRECT_ROLL, buf, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CORRECT_ROLL_MIN_LEN, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CORRECT_ROLL_LEN, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CORRECT_ROLL_CRC);
+#else
+ mavlink_storm32_gimbal_manager_correct_roll_t *packet = (mavlink_storm32_gimbal_manager_correct_roll_t *)msgbuf;
+ packet->roll = roll;
+ packet->target_system = target_system;
+ packet->target_component = target_component;
+ packet->gimbal_id = gimbal_id;
+ packet->client = client;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CORRECT_ROLL, (const char *)packet, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CORRECT_ROLL_MIN_LEN, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CORRECT_ROLL_LEN, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CORRECT_ROLL_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE STORM32_GIMBAL_MANAGER_CORRECT_ROLL UNPACKING
+
+
+/**
+ * @brief Get field target_system from storm32_gimbal_manager_correct_roll message
+ *
+ * @return System ID
+ */
+static inline uint8_t mavlink_msg_storm32_gimbal_manager_correct_roll_get_target_system(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 4);
+}
+
+/**
+ * @brief Get field target_component from storm32_gimbal_manager_correct_roll message
+ *
+ * @return Component ID
+ */
+static inline uint8_t mavlink_msg_storm32_gimbal_manager_correct_roll_get_target_component(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 5);
+}
+
+/**
+ * @brief Get field gimbal_id from storm32_gimbal_manager_correct_roll message
+ *
+ * @return Gimbal ID of the gimbal manager to address (component ID or 1-6 for non-MAVLink gimbal, 0 for all gimbals). Send command multiple times for more than one but not all gimbals.
+ */
+static inline uint8_t mavlink_msg_storm32_gimbal_manager_correct_roll_get_gimbal_id(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 6);
+}
+
+/**
+ * @brief Get field client from storm32_gimbal_manager_correct_roll message
+ *
+ * @return Client which is contacting the gimbal manager (must be set).
+ */
+static inline uint8_t mavlink_msg_storm32_gimbal_manager_correct_roll_get_client(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 7);
+}
+
+/**
+ * @brief Get field roll from storm32_gimbal_manager_correct_roll message
+ *
+ * @return [rad] Roll angle (positive to roll to the right).
+ */
+static inline float mavlink_msg_storm32_gimbal_manager_correct_roll_get_roll(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 0);
+}
+
+/**
+ * @brief Decode a storm32_gimbal_manager_correct_roll message into a struct
+ *
+ * @param msg The message to decode
+ * @param storm32_gimbal_manager_correct_roll C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_storm32_gimbal_manager_correct_roll_decode(const mavlink_message_t* msg, mavlink_storm32_gimbal_manager_correct_roll_t* storm32_gimbal_manager_correct_roll)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ storm32_gimbal_manager_correct_roll->roll = mavlink_msg_storm32_gimbal_manager_correct_roll_get_roll(msg);
+ storm32_gimbal_manager_correct_roll->target_system = mavlink_msg_storm32_gimbal_manager_correct_roll_get_target_system(msg);
+ storm32_gimbal_manager_correct_roll->target_component = mavlink_msg_storm32_gimbal_manager_correct_roll_get_target_component(msg);
+ storm32_gimbal_manager_correct_roll->gimbal_id = mavlink_msg_storm32_gimbal_manager_correct_roll_get_gimbal_id(msg);
+ storm32_gimbal_manager_correct_roll->client = mavlink_msg_storm32_gimbal_manager_correct_roll_get_client(msg);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CORRECT_ROLL_LEN? msg->len : MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CORRECT_ROLL_LEN;
+ memset(storm32_gimbal_manager_correct_roll, 0, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CORRECT_ROLL_LEN);
+ memcpy(storm32_gimbal_manager_correct_roll, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/storm32/mavlink_msg_storm32_gimbal_manager_information.h b/lib/main/MAVLink/storm32/mavlink_msg_storm32_gimbal_manager_information.h
new file mode 100644
index 00000000000..529f9a0d780
--- /dev/null
+++ b/lib/main/MAVLink/storm32/mavlink_msg_storm32_gimbal_manager_information.h
@@ -0,0 +1,484 @@
+#pragma once
+// MESSAGE STORM32_GIMBAL_MANAGER_INFORMATION PACKING
+
+#define MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_INFORMATION 60010
+
+
+typedef struct __mavlink_storm32_gimbal_manager_information_t {
+ uint32_t device_cap_flags; /*< Gimbal device capability flags. Same flags as reported by GIMBAL_DEVICE_INFORMATION. The flag is only 16 bit wide, but stored in 32 bit, for backwards compatibility (high word is zero).*/
+ uint32_t manager_cap_flags; /*< Gimbal manager capability flags.*/
+ float roll_min; /*< [rad] Hardware minimum roll angle (positive: roll to the right). NaN if unknown.*/
+ float roll_max; /*< [rad] Hardware maximum roll angle (positive: roll to the right). NaN if unknown.*/
+ float pitch_min; /*< [rad] Hardware minimum pitch/tilt angle (positive: tilt up). NaN if unknown.*/
+ float pitch_max; /*< [rad] Hardware maximum pitch/tilt angle (positive: tilt up). NaN if unknown.*/
+ float yaw_min; /*< [rad] Hardware minimum yaw/pan angle (positive: pan to the right, relative to the vehicle/gimbal base). NaN if unknown.*/
+ float yaw_max; /*< [rad] Hardware maximum yaw/pan angle (positive: pan to the right, relative to the vehicle/gimbal base). NaN if unknown.*/
+ uint8_t gimbal_id; /*< Gimbal ID (component ID or 1-6 for non-MAVLink gimbal) that this gimbal manager is responsible for.*/
+} mavlink_storm32_gimbal_manager_information_t;
+
+#define MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_INFORMATION_LEN 33
+#define MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_INFORMATION_MIN_LEN 33
+#define MAVLINK_MSG_ID_60010_LEN 33
+#define MAVLINK_MSG_ID_60010_MIN_LEN 33
+
+#define MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_INFORMATION_CRC 208
+#define MAVLINK_MSG_ID_60010_CRC 208
+
+
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_STORM32_GIMBAL_MANAGER_INFORMATION { \
+ 60010, \
+ "STORM32_GIMBAL_MANAGER_INFORMATION", \
+ 9, \
+ { { "gimbal_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_storm32_gimbal_manager_information_t, gimbal_id) }, \
+ { "device_cap_flags", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_storm32_gimbal_manager_information_t, device_cap_flags) }, \
+ { "manager_cap_flags", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_storm32_gimbal_manager_information_t, manager_cap_flags) }, \
+ { "roll_min", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_storm32_gimbal_manager_information_t, roll_min) }, \
+ { "roll_max", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_storm32_gimbal_manager_information_t, roll_max) }, \
+ { "pitch_min", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_storm32_gimbal_manager_information_t, pitch_min) }, \
+ { "pitch_max", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_storm32_gimbal_manager_information_t, pitch_max) }, \
+ { "yaw_min", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_storm32_gimbal_manager_information_t, yaw_min) }, \
+ { "yaw_max", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_storm32_gimbal_manager_information_t, yaw_max) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_STORM32_GIMBAL_MANAGER_INFORMATION { \
+ "STORM32_GIMBAL_MANAGER_INFORMATION", \
+ 9, \
+ { { "gimbal_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_storm32_gimbal_manager_information_t, gimbal_id) }, \
+ { "device_cap_flags", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_storm32_gimbal_manager_information_t, device_cap_flags) }, \
+ { "manager_cap_flags", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_storm32_gimbal_manager_information_t, manager_cap_flags) }, \
+ { "roll_min", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_storm32_gimbal_manager_information_t, roll_min) }, \
+ { "roll_max", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_storm32_gimbal_manager_information_t, roll_max) }, \
+ { "pitch_min", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_storm32_gimbal_manager_information_t, pitch_min) }, \
+ { "pitch_max", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_storm32_gimbal_manager_information_t, pitch_max) }, \
+ { "yaw_min", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_storm32_gimbal_manager_information_t, yaw_min) }, \
+ { "yaw_max", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_storm32_gimbal_manager_information_t, yaw_max) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a storm32_gimbal_manager_information 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 gimbal_id Gimbal ID (component ID or 1-6 for non-MAVLink gimbal) that this gimbal manager is responsible for.
+ * @param device_cap_flags Gimbal device capability flags. Same flags as reported by GIMBAL_DEVICE_INFORMATION. The flag is only 16 bit wide, but stored in 32 bit, for backwards compatibility (high word is zero).
+ * @param manager_cap_flags Gimbal manager capability flags.
+ * @param roll_min [rad] Hardware minimum roll angle (positive: roll to the right). NaN if unknown.
+ * @param roll_max [rad] Hardware maximum roll angle (positive: roll to the right). NaN if unknown.
+ * @param pitch_min [rad] Hardware minimum pitch/tilt angle (positive: tilt up). NaN if unknown.
+ * @param pitch_max [rad] Hardware maximum pitch/tilt angle (positive: tilt up). NaN if unknown.
+ * @param yaw_min [rad] Hardware minimum yaw/pan angle (positive: pan to the right, relative to the vehicle/gimbal base). NaN if unknown.
+ * @param yaw_max [rad] Hardware maximum yaw/pan angle (positive: pan to the right, relative to the vehicle/gimbal base). NaN if unknown.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_storm32_gimbal_manager_information_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint8_t gimbal_id, uint32_t device_cap_flags, uint32_t manager_cap_flags, float roll_min, float roll_max, float pitch_min, float pitch_max, float yaw_min, float yaw_max)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_INFORMATION_LEN];
+ _mav_put_uint32_t(buf, 0, device_cap_flags);
+ _mav_put_uint32_t(buf, 4, manager_cap_flags);
+ _mav_put_float(buf, 8, roll_min);
+ _mav_put_float(buf, 12, roll_max);
+ _mav_put_float(buf, 16, pitch_min);
+ _mav_put_float(buf, 20, pitch_max);
+ _mav_put_float(buf, 24, yaw_min);
+ _mav_put_float(buf, 28, yaw_max);
+ _mav_put_uint8_t(buf, 32, gimbal_id);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_INFORMATION_LEN);
+#else
+ mavlink_storm32_gimbal_manager_information_t packet;
+ packet.device_cap_flags = device_cap_flags;
+ packet.manager_cap_flags = manager_cap_flags;
+ packet.roll_min = roll_min;
+ packet.roll_max = roll_max;
+ packet.pitch_min = pitch_min;
+ packet.pitch_max = pitch_max;
+ packet.yaw_min = yaw_min;
+ packet.yaw_max = yaw_max;
+ packet.gimbal_id = gimbal_id;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_INFORMATION_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_INFORMATION;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_INFORMATION_LEN, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_INFORMATION_CRC);
+}
+
+/**
+ * @brief Pack a storm32_gimbal_manager_information 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 gimbal_id Gimbal ID (component ID or 1-6 for non-MAVLink gimbal) that this gimbal manager is responsible for.
+ * @param device_cap_flags Gimbal device capability flags. Same flags as reported by GIMBAL_DEVICE_INFORMATION. The flag is only 16 bit wide, but stored in 32 bit, for backwards compatibility (high word is zero).
+ * @param manager_cap_flags Gimbal manager capability flags.
+ * @param roll_min [rad] Hardware minimum roll angle (positive: roll to the right). NaN if unknown.
+ * @param roll_max [rad] Hardware maximum roll angle (positive: roll to the right). NaN if unknown.
+ * @param pitch_min [rad] Hardware minimum pitch/tilt angle (positive: tilt up). NaN if unknown.
+ * @param pitch_max [rad] Hardware maximum pitch/tilt angle (positive: tilt up). NaN if unknown.
+ * @param yaw_min [rad] Hardware minimum yaw/pan angle (positive: pan to the right, relative to the vehicle/gimbal base). NaN if unknown.
+ * @param yaw_max [rad] Hardware maximum yaw/pan angle (positive: pan to the right, relative to the vehicle/gimbal base). NaN if unknown.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_storm32_gimbal_manager_information_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ uint8_t gimbal_id, uint32_t device_cap_flags, uint32_t manager_cap_flags, float roll_min, float roll_max, float pitch_min, float pitch_max, float yaw_min, float yaw_max)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_INFORMATION_LEN];
+ _mav_put_uint32_t(buf, 0, device_cap_flags);
+ _mav_put_uint32_t(buf, 4, manager_cap_flags);
+ _mav_put_float(buf, 8, roll_min);
+ _mav_put_float(buf, 12, roll_max);
+ _mav_put_float(buf, 16, pitch_min);
+ _mav_put_float(buf, 20, pitch_max);
+ _mav_put_float(buf, 24, yaw_min);
+ _mav_put_float(buf, 28, yaw_max);
+ _mav_put_uint8_t(buf, 32, gimbal_id);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_INFORMATION_LEN);
+#else
+ mavlink_storm32_gimbal_manager_information_t packet;
+ packet.device_cap_flags = device_cap_flags;
+ packet.manager_cap_flags = manager_cap_flags;
+ packet.roll_min = roll_min;
+ packet.roll_max = roll_max;
+ packet.pitch_min = pitch_min;
+ packet.pitch_max = pitch_max;
+ packet.yaw_min = yaw_min;
+ packet.yaw_max = yaw_max;
+ packet.gimbal_id = gimbal_id;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_INFORMATION_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_INFORMATION;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_INFORMATION_LEN, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_INFORMATION_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_INFORMATION_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a storm32_gimbal_manager_information 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 gimbal_id Gimbal ID (component ID or 1-6 for non-MAVLink gimbal) that this gimbal manager is responsible for.
+ * @param device_cap_flags Gimbal device capability flags. Same flags as reported by GIMBAL_DEVICE_INFORMATION. The flag is only 16 bit wide, but stored in 32 bit, for backwards compatibility (high word is zero).
+ * @param manager_cap_flags Gimbal manager capability flags.
+ * @param roll_min [rad] Hardware minimum roll angle (positive: roll to the right). NaN if unknown.
+ * @param roll_max [rad] Hardware maximum roll angle (positive: roll to the right). NaN if unknown.
+ * @param pitch_min [rad] Hardware minimum pitch/tilt angle (positive: tilt up). NaN if unknown.
+ * @param pitch_max [rad] Hardware maximum pitch/tilt angle (positive: tilt up). NaN if unknown.
+ * @param yaw_min [rad] Hardware minimum yaw/pan angle (positive: pan to the right, relative to the vehicle/gimbal base). NaN if unknown.
+ * @param yaw_max [rad] Hardware maximum yaw/pan angle (positive: pan to the right, relative to the vehicle/gimbal base). NaN if unknown.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_storm32_gimbal_manager_information_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint8_t gimbal_id,uint32_t device_cap_flags,uint32_t manager_cap_flags,float roll_min,float roll_max,float pitch_min,float pitch_max,float yaw_min,float yaw_max)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_INFORMATION_LEN];
+ _mav_put_uint32_t(buf, 0, device_cap_flags);
+ _mav_put_uint32_t(buf, 4, manager_cap_flags);
+ _mav_put_float(buf, 8, roll_min);
+ _mav_put_float(buf, 12, roll_max);
+ _mav_put_float(buf, 16, pitch_min);
+ _mav_put_float(buf, 20, pitch_max);
+ _mav_put_float(buf, 24, yaw_min);
+ _mav_put_float(buf, 28, yaw_max);
+ _mav_put_uint8_t(buf, 32, gimbal_id);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_INFORMATION_LEN);
+#else
+ mavlink_storm32_gimbal_manager_information_t packet;
+ packet.device_cap_flags = device_cap_flags;
+ packet.manager_cap_flags = manager_cap_flags;
+ packet.roll_min = roll_min;
+ packet.roll_max = roll_max;
+ packet.pitch_min = pitch_min;
+ packet.pitch_max = pitch_max;
+ packet.yaw_min = yaw_min;
+ packet.yaw_max = yaw_max;
+ packet.gimbal_id = gimbal_id;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_INFORMATION_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_INFORMATION;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_INFORMATION_LEN, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_INFORMATION_CRC);
+}
+
+/**
+ * @brief Encode a storm32_gimbal_manager_information 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 storm32_gimbal_manager_information C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_storm32_gimbal_manager_information_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_storm32_gimbal_manager_information_t* storm32_gimbal_manager_information)
+{
+ return mavlink_msg_storm32_gimbal_manager_information_pack(system_id, component_id, msg, storm32_gimbal_manager_information->gimbal_id, storm32_gimbal_manager_information->device_cap_flags, storm32_gimbal_manager_information->manager_cap_flags, storm32_gimbal_manager_information->roll_min, storm32_gimbal_manager_information->roll_max, storm32_gimbal_manager_information->pitch_min, storm32_gimbal_manager_information->pitch_max, storm32_gimbal_manager_information->yaw_min, storm32_gimbal_manager_information->yaw_max);
+}
+
+/**
+ * @brief Encode a storm32_gimbal_manager_information 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 storm32_gimbal_manager_information C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_storm32_gimbal_manager_information_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_storm32_gimbal_manager_information_t* storm32_gimbal_manager_information)
+{
+ return mavlink_msg_storm32_gimbal_manager_information_pack_chan(system_id, component_id, chan, msg, storm32_gimbal_manager_information->gimbal_id, storm32_gimbal_manager_information->device_cap_flags, storm32_gimbal_manager_information->manager_cap_flags, storm32_gimbal_manager_information->roll_min, storm32_gimbal_manager_information->roll_max, storm32_gimbal_manager_information->pitch_min, storm32_gimbal_manager_information->pitch_max, storm32_gimbal_manager_information->yaw_min, storm32_gimbal_manager_information->yaw_max);
+}
+
+/**
+ * @brief Encode a storm32_gimbal_manager_information 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 storm32_gimbal_manager_information C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_storm32_gimbal_manager_information_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_storm32_gimbal_manager_information_t* storm32_gimbal_manager_information)
+{
+ return mavlink_msg_storm32_gimbal_manager_information_pack_status(system_id, component_id, _status, msg, storm32_gimbal_manager_information->gimbal_id, storm32_gimbal_manager_information->device_cap_flags, storm32_gimbal_manager_information->manager_cap_flags, storm32_gimbal_manager_information->roll_min, storm32_gimbal_manager_information->roll_max, storm32_gimbal_manager_information->pitch_min, storm32_gimbal_manager_information->pitch_max, storm32_gimbal_manager_information->yaw_min, storm32_gimbal_manager_information->yaw_max);
+}
+
+/**
+ * @brief Send a storm32_gimbal_manager_information message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param gimbal_id Gimbal ID (component ID or 1-6 for non-MAVLink gimbal) that this gimbal manager is responsible for.
+ * @param device_cap_flags Gimbal device capability flags. Same flags as reported by GIMBAL_DEVICE_INFORMATION. The flag is only 16 bit wide, but stored in 32 bit, for backwards compatibility (high word is zero).
+ * @param manager_cap_flags Gimbal manager capability flags.
+ * @param roll_min [rad] Hardware minimum roll angle (positive: roll to the right). NaN if unknown.
+ * @param roll_max [rad] Hardware maximum roll angle (positive: roll to the right). NaN if unknown.
+ * @param pitch_min [rad] Hardware minimum pitch/tilt angle (positive: tilt up). NaN if unknown.
+ * @param pitch_max [rad] Hardware maximum pitch/tilt angle (positive: tilt up). NaN if unknown.
+ * @param yaw_min [rad] Hardware minimum yaw/pan angle (positive: pan to the right, relative to the vehicle/gimbal base). NaN if unknown.
+ * @param yaw_max [rad] Hardware maximum yaw/pan angle (positive: pan to the right, relative to the vehicle/gimbal base). NaN if unknown.
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_storm32_gimbal_manager_information_send(mavlink_channel_t chan, uint8_t gimbal_id, uint32_t device_cap_flags, uint32_t manager_cap_flags, float roll_min, float roll_max, float pitch_min, float pitch_max, float yaw_min, float yaw_max)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_INFORMATION_LEN];
+ _mav_put_uint32_t(buf, 0, device_cap_flags);
+ _mav_put_uint32_t(buf, 4, manager_cap_flags);
+ _mav_put_float(buf, 8, roll_min);
+ _mav_put_float(buf, 12, roll_max);
+ _mav_put_float(buf, 16, pitch_min);
+ _mav_put_float(buf, 20, pitch_max);
+ _mav_put_float(buf, 24, yaw_min);
+ _mav_put_float(buf, 28, yaw_max);
+ _mav_put_uint8_t(buf, 32, gimbal_id);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_INFORMATION, buf, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_INFORMATION_LEN, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_INFORMATION_CRC);
+#else
+ mavlink_storm32_gimbal_manager_information_t packet;
+ packet.device_cap_flags = device_cap_flags;
+ packet.manager_cap_flags = manager_cap_flags;
+ packet.roll_min = roll_min;
+ packet.roll_max = roll_max;
+ packet.pitch_min = pitch_min;
+ packet.pitch_max = pitch_max;
+ packet.yaw_min = yaw_min;
+ packet.yaw_max = yaw_max;
+ packet.gimbal_id = gimbal_id;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_INFORMATION, (const char *)&packet, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_INFORMATION_LEN, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_INFORMATION_CRC);
+#endif
+}
+
+/**
+ * @brief Send a storm32_gimbal_manager_information message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_storm32_gimbal_manager_information_send_struct(mavlink_channel_t chan, const mavlink_storm32_gimbal_manager_information_t* storm32_gimbal_manager_information)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_storm32_gimbal_manager_information_send(chan, storm32_gimbal_manager_information->gimbal_id, storm32_gimbal_manager_information->device_cap_flags, storm32_gimbal_manager_information->manager_cap_flags, storm32_gimbal_manager_information->roll_min, storm32_gimbal_manager_information->roll_max, storm32_gimbal_manager_information->pitch_min, storm32_gimbal_manager_information->pitch_max, storm32_gimbal_manager_information->yaw_min, storm32_gimbal_manager_information->yaw_max);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_INFORMATION, (const char *)storm32_gimbal_manager_information, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_INFORMATION_LEN, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_INFORMATION_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_INFORMATION_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_storm32_gimbal_manager_information_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t gimbal_id, uint32_t device_cap_flags, uint32_t manager_cap_flags, float roll_min, float roll_max, float pitch_min, float pitch_max, float yaw_min, float yaw_max)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint32_t(buf, 0, device_cap_flags);
+ _mav_put_uint32_t(buf, 4, manager_cap_flags);
+ _mav_put_float(buf, 8, roll_min);
+ _mav_put_float(buf, 12, roll_max);
+ _mav_put_float(buf, 16, pitch_min);
+ _mav_put_float(buf, 20, pitch_max);
+ _mav_put_float(buf, 24, yaw_min);
+ _mav_put_float(buf, 28, yaw_max);
+ _mav_put_uint8_t(buf, 32, gimbal_id);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_INFORMATION, buf, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_INFORMATION_LEN, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_INFORMATION_CRC);
+#else
+ mavlink_storm32_gimbal_manager_information_t *packet = (mavlink_storm32_gimbal_manager_information_t *)msgbuf;
+ packet->device_cap_flags = device_cap_flags;
+ packet->manager_cap_flags = manager_cap_flags;
+ packet->roll_min = roll_min;
+ packet->roll_max = roll_max;
+ packet->pitch_min = pitch_min;
+ packet->pitch_max = pitch_max;
+ packet->yaw_min = yaw_min;
+ packet->yaw_max = yaw_max;
+ packet->gimbal_id = gimbal_id;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_INFORMATION, (const char *)packet, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_INFORMATION_LEN, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_INFORMATION_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE STORM32_GIMBAL_MANAGER_INFORMATION UNPACKING
+
+
+/**
+ * @brief Get field gimbal_id from storm32_gimbal_manager_information message
+ *
+ * @return Gimbal ID (component ID or 1-6 for non-MAVLink gimbal) that this gimbal manager is responsible for.
+ */
+static inline uint8_t mavlink_msg_storm32_gimbal_manager_information_get_gimbal_id(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 32);
+}
+
+/**
+ * @brief Get field device_cap_flags from storm32_gimbal_manager_information message
+ *
+ * @return Gimbal device capability flags. Same flags as reported by GIMBAL_DEVICE_INFORMATION. The flag is only 16 bit wide, but stored in 32 bit, for backwards compatibility (high word is zero).
+ */
+static inline uint32_t mavlink_msg_storm32_gimbal_manager_information_get_device_cap_flags(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint32_t(msg, 0);
+}
+
+/**
+ * @brief Get field manager_cap_flags from storm32_gimbal_manager_information message
+ *
+ * @return Gimbal manager capability flags.
+ */
+static inline uint32_t mavlink_msg_storm32_gimbal_manager_information_get_manager_cap_flags(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint32_t(msg, 4);
+}
+
+/**
+ * @brief Get field roll_min from storm32_gimbal_manager_information message
+ *
+ * @return [rad] Hardware minimum roll angle (positive: roll to the right). NaN if unknown.
+ */
+static inline float mavlink_msg_storm32_gimbal_manager_information_get_roll_min(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 8);
+}
+
+/**
+ * @brief Get field roll_max from storm32_gimbal_manager_information message
+ *
+ * @return [rad] Hardware maximum roll angle (positive: roll to the right). NaN if unknown.
+ */
+static inline float mavlink_msg_storm32_gimbal_manager_information_get_roll_max(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 12);
+}
+
+/**
+ * @brief Get field pitch_min from storm32_gimbal_manager_information message
+ *
+ * @return [rad] Hardware minimum pitch/tilt angle (positive: tilt up). NaN if unknown.
+ */
+static inline float mavlink_msg_storm32_gimbal_manager_information_get_pitch_min(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 16);
+}
+
+/**
+ * @brief Get field pitch_max from storm32_gimbal_manager_information message
+ *
+ * @return [rad] Hardware maximum pitch/tilt angle (positive: tilt up). NaN if unknown.
+ */
+static inline float mavlink_msg_storm32_gimbal_manager_information_get_pitch_max(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 20);
+}
+
+/**
+ * @brief Get field yaw_min from storm32_gimbal_manager_information message
+ *
+ * @return [rad] Hardware minimum yaw/pan angle (positive: pan to the right, relative to the vehicle/gimbal base). NaN if unknown.
+ */
+static inline float mavlink_msg_storm32_gimbal_manager_information_get_yaw_min(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 24);
+}
+
+/**
+ * @brief Get field yaw_max from storm32_gimbal_manager_information message
+ *
+ * @return [rad] Hardware maximum yaw/pan angle (positive: pan to the right, relative to the vehicle/gimbal base). NaN if unknown.
+ */
+static inline float mavlink_msg_storm32_gimbal_manager_information_get_yaw_max(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_float(msg, 28);
+}
+
+/**
+ * @brief Decode a storm32_gimbal_manager_information message into a struct
+ *
+ * @param msg The message to decode
+ * @param storm32_gimbal_manager_information C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_storm32_gimbal_manager_information_decode(const mavlink_message_t* msg, mavlink_storm32_gimbal_manager_information_t* storm32_gimbal_manager_information)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ storm32_gimbal_manager_information->device_cap_flags = mavlink_msg_storm32_gimbal_manager_information_get_device_cap_flags(msg);
+ storm32_gimbal_manager_information->manager_cap_flags = mavlink_msg_storm32_gimbal_manager_information_get_manager_cap_flags(msg);
+ storm32_gimbal_manager_information->roll_min = mavlink_msg_storm32_gimbal_manager_information_get_roll_min(msg);
+ storm32_gimbal_manager_information->roll_max = mavlink_msg_storm32_gimbal_manager_information_get_roll_max(msg);
+ storm32_gimbal_manager_information->pitch_min = mavlink_msg_storm32_gimbal_manager_information_get_pitch_min(msg);
+ storm32_gimbal_manager_information->pitch_max = mavlink_msg_storm32_gimbal_manager_information_get_pitch_max(msg);
+ storm32_gimbal_manager_information->yaw_min = mavlink_msg_storm32_gimbal_manager_information_get_yaw_min(msg);
+ storm32_gimbal_manager_information->yaw_max = mavlink_msg_storm32_gimbal_manager_information_get_yaw_max(msg);
+ storm32_gimbal_manager_information->gimbal_id = mavlink_msg_storm32_gimbal_manager_information_get_gimbal_id(msg);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_INFORMATION_LEN? msg->len : MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_INFORMATION_LEN;
+ memset(storm32_gimbal_manager_information, 0, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_INFORMATION_LEN);
+ memcpy(storm32_gimbal_manager_information, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/storm32/mavlink_msg_storm32_gimbal_manager_status.h b/lib/main/MAVLink/storm32/mavlink_msg_storm32_gimbal_manager_status.h
new file mode 100644
index 00000000000..73f03561d71
--- /dev/null
+++ b/lib/main/MAVLink/storm32/mavlink_msg_storm32_gimbal_manager_status.h
@@ -0,0 +1,372 @@
+#pragma once
+// MESSAGE STORM32_GIMBAL_MANAGER_STATUS PACKING
+
+#define MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_STATUS 60011
+
+
+typedef struct __mavlink_storm32_gimbal_manager_status_t {
+ uint16_t device_flags; /*< Gimbal device flags currently applied. Same flags as reported by GIMBAL_DEVICE_ATTITUDE_STATUS.*/
+ uint16_t manager_flags; /*< Gimbal manager flags currently applied.*/
+ uint8_t gimbal_id; /*< Gimbal ID (component ID or 1-6 for non-MAVLink gimbal) that this gimbal manager is responsible for.*/
+ uint8_t supervisor; /*< Client who is currently supervisor (0 = none).*/
+ uint8_t profile; /*< Profile currently applied (0 = default).*/
+} mavlink_storm32_gimbal_manager_status_t;
+
+#define MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_STATUS_LEN 7
+#define MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_STATUS_MIN_LEN 7
+#define MAVLINK_MSG_ID_60011_LEN 7
+#define MAVLINK_MSG_ID_60011_MIN_LEN 7
+
+#define MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_STATUS_CRC 183
+#define MAVLINK_MSG_ID_60011_CRC 183
+
+
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_STORM32_GIMBAL_MANAGER_STATUS { \
+ 60011, \
+ "STORM32_GIMBAL_MANAGER_STATUS", \
+ 5, \
+ { { "gimbal_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_storm32_gimbal_manager_status_t, gimbal_id) }, \
+ { "supervisor", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_storm32_gimbal_manager_status_t, supervisor) }, \
+ { "device_flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_storm32_gimbal_manager_status_t, device_flags) }, \
+ { "manager_flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_storm32_gimbal_manager_status_t, manager_flags) }, \
+ { "profile", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_storm32_gimbal_manager_status_t, profile) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_STORM32_GIMBAL_MANAGER_STATUS { \
+ "STORM32_GIMBAL_MANAGER_STATUS", \
+ 5, \
+ { { "gimbal_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_storm32_gimbal_manager_status_t, gimbal_id) }, \
+ { "supervisor", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_storm32_gimbal_manager_status_t, supervisor) }, \
+ { "device_flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_storm32_gimbal_manager_status_t, device_flags) }, \
+ { "manager_flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_storm32_gimbal_manager_status_t, manager_flags) }, \
+ { "profile", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_storm32_gimbal_manager_status_t, profile) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a storm32_gimbal_manager_status 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 gimbal_id Gimbal ID (component ID or 1-6 for non-MAVLink gimbal) that this gimbal manager is responsible for.
+ * @param supervisor Client who is currently supervisor (0 = none).
+ * @param device_flags Gimbal device flags currently applied. Same flags as reported by GIMBAL_DEVICE_ATTITUDE_STATUS.
+ * @param manager_flags Gimbal manager flags currently applied.
+ * @param profile Profile currently applied (0 = default).
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_storm32_gimbal_manager_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint8_t gimbal_id, uint8_t supervisor, uint16_t device_flags, uint16_t manager_flags, uint8_t profile)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_STATUS_LEN];
+ _mav_put_uint16_t(buf, 0, device_flags);
+ _mav_put_uint16_t(buf, 2, manager_flags);
+ _mav_put_uint8_t(buf, 4, gimbal_id);
+ _mav_put_uint8_t(buf, 5, supervisor);
+ _mav_put_uint8_t(buf, 6, profile);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_STATUS_LEN);
+#else
+ mavlink_storm32_gimbal_manager_status_t packet;
+ packet.device_flags = device_flags;
+ packet.manager_flags = manager_flags;
+ packet.gimbal_id = gimbal_id;
+ packet.supervisor = supervisor;
+ packet.profile = profile;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_STATUS_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_STATUS;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_STATUS_MIN_LEN, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_STATUS_LEN, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_STATUS_CRC);
+}
+
+/**
+ * @brief Pack a storm32_gimbal_manager_status 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 gimbal_id Gimbal ID (component ID or 1-6 for non-MAVLink gimbal) that this gimbal manager is responsible for.
+ * @param supervisor Client who is currently supervisor (0 = none).
+ * @param device_flags Gimbal device flags currently applied. Same flags as reported by GIMBAL_DEVICE_ATTITUDE_STATUS.
+ * @param manager_flags Gimbal manager flags currently applied.
+ * @param profile Profile currently applied (0 = default).
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_storm32_gimbal_manager_status_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ uint8_t gimbal_id, uint8_t supervisor, uint16_t device_flags, uint16_t manager_flags, uint8_t profile)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_STATUS_LEN];
+ _mav_put_uint16_t(buf, 0, device_flags);
+ _mav_put_uint16_t(buf, 2, manager_flags);
+ _mav_put_uint8_t(buf, 4, gimbal_id);
+ _mav_put_uint8_t(buf, 5, supervisor);
+ _mav_put_uint8_t(buf, 6, profile);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_STATUS_LEN);
+#else
+ mavlink_storm32_gimbal_manager_status_t packet;
+ packet.device_flags = device_flags;
+ packet.manager_flags = manager_flags;
+ packet.gimbal_id = gimbal_id;
+ packet.supervisor = supervisor;
+ packet.profile = profile;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_STATUS_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_STATUS;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_STATUS_MIN_LEN, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_STATUS_LEN, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_STATUS_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_STATUS_MIN_LEN, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_STATUS_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a storm32_gimbal_manager_status 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 gimbal_id Gimbal ID (component ID or 1-6 for non-MAVLink gimbal) that this gimbal manager is responsible for.
+ * @param supervisor Client who is currently supervisor (0 = none).
+ * @param device_flags Gimbal device flags currently applied. Same flags as reported by GIMBAL_DEVICE_ATTITUDE_STATUS.
+ * @param manager_flags Gimbal manager flags currently applied.
+ * @param profile Profile currently applied (0 = default).
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_storm32_gimbal_manager_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint8_t gimbal_id,uint8_t supervisor,uint16_t device_flags,uint16_t manager_flags,uint8_t profile)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_STATUS_LEN];
+ _mav_put_uint16_t(buf, 0, device_flags);
+ _mav_put_uint16_t(buf, 2, manager_flags);
+ _mav_put_uint8_t(buf, 4, gimbal_id);
+ _mav_put_uint8_t(buf, 5, supervisor);
+ _mav_put_uint8_t(buf, 6, profile);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_STATUS_LEN);
+#else
+ mavlink_storm32_gimbal_manager_status_t packet;
+ packet.device_flags = device_flags;
+ packet.manager_flags = manager_flags;
+ packet.gimbal_id = gimbal_id;
+ packet.supervisor = supervisor;
+ packet.profile = profile;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_STATUS_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_STATUS;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_STATUS_MIN_LEN, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_STATUS_LEN, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_STATUS_CRC);
+}
+
+/**
+ * @brief Encode a storm32_gimbal_manager_status 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 storm32_gimbal_manager_status C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_storm32_gimbal_manager_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_storm32_gimbal_manager_status_t* storm32_gimbal_manager_status)
+{
+ return mavlink_msg_storm32_gimbal_manager_status_pack(system_id, component_id, msg, storm32_gimbal_manager_status->gimbal_id, storm32_gimbal_manager_status->supervisor, storm32_gimbal_manager_status->device_flags, storm32_gimbal_manager_status->manager_flags, storm32_gimbal_manager_status->profile);
+}
+
+/**
+ * @brief Encode a storm32_gimbal_manager_status 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 storm32_gimbal_manager_status C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_storm32_gimbal_manager_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_storm32_gimbal_manager_status_t* storm32_gimbal_manager_status)
+{
+ return mavlink_msg_storm32_gimbal_manager_status_pack_chan(system_id, component_id, chan, msg, storm32_gimbal_manager_status->gimbal_id, storm32_gimbal_manager_status->supervisor, storm32_gimbal_manager_status->device_flags, storm32_gimbal_manager_status->manager_flags, storm32_gimbal_manager_status->profile);
+}
+
+/**
+ * @brief Encode a storm32_gimbal_manager_status 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 storm32_gimbal_manager_status C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_storm32_gimbal_manager_status_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_storm32_gimbal_manager_status_t* storm32_gimbal_manager_status)
+{
+ return mavlink_msg_storm32_gimbal_manager_status_pack_status(system_id, component_id, _status, msg, storm32_gimbal_manager_status->gimbal_id, storm32_gimbal_manager_status->supervisor, storm32_gimbal_manager_status->device_flags, storm32_gimbal_manager_status->manager_flags, storm32_gimbal_manager_status->profile);
+}
+
+/**
+ * @brief Send a storm32_gimbal_manager_status message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param gimbal_id Gimbal ID (component ID or 1-6 for non-MAVLink gimbal) that this gimbal manager is responsible for.
+ * @param supervisor Client who is currently supervisor (0 = none).
+ * @param device_flags Gimbal device flags currently applied. Same flags as reported by GIMBAL_DEVICE_ATTITUDE_STATUS.
+ * @param manager_flags Gimbal manager flags currently applied.
+ * @param profile Profile currently applied (0 = default).
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_storm32_gimbal_manager_status_send(mavlink_channel_t chan, uint8_t gimbal_id, uint8_t supervisor, uint16_t device_flags, uint16_t manager_flags, uint8_t profile)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_STATUS_LEN];
+ _mav_put_uint16_t(buf, 0, device_flags);
+ _mav_put_uint16_t(buf, 2, manager_flags);
+ _mav_put_uint8_t(buf, 4, gimbal_id);
+ _mav_put_uint8_t(buf, 5, supervisor);
+ _mav_put_uint8_t(buf, 6, profile);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_STATUS, buf, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_STATUS_MIN_LEN, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_STATUS_LEN, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_STATUS_CRC);
+#else
+ mavlink_storm32_gimbal_manager_status_t packet;
+ packet.device_flags = device_flags;
+ packet.manager_flags = manager_flags;
+ packet.gimbal_id = gimbal_id;
+ packet.supervisor = supervisor;
+ packet.profile = profile;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_STATUS, (const char *)&packet, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_STATUS_MIN_LEN, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_STATUS_LEN, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_STATUS_CRC);
+#endif
+}
+
+/**
+ * @brief Send a storm32_gimbal_manager_status message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_storm32_gimbal_manager_status_send_struct(mavlink_channel_t chan, const mavlink_storm32_gimbal_manager_status_t* storm32_gimbal_manager_status)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_storm32_gimbal_manager_status_send(chan, storm32_gimbal_manager_status->gimbal_id, storm32_gimbal_manager_status->supervisor, storm32_gimbal_manager_status->device_flags, storm32_gimbal_manager_status->manager_flags, storm32_gimbal_manager_status->profile);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_STATUS, (const char *)storm32_gimbal_manager_status, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_STATUS_MIN_LEN, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_STATUS_LEN, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_STATUS_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_storm32_gimbal_manager_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t gimbal_id, uint8_t supervisor, uint16_t device_flags, uint16_t manager_flags, uint8_t profile)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint16_t(buf, 0, device_flags);
+ _mav_put_uint16_t(buf, 2, manager_flags);
+ _mav_put_uint8_t(buf, 4, gimbal_id);
+ _mav_put_uint8_t(buf, 5, supervisor);
+ _mav_put_uint8_t(buf, 6, profile);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_STATUS, buf, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_STATUS_MIN_LEN, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_STATUS_LEN, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_STATUS_CRC);
+#else
+ mavlink_storm32_gimbal_manager_status_t *packet = (mavlink_storm32_gimbal_manager_status_t *)msgbuf;
+ packet->device_flags = device_flags;
+ packet->manager_flags = manager_flags;
+ packet->gimbal_id = gimbal_id;
+ packet->supervisor = supervisor;
+ packet->profile = profile;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_STATUS, (const char *)packet, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_STATUS_MIN_LEN, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_STATUS_LEN, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_STATUS_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE STORM32_GIMBAL_MANAGER_STATUS UNPACKING
+
+
+/**
+ * @brief Get field gimbal_id from storm32_gimbal_manager_status message
+ *
+ * @return Gimbal ID (component ID or 1-6 for non-MAVLink gimbal) that this gimbal manager is responsible for.
+ */
+static inline uint8_t mavlink_msg_storm32_gimbal_manager_status_get_gimbal_id(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 4);
+}
+
+/**
+ * @brief Get field supervisor from storm32_gimbal_manager_status message
+ *
+ * @return Client who is currently supervisor (0 = none).
+ */
+static inline uint8_t mavlink_msg_storm32_gimbal_manager_status_get_supervisor(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 5);
+}
+
+/**
+ * @brief Get field device_flags from storm32_gimbal_manager_status message
+ *
+ * @return Gimbal device flags currently applied. Same flags as reported by GIMBAL_DEVICE_ATTITUDE_STATUS.
+ */
+static inline uint16_t mavlink_msg_storm32_gimbal_manager_status_get_device_flags(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 0);
+}
+
+/**
+ * @brief Get field manager_flags from storm32_gimbal_manager_status message
+ *
+ * @return Gimbal manager flags currently applied.
+ */
+static inline uint16_t mavlink_msg_storm32_gimbal_manager_status_get_manager_flags(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 2);
+}
+
+/**
+ * @brief Get field profile from storm32_gimbal_manager_status message
+ *
+ * @return Profile currently applied (0 = default).
+ */
+static inline uint8_t mavlink_msg_storm32_gimbal_manager_status_get_profile(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 6);
+}
+
+/**
+ * @brief Decode a storm32_gimbal_manager_status message into a struct
+ *
+ * @param msg The message to decode
+ * @param storm32_gimbal_manager_status C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_storm32_gimbal_manager_status_decode(const mavlink_message_t* msg, mavlink_storm32_gimbal_manager_status_t* storm32_gimbal_manager_status)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ storm32_gimbal_manager_status->device_flags = mavlink_msg_storm32_gimbal_manager_status_get_device_flags(msg);
+ storm32_gimbal_manager_status->manager_flags = mavlink_msg_storm32_gimbal_manager_status_get_manager_flags(msg);
+ storm32_gimbal_manager_status->gimbal_id = mavlink_msg_storm32_gimbal_manager_status_get_gimbal_id(msg);
+ storm32_gimbal_manager_status->supervisor = mavlink_msg_storm32_gimbal_manager_status_get_supervisor(msg);
+ storm32_gimbal_manager_status->profile = mavlink_msg_storm32_gimbal_manager_status_get_profile(msg);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_STATUS_LEN? msg->len : MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_STATUS_LEN;
+ memset(storm32_gimbal_manager_status, 0, MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_STATUS_LEN);
+ memcpy(storm32_gimbal_manager_status, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/storm32/storm32.h b/lib/main/MAVLink/storm32/storm32.h
new file mode 100644
index 00000000000..824462bce95
--- /dev/null
+++ b/lib/main/MAVLink/storm32/storm32.h
@@ -0,0 +1,542 @@
+/** @file
+ * @brief MAVLink comm protocol generated from storm32.xml
+ * @see http://mavlink.org
+ */
+#pragma once
+#ifndef MAVLINK_STORM32_H
+#define MAVLINK_STORM32_H
+
+#ifndef MAVLINK_H
+ #error Wrong include order: MAVLINK_STORM32.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_STORM32_XML_HASH 4084971003650403896
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+// MESSAGE LENGTHS AND CRCS
+
+#ifndef MAVLINK_MESSAGE_LENGTHS
+#define MAVLINK_MESSAGE_LENGTHS {}
+#endif
+
+#ifndef MAVLINK_MESSAGE_CRCS
+#define MAVLINK_MESSAGE_CRCS {{0, 50, 9, 9, 0, 0, 0}, {1, 124, 31, 43, 0, 0, 0}, {2, 137, 12, 12, 0, 0, 0}, {4, 237, 14, 14, 3, 12, 13}, {5, 217, 28, 28, 1, 0, 0}, {6, 104, 3, 3, 0, 0, 0}, {7, 119, 32, 32, 0, 0, 0}, {8, 117, 36, 36, 0, 0, 0}, {11, 89, 6, 6, 1, 4, 0}, {20, 214, 20, 20, 3, 2, 3}, {21, 159, 2, 2, 3, 0, 1}, {22, 220, 25, 25, 0, 0, 0}, {23, 168, 23, 23, 3, 4, 5}, {24, 24, 30, 52, 0, 0, 0}, {25, 23, 101, 101, 0, 0, 0}, {26, 170, 22, 24, 0, 0, 0}, {27, 144, 26, 29, 0, 0, 0}, {28, 67, 16, 16, 0, 0, 0}, {29, 115, 14, 16, 0, 0, 0}, {30, 39, 28, 28, 0, 0, 0}, {31, 246, 32, 48, 0, 0, 0}, {32, 185, 28, 28, 0, 0, 0}, {33, 104, 28, 28, 0, 0, 0}, {34, 237, 22, 22, 0, 0, 0}, {35, 244, 22, 22, 0, 0, 0}, {36, 222, 21, 37, 0, 0, 0}, {37, 212, 6, 7, 3, 4, 5}, {38, 9, 6, 7, 3, 4, 5}, {39, 254, 37, 38, 3, 32, 33}, {40, 230, 4, 5, 3, 2, 3}, {41, 28, 4, 4, 3, 2, 3}, {42, 28, 2, 18, 0, 0, 0}, {43, 132, 2, 3, 3, 0, 1}, {44, 221, 4, 9, 3, 2, 3}, {45, 232, 2, 3, 3, 0, 1}, {46, 11, 2, 2, 0, 0, 0}, {47, 153, 3, 8, 3, 0, 1}, {48, 41, 13, 21, 1, 12, 0}, {49, 39, 12, 20, 0, 0, 0}, {50, 78, 37, 37, 3, 18, 19}, {51, 196, 4, 5, 3, 2, 3}, {54, 15, 27, 27, 3, 24, 25}, {55, 3, 25, 25, 0, 0, 0}, {61, 167, 72, 72, 0, 0, 0}, {62, 183, 26, 26, 0, 0, 0}, {63, 119, 181, 181, 0, 0, 0}, {64, 191, 225, 225, 0, 0, 0}, {65, 118, 42, 42, 0, 0, 0}, {66, 148, 6, 6, 3, 2, 3}, {67, 21, 4, 4, 0, 0, 0}, {69, 243, 11, 30, 1, 10, 0}, {70, 124, 18, 38, 3, 16, 17}, {73, 38, 37, 38, 3, 32, 33}, {74, 20, 20, 20, 0, 0, 0}, {75, 158, 35, 35, 3, 30, 31}, {76, 152, 33, 33, 3, 30, 31}, {77, 143, 3, 10, 3, 8, 9}, {80, 14, 4, 4, 3, 2, 3}, {81, 106, 22, 22, 0, 0, 0}, {82, 49, 39, 51, 3, 36, 37}, {83, 22, 37, 37, 0, 0, 0}, {84, 143, 53, 53, 3, 50, 51}, {85, 140, 51, 51, 0, 0, 0}, {86, 5, 53, 53, 3, 50, 51}, {87, 150, 51, 51, 0, 0, 0}, {89, 231, 28, 28, 0, 0, 0}, {90, 183, 56, 56, 0, 0, 0}, {91, 63, 42, 42, 0, 0, 0}, {92, 54, 33, 33, 0, 0, 0}, {93, 47, 81, 81, 0, 0, 0}, {100, 175, 26, 34, 0, 0, 0}, {101, 102, 32, 117, 0, 0, 0}, {102, 158, 32, 117, 0, 0, 0}, {103, 208, 20, 57, 0, 0, 0}, {104, 56, 32, 116, 0, 0, 0}, {105, 93, 62, 63, 0, 0, 0}, {106, 138, 44, 44, 0, 0, 0}, {107, 108, 64, 65, 0, 0, 0}, {108, 32, 84, 92, 0, 0, 0}, {109, 185, 9, 9, 0, 0, 0}, {110, 84, 254, 254, 3, 1, 2}, {111, 34, 16, 18, 3, 16, 17}, {112, 174, 12, 12, 0, 0, 0}, {113, 124, 36, 39, 0, 0, 0}, {114, 237, 44, 44, 0, 0, 0}, {115, 4, 64, 64, 0, 0, 0}, {116, 76, 22, 24, 0, 0, 0}, {117, 128, 6, 6, 3, 4, 5}, {118, 56, 14, 14, 0, 0, 0}, {119, 116, 12, 12, 3, 10, 11}, {120, 134, 97, 97, 0, 0, 0}, {121, 237, 2, 2, 3, 0, 1}, {122, 203, 2, 2, 3, 0, 1}, {123, 250, 113, 113, 3, 0, 1}, {124, 87, 35, 57, 0, 0, 0}, {125, 203, 6, 6, 0, 0, 0}, {126, 220, 79, 81, 3, 79, 80}, {127, 25, 35, 35, 0, 0, 0}, {128, 226, 35, 35, 0, 0, 0}, {129, 46, 22, 24, 0, 0, 0}, {130, 29, 13, 13, 0, 0, 0}, {131, 223, 255, 255, 0, 0, 0}, {132, 85, 14, 39, 0, 0, 0}, {133, 6, 18, 18, 0, 0, 0}, {134, 229, 43, 43, 0, 0, 0}, {135, 203, 8, 8, 0, 0, 0}, {136, 1, 22, 22, 0, 0, 0}, {137, 195, 14, 16, 0, 0, 0}, {138, 109, 36, 120, 0, 0, 0}, {139, 168, 43, 43, 3, 41, 42}, {140, 181, 41, 41, 0, 0, 0}, {141, 47, 32, 32, 0, 0, 0}, {142, 72, 243, 243, 0, 0, 0}, {143, 131, 14, 16, 0, 0, 0}, {144, 127, 93, 93, 0, 0, 0}, {146, 103, 100, 100, 0, 0, 0}, {147, 154, 36, 54, 0, 0, 0}, {148, 178, 60, 78, 0, 0, 0}, {149, 200, 30, 60, 0, 0, 0}, {150, 134, 42, 42, 0, 0, 0}, {151, 219, 8, 8, 3, 6, 7}, {152, 208, 4, 8, 0, 0, 0}, {153, 188, 12, 12, 0, 0, 0}, {154, 84, 15, 15, 3, 6, 7}, {155, 22, 13, 13, 3, 4, 5}, {156, 19, 6, 6, 3, 0, 1}, {157, 21, 15, 15, 3, 12, 13}, {158, 134, 14, 15, 3, 12, 13}, {160, 78, 12, 12, 3, 8, 9}, {161, 68, 3, 3, 3, 0, 1}, {162, 189, 8, 9, 0, 0, 0}, {163, 127, 28, 28, 0, 0, 0}, {164, 154, 44, 44, 0, 0, 0}, {165, 21, 3, 3, 0, 0, 0}, {166, 21, 9, 9, 0, 0, 0}, {167, 144, 22, 22, 0, 0, 0}, {168, 1, 12, 12, 0, 0, 0}, {169, 234, 18, 18, 0, 0, 0}, {170, 73, 34, 34, 0, 0, 0}, {171, 181, 66, 66, 0, 0, 0}, {172, 22, 98, 98, 0, 0, 0}, {173, 83, 8, 8, 0, 0, 0}, {174, 167, 48, 48, 0, 0, 0}, {175, 138, 19, 19, 3, 14, 15}, {176, 234, 3, 3, 3, 0, 1}, {177, 240, 20, 20, 0, 0, 0}, {178, 47, 24, 24, 0, 0, 0}, {179, 189, 29, 29, 1, 26, 0}, {180, 52, 45, 47, 1, 42, 0}, {181, 174, 4, 4, 0, 0, 0}, {182, 229, 40, 40, 0, 0, 0}, {183, 85, 2, 2, 3, 0, 1}, {184, 159, 206, 206, 3, 4, 5}, {185, 186, 7, 7, 3, 4, 5}, {186, 72, 29, 29, 3, 0, 1}, {191, 92, 27, 27, 0, 0, 0}, {192, 36, 44, 54, 0, 0, 0}, {193, 71, 22, 26, 0, 0, 0}, {194, 98, 25, 33, 0, 0, 0}, {195, 120, 37, 37, 0, 0, 0}, {200, 134, 42, 42, 3, 40, 41}, {201, 205, 14, 14, 3, 12, 13}, {214, 69, 8, 8, 3, 6, 7}, {215, 101, 3, 3, 0, 0, 0}, {216, 50, 3, 3, 3, 0, 1}, {217, 202, 6, 6, 0, 0, 0}, {218, 17, 7, 7, 3, 0, 1}, {219, 162, 2, 2, 0, 0, 0}, {225, 208, 65, 73, 0, 0, 0}, {226, 207, 8, 8, 0, 0, 0}, {230, 163, 42, 42, 0, 0, 0}, {231, 105, 40, 40, 0, 0, 0}, {232, 151, 63, 65, 0, 0, 0}, {233, 35, 182, 182, 0, 0, 0}, {234, 150, 40, 40, 0, 0, 0}, {235, 179, 42, 42, 0, 0, 0}, {241, 90, 32, 32, 0, 0, 0}, {242, 104, 52, 60, 0, 0, 0}, {243, 85, 53, 61, 1, 52, 0}, {244, 95, 6, 6, 0, 0, 0}, {245, 130, 2, 2, 0, 0, 0}, {246, 184, 38, 38, 0, 0, 0}, {247, 81, 19, 19, 0, 0, 0}, {248, 8, 254, 254, 3, 3, 4}, {249, 204, 36, 36, 0, 0, 0}, {250, 49, 30, 30, 0, 0, 0}, {251, 170, 18, 18, 0, 0, 0}, {252, 44, 18, 18, 0, 0, 0}, {253, 83, 51, 54, 0, 0, 0}, {254, 46, 9, 9, 0, 0, 0}, {256, 71, 42, 42, 3, 8, 9}, {257, 131, 9, 9, 0, 0, 0}, {258, 187, 32, 232, 3, 0, 1}, {259, 92, 235, 237, 0, 0, 0}, {260, 146, 5, 14, 0, 0, 0}, {261, 179, 27, 61, 0, 0, 0}, {262, 12, 18, 23, 0, 0, 0}, {263, 133, 255, 255, 0, 0, 0}, {264, 49, 28, 32, 0, 0, 0}, {265, 26, 16, 20, 0, 0, 0}, {266, 193, 255, 255, 3, 2, 3}, {267, 35, 255, 255, 3, 2, 3}, {268, 14, 4, 4, 3, 2, 3}, {269, 109, 213, 215, 0, 0, 0}, {270, 59, 19, 20, 0, 0, 0}, {271, 22, 52, 53, 0, 0, 0}, {275, 126, 31, 32, 0, 0, 0}, {276, 18, 49, 50, 0, 0, 0}, {277, 62, 30, 30, 0, 0, 0}, {280, 70, 33, 33, 0, 0, 0}, {281, 48, 13, 13, 0, 0, 0}, {282, 123, 35, 35, 3, 32, 33}, {283, 74, 144, 149, 0, 0, 0}, {284, 99, 32, 32, 3, 30, 31}, {285, 137, 40, 49, 3, 38, 39}, {286, 210, 53, 57, 3, 50, 51}, {287, 1, 23, 23, 3, 20, 21}, {288, 20, 23, 23, 3, 20, 21}, {290, 251, 46, 46, 0, 0, 0}, {291, 10, 57, 57, 0, 0, 0}, {295, 234, 12, 12, 0, 0, 0}, {296, 158, 41, 41, 3, 36, 37}, {299, 19, 96, 98, 0, 0, 0}, {300, 217, 22, 22, 0, 0, 0}, {301, 243, 58, 58, 0, 0, 0}, {310, 28, 17, 17, 0, 0, 0}, {311, 95, 116, 116, 0, 0, 0}, {320, 243, 20, 20, 3, 2, 3}, {321, 88, 2, 2, 3, 0, 1}, {322, 243, 149, 149, 0, 0, 0}, {323, 78, 147, 147, 3, 0, 1}, {324, 132, 146, 146, 0, 0, 0}, {330, 23, 158, 167, 0, 0, 0}, {331, 91, 230, 233, 0, 0, 0}, {332, 236, 239, 239, 0, 0, 0}, {333, 231, 109, 109, 0, 0, 0}, {334, 72, 10, 10, 0, 0, 0}, {335, 225, 24, 24, 0, 0, 0}, {336, 245, 84, 84, 0, 0, 0}, {339, 199, 5, 5, 0, 0, 0}, {340, 99, 70, 70, 0, 0, 0}, {345, 209, 21, 21, 3, 2, 3}, {350, 232, 20, 252, 0, 0, 0}, {360, 11, 25, 25, 0, 0, 0}, {361, 93, 33, 33, 0, 0, 0}, {370, 75, 87, 109, 0, 0, 0}, {371, 10, 26, 26, 0, 0, 0}, {372, 26, 140, 140, 0, 0, 0}, {373, 117, 42, 42, 0, 0, 0}, {375, 251, 140, 140, 0, 0, 0}, {376, 199, 8, 8, 0, 0, 0}, {380, 232, 20, 20, 0, 0, 0}, {385, 147, 133, 133, 3, 2, 3}, {386, 132, 16, 16, 3, 4, 5}, {387, 4, 72, 72, 3, 4, 5}, {388, 8, 37, 37, 3, 32, 33}, {390, 156, 238, 240, 0, 0, 0}, {395, 0, 212, 212, 0, 0, 0}, {396, 50, 160, 160, 0, 0, 0}, {397, 182, 108, 108, 0, 0, 0}, {400, 110, 254, 254, 3, 4, 5}, {401, 183, 6, 6, 3, 4, 5}, {410, 160, 53, 53, 0, 0, 0}, {411, 106, 3, 3, 0, 0, 0}, {412, 33, 6, 6, 3, 4, 5}, {413, 77, 7, 7, 3, 4, 5}, {435, 134, 46, 46, 0, 0, 0}, {436, 193, 9, 9, 0, 0, 0}, {437, 30, 1, 1, 0, 0, 0}, {440, 66, 35, 35, 0, 0, 0}, {9000, 113, 137, 137, 0, 0, 0}, {9005, 117, 34, 34, 0, 0, 0}, {10001, 209, 20, 20, 0, 0, 0}, {10002, 186, 41, 41, 0, 0, 0}, {10003, 4, 1, 1, 0, 0, 0}, {10004, 133, 9, 9, 0, 0, 0}, {10005, 103, 9, 9, 0, 0, 0}, {10006, 193, 4, 4, 0, 0, 0}, {10007, 71, 17, 17, 0, 0, 0}, {10008, 240, 14, 14, 0, 0, 0}, {10151, 195, 85, 85, 0, 0, 0}, {11000, 134, 51, 52, 3, 4, 5}, {11001, 15, 135, 136, 0, 0, 0}, {11002, 234, 179, 180, 3, 4, 5}, {11003, 64, 5, 5, 0, 0, 0}, {11004, 11, 232, 232, 3, 8, 9}, {11005, 93, 230, 230, 0, 0, 0}, {11010, 46, 49, 49, 0, 0, 0}, {11011, 106, 44, 44, 0, 0, 0}, {11020, 205, 16, 16, 0, 0, 0}, {11030, 144, 44, 44, 0, 0, 0}, {11031, 133, 44, 44, 0, 0, 0}, {11032, 85, 44, 44, 0, 0, 0}, {11033, 195, 37, 37, 3, 16, 17}, {11034, 79, 5, 5, 0, 0, 0}, {11035, 128, 8, 8, 3, 4, 5}, {11036, 177, 34, 34, 0, 0, 0}, {11037, 130, 28, 28, 0, 0, 0}, {11038, 47, 38, 38, 0, 0, 0}, {11039, 142, 9, 9, 0, 0, 0}, {11040, 132, 44, 44, 0, 0, 0}, {11041, 208, 44, 44, 0, 0, 0}, {11042, 201, 44, 44, 0, 0, 0}, {11043, 193, 44, 44, 0, 0, 0}, {11044, 189, 44, 44, 0, 0, 0}, {11060, 162, 78, 78, 0, 0, 0}, {12900, 114, 44, 44, 3, 0, 1}, {12901, 254, 59, 59, 3, 30, 31}, {12902, 140, 53, 53, 3, 4, 5}, {12903, 249, 46, 46, 3, 0, 1}, {12904, 77, 54, 54, 3, 28, 29}, {12905, 49, 43, 43, 3, 0, 1}, {12915, 94, 249, 249, 3, 0, 1}, {12918, 139, 51, 51, 0, 0, 0}, {12919, 7, 18, 18, 3, 16, 17}, {12920, 20, 5, 5, 0, 0, 0}, {42000, 227, 1, 1, 0, 0, 0}, {42001, 239, 46, 46, 0, 0, 0}, {50001, 246, 32, 32, 0, 0, 0}, {50002, 181, 246, 246, 0, 0, 0}, {50003, 62, 19, 19, 0, 0, 0}, {50004, 240, 10, 10, 3, 8, 9}, {50005, 152, 6, 6, 3, 4, 5}, {52000, 13, 100, 100, 0, 0, 0}, {52001, 239, 1, 1, 0, 0, 0}, {60000, 4, 22, 22, 3, 20, 21}, {60010, 208, 33, 33, 0, 0, 0}, {60011, 183, 7, 7, 0, 0, 0}, {60012, 99, 36, 36, 3, 32, 33}, {60013, 129, 24, 24, 3, 20, 21}, {60014, 134, 8, 8, 3, 4, 5}, {60020, 202, 4, 4, 0, 0, 0}, {60040, 156, 245, 245, 0, 0, 0}, {60041, 191, 255, 255, 0, 0, 0}, {60045, 14, 15, 23, 3, 2, 3}, {60046, 171, 28, 28, 3, 8, 9}, {60047, 55, 7, 7, 0, 0, 0}}
+#endif
+
+#include "../protocol.h"
+
+#define MAVLINK_ENABLED_STORM32
+
+// ENUM DEFINITIONS
+
+
+/** @brief */
+#ifndef HAVE_ENUM_MAV_STORM32_TUNNEL_PAYLOAD_TYPE
+#define HAVE_ENUM_MAV_STORM32_TUNNEL_PAYLOAD_TYPE
+typedef enum MAV_STORM32_TUNNEL_PAYLOAD_TYPE
+{
+ MAV_STORM32_TUNNEL_PAYLOAD_TYPE_STORM32_CH1_IN=200, /* Registered for STorM32 gimbal controller. For communication with gimbal or camera. | */
+ MAV_STORM32_TUNNEL_PAYLOAD_TYPE_STORM32_CH1_OUT=201, /* Registered for STorM32 gimbal controller. For communication with gimbal or camera. | */
+ MAV_STORM32_TUNNEL_PAYLOAD_TYPE_STORM32_CH2_IN=202, /* Registered for STorM32 gimbal controller. For communication with gimbal. | */
+ MAV_STORM32_TUNNEL_PAYLOAD_TYPE_STORM32_CH2_OUT=203, /* Registered for STorM32 gimbal controller. For communication with gimbal. | */
+ MAV_STORM32_TUNNEL_PAYLOAD_TYPE_STORM32_CH3_IN=204, /* Registered for STorM32 gimbal controller. For communication with camera. | */
+ MAV_STORM32_TUNNEL_PAYLOAD_TYPE_STORM32_CH3_OUT=205, /* Registered for STorM32 gimbal controller. For communication with camera. | */
+ MAV_STORM32_TUNNEL_PAYLOAD_TYPE_ENUM_END=206, /* | */
+} MAV_STORM32_TUNNEL_PAYLOAD_TYPE;
+#endif
+
+/** @brief Gimbal manager capability flags. */
+#ifndef HAVE_ENUM_MAV_STORM32_GIMBAL_MANAGER_CAP_FLAGS
+#define HAVE_ENUM_MAV_STORM32_GIMBAL_MANAGER_CAP_FLAGS
+typedef enum MAV_STORM32_GIMBAL_MANAGER_CAP_FLAGS
+{
+ MAV_STORM32_GIMBAL_MANAGER_CAP_FLAGS_HAS_PROFILES=1, /* The gimbal manager supports several profiles. | */
+ MAV_STORM32_GIMBAL_MANAGER_CAP_FLAGS_ENUM_END=2, /* | */
+} MAV_STORM32_GIMBAL_MANAGER_CAP_FLAGS;
+#endif
+
+/** @brief Flags for gimbal manager operation. Used for setting and reporting, unless specified otherwise. If a setting has been accepted by the gimbal manager is reported in the STORM32_GIMBAL_MANAGER_STATUS message. */
+#ifndef HAVE_ENUM_MAV_STORM32_GIMBAL_MANAGER_FLAGS
+#define HAVE_ENUM_MAV_STORM32_GIMBAL_MANAGER_FLAGS
+typedef enum MAV_STORM32_GIMBAL_MANAGER_FLAGS
+{
+ MAV_STORM32_GIMBAL_MANAGER_FLAGS_RC_ACTIVE=1, /* Request to set RC input to active, or report RC input is active. Implies RC mixed. RC exclusive is achieved by setting all clients to inactive. | */
+ MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_ONBOARD_ACTIVE=2, /* Request to set onboard/companion computer client to active, or report this client is active. | */
+ MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_AUTOPILOT_ACTIVE=4, /* Request to set autopliot client to active, or report this client is active. | */
+ MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_GCS_ACTIVE=8, /* Request to set GCS client to active, or report this client is active. | */
+ MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_CAMERA_ACTIVE=16, /* Request to set camera client to active, or report this client is active. | */
+ MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_GCS2_ACTIVE=32, /* Request to set GCS2 client to active, or report this client is active. | */
+ MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_CAMERA2_ACTIVE=64, /* Request to set camera2 client to active, or report this client is active. | */
+ MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_CUSTOM_ACTIVE=128, /* Request to set custom client to active, or report this client is active. | */
+ MAV_STORM32_GIMBAL_MANAGER_FLAGS_CLIENT_CUSTOM2_ACTIVE=256, /* Request to set custom2 client to active, or report this client is active. | */
+ MAV_STORM32_GIMBAL_MANAGER_FLAGS_SET_SUPERVISON=512, /* Request supervision. This flag is only for setting, it is not reported. | */
+ MAV_STORM32_GIMBAL_MANAGER_FLAGS_SET_RELEASE=1024, /* Release supervision. This flag is only for setting, it is not reported. | */
+ MAV_STORM32_GIMBAL_MANAGER_FLAGS_ENUM_END=1025, /* | */
+} MAV_STORM32_GIMBAL_MANAGER_FLAGS;
+#endif
+
+/** @brief Gimbal manager client ID. In a prioritizing profile, the priorities are determined by the implementation; they could e.g. be custom1 > onboard > GCS > autopilot/camera > GCS2 > custom2. */
+#ifndef HAVE_ENUM_MAV_STORM32_GIMBAL_MANAGER_CLIENT
+#define HAVE_ENUM_MAV_STORM32_GIMBAL_MANAGER_CLIENT
+typedef enum MAV_STORM32_GIMBAL_MANAGER_CLIENT
+{
+ MAV_STORM32_GIMBAL_MANAGER_CLIENT_NONE=0, /* For convenience. | */
+ MAV_STORM32_GIMBAL_MANAGER_CLIENT_ONBOARD=1, /* This is the onboard/companion computer client. | */
+ MAV_STORM32_GIMBAL_MANAGER_CLIENT_AUTOPILOT=2, /* This is the autopilot client. | */
+ MAV_STORM32_GIMBAL_MANAGER_CLIENT_GCS=3, /* This is the GCS client. | */
+ MAV_STORM32_GIMBAL_MANAGER_CLIENT_CAMERA=4, /* This is the camera client. | */
+ MAV_STORM32_GIMBAL_MANAGER_CLIENT_GCS2=5, /* This is the GCS2 client. | */
+ MAV_STORM32_GIMBAL_MANAGER_CLIENT_CAMERA2=6, /* This is the camera2 client. | */
+ MAV_STORM32_GIMBAL_MANAGER_CLIENT_CUSTOM=7, /* This is the custom client. | */
+ MAV_STORM32_GIMBAL_MANAGER_CLIENT_CUSTOM2=8, /* This is the custom2 client. | */
+ MAV_STORM32_GIMBAL_MANAGER_CLIENT_ENUM_END=9, /* | */
+} MAV_STORM32_GIMBAL_MANAGER_CLIENT;
+#endif
+
+/** @brief Gimbal manager profiles. Only standard profiles are defined. Any implementation can define its own profile(s) in addition, and should use enum values > 16. */
+#ifndef HAVE_ENUM_MAV_STORM32_GIMBAL_MANAGER_PROFILE
+#define HAVE_ENUM_MAV_STORM32_GIMBAL_MANAGER_PROFILE
+typedef enum MAV_STORM32_GIMBAL_MANAGER_PROFILE
+{
+ MAV_STORM32_GIMBAL_MANAGER_PROFILE_DEFAULT=0, /* Default profile. Implementation specific. | */
+ MAV_STORM32_GIMBAL_MANAGER_PROFILE_CUSTOM=1, /* Not supported/deprecated. | */
+ MAV_STORM32_GIMBAL_MANAGER_PROFILE_COOPERATIVE=2, /* Profile with cooperative behavior. | */
+ MAV_STORM32_GIMBAL_MANAGER_PROFILE_EXCLUSIVE=3, /* Profile with exclusive behavior. | */
+ MAV_STORM32_GIMBAL_MANAGER_PROFILE_PRIORITY_COOPERATIVE=4, /* Profile with priority and cooperative behavior for equal priority. | */
+ MAV_STORM32_GIMBAL_MANAGER_PROFILE_PRIORITY_EXCLUSIVE=5, /* Profile with priority and exclusive behavior for equal priority. | */
+ MAV_STORM32_GIMBAL_MANAGER_PROFILE_ENUM_END=6, /* | */
+} MAV_STORM32_GIMBAL_MANAGER_PROFILE;
+#endif
+
+/** @brief Enumeration of possible shot modes. */
+#ifndef HAVE_ENUM_MAV_QSHOT_MODE
+#define HAVE_ENUM_MAV_QSHOT_MODE
+typedef enum MAV_QSHOT_MODE
+{
+ MAV_QSHOT_MODE_UNDEFINED=0, /* Undefined shot mode. Can be used to determine if qshots should be used or not. | */
+ MAV_QSHOT_MODE_DEFAULT=1, /* Start normal gimbal operation. Is usually used to return back from a shot. | */
+ MAV_QSHOT_MODE_GIMBAL_RETRACT=2, /* Load and keep safe gimbal position and stop stabilization. | */
+ MAV_QSHOT_MODE_GIMBAL_NEUTRAL=3, /* Load neutral gimbal position and keep it while stabilizing. | */
+ MAV_QSHOT_MODE_GIMBAL_MISSION=4, /* Start mission with gimbal control. | */
+ MAV_QSHOT_MODE_GIMBAL_RC_CONTROL=5, /* Start RC gimbal control. | */
+ MAV_QSHOT_MODE_POI_TARGETING=6, /* Start gimbal tracking the point specified by Lat, Lon, Alt. | */
+ MAV_QSHOT_MODE_SYSID_TARGETING=7, /* Start gimbal tracking the system with specified system ID. | */
+ MAV_QSHOT_MODE_CABLECAM_2POINT=8, /* Start 2-point cable cam quick shot. | */
+ MAV_QSHOT_MODE_HOME_TARGETING=9, /* Start gimbal tracking the home location. | */
+ MAV_QSHOT_MODE_ENUM_END=10, /* | */
+} MAV_QSHOT_MODE;
+#endif
+
+/** @brief Commands to be executed by the MAV. They can be executed on user request, or as part of a mission script. If the action is used in a mission, the parameter mapping to the waypoint/mission message is as follows: Param 1, Param 2, Param 3, Param 4, X: Param 5, Y:Param 6, Z:Param 7. This command list is similar what ARINC 424 is for commercial aircraft: A data format how to interpret waypoint/mission data. NaN and INT32_MAX may be used in float/integer params (respectively) to indicate optional/default values (e.g. to use the component's current yaw or latitude rather than a specific value). See https://mavlink.io/en/guide/xml_schema.html#MAV_CMD for information about the structure of the MAV_CMD entries */
+#ifndef HAVE_ENUM_MAV_CMD
+#define HAVE_ENUM_MAV_CMD
+typedef enum MAV_CMD
+{
+ MAV_CMD_NAV_WAYPOINT=16, /* Navigate to waypoint. This is intended for use in missions (for guided commands outside of missions use MAV_CMD_DO_REPOSITION). |Hold time. (ignored by fixed wing, time to stay at waypoint for rotary wing)| Acceptance radius (if the sphere with this radius is hit, the waypoint counts as reached)| 0 to pass through the WP, if > 0 radius to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control.| Desired yaw angle at waypoint (rotary wing). NaN to use the current system yaw heading mode (e.g. yaw towards next waypoint, yaw to home, etc.).| Latitude| Longitude| Altitude| */
+ MAV_CMD_NAV_LOITER_UNLIM=17, /* Loiter around this waypoint an unlimited amount of time |Empty| Empty| Loiter radius around waypoint for forward-only moving vehicles (not multicopters). If positive loiter clockwise, else counter-clockwise| Desired yaw angle. NaN to use the current system yaw heading mode (e.g. yaw towards next waypoint, yaw to home, etc.).| Latitude| Longitude| Altitude| */
+ MAV_CMD_NAV_LOITER_TURNS=18, /* Loiter around this waypoint for X turns |Number of turns.| Leave loiter circle only when track heads towards the next waypoint (MAV_BOOL_FALSE: Leave when turns complete). Values not equal to 0 or 1 are invalid.| Loiter radius around waypoint for forward-only moving vehicles (not multicopters). If positive loiter clockwise, else counter-clockwise| Loiter circle exit location and/or path to next waypoint ("xtrack") for forward-only moving vehicles (not multicopters). 0 for the vehicle to converge towards the center xtrack when it leaves the loiter (the line between the centers of the current and next waypoint), 1 to converge to the direct line between the location that the vehicle exits the loiter radius and the next waypoint. Otherwise the angle (in degrees) between the tangent of the loiter circle and the center xtrack at which the vehicle must leave the loiter (and converge to the center xtrack). NaN to use the current system default xtrack behaviour.| Latitude| Longitude| Altitude| */
+ MAV_CMD_NAV_LOITER_TIME=19, /* Loiter at the specified latitude, longitude and altitude for a certain amount of time. Multicopter vehicles stop at the point (within a vehicle-specific acceptance radius). Forward-only moving vehicles (e.g. fixed-wing) circle the point with the specified radius/direction. If the Heading Required parameter (2) is non-zero forward moving aircraft will only leave the loiter circle once heading towards the next waypoint. |Loiter time (only starts once Lat, Lon and Alt is reached).| Leave loiter circle only when track heading towards the next waypoint (MAV_BOOL_FALSE: Leave on time expiry). Values not equal to 0 or 1 are invalid.| Loiter radius around waypoint for forward-only moving vehicles (not multicopters). If positive loiter clockwise, else counter-clockwise.| Loiter circle exit location and/or path to next waypoint ("xtrack") for forward-only moving vehicles (not multicopters). 0 for the vehicle to converge towards the center xtrack when it leaves the loiter (the line between the centers of the current and next waypoint), 1 to converge to the direct line between the location that the vehicle exits the loiter radius and the next waypoint. Otherwise the angle (in degrees) between the tangent of the loiter circle and the center xtrack at which the vehicle must leave the loiter (and converge to the center xtrack). NaN to use the current system default xtrack behaviour.| Latitude| Longitude| Altitude| */
+ MAV_CMD_NAV_RETURN_TO_LAUNCH=20, /* Return to launch location |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */
+ MAV_CMD_NAV_LAND=21, /* Land at location. |Minimum target altitude if landing is aborted (0 = undefined/use system default).| Precision land mode.| Empty.| Desired yaw angle. NaN to use the current system yaw heading mode (e.g. yaw towards next waypoint, yaw to home, etc.).| Latitude.| Longitude.| Landing altitude (ground level in current frame).| */
+ MAV_CMD_NAV_TAKEOFF=22, /* Takeoff from ground / hand. Vehicles that support multiple takeoff modes (e.g. VTOL quadplane) should take off using the currently configured mode. |Minimum pitch (if airspeed sensor present), desired pitch without sensor| Empty| Bitmask of options flags.| Yaw angle (if magnetometer present), ignored without magnetometer. NaN to use the current system yaw heading mode (e.g. yaw towards next waypoint, yaw to home, etc.).| Latitude| Longitude| Altitude| */
+ MAV_CMD_NAV_LAND_LOCAL=23, /* Land at local position (local frame only) |Landing target number (if available)| Maximum accepted offset from desired landing position - computed magnitude from spherical coordinates: d = sqrt(x^2 + y^2 + z^2), which gives the maximum accepted distance between the desired landing position and the position where the vehicle is about to land| Landing descend rate| Desired yaw angle| Y-axis position| X-axis position| Z-axis / ground level position| */
+ MAV_CMD_NAV_TAKEOFF_LOCAL=24, /* Takeoff from local position (local frame only) |Minimum pitch (if airspeed sensor present), desired pitch without sensor| Empty| Takeoff ascend rate| Yaw angle (if magnetometer or another yaw estimation source present), ignored without one of these| Y-axis position| X-axis position| Z-axis position| */
+ MAV_CMD_NAV_FOLLOW=25, /* Vehicle following, i.e. this waypoint represents the position of a moving vehicle |Following logic to use (e.g. loitering or sinusoidal following) - depends on specific autopilot implementation| Ground speed of vehicle to be followed| Radius around waypoint. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */
+ MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT=30, /* Continue on the current course and climb/descend to specified altitude. When the altitude is reached continue to the next command (i.e., don't proceed to the next command until the desired altitude is reached. |Climb or Descend (0 = Neutral, command completes when within 5m of this command's altitude, 1 = Climbing, command completes when at or above this command's altitude, 2 = Descending, command completes when at or below this command's altitude.| Empty| Empty| Empty| Empty| Empty| Desired altitude| */
+ MAV_CMD_NAV_LOITER_TO_ALT=31, /* Begin loiter at the specified Latitude and Longitude. If Lat=Lon=0, then loiter at the current position. Don't consider the navigation command complete (don't leave loiter) until the altitude has been reached. Additionally, if the Heading Required parameter is non-zero the aircraft will not leave the loiter until heading toward the next waypoint. |Leave loiter circle only when track heading towards the next waypoint (MAV_BOOL_FALSE: Leave when altitude reached). Values not equal to 0 or 1 are invalid.| Loiter radius around waypoint for forward-only moving vehicles (not multicopters). If positive loiter clockwise, negative counter-clockwise, 0 means no change to standard loiter.| Empty| Loiter circle exit location and/or path to next waypoint ("xtrack") for forward-only moving vehicles (not multicopters). 0 for the vehicle to converge towards the center xtrack when it leaves the loiter (the line between the centers of the current and next waypoint), 1 to converge to the direct line between the location that the vehicle exits the loiter radius and the next waypoint. Otherwise the angle (in degrees) between the tangent of the loiter circle and the center xtrack at which the vehicle must leave the loiter (and converge to the center xtrack). NaN to use the current system default xtrack behaviour.| Latitude| Longitude| Altitude| */
+ MAV_CMD_DO_FOLLOW=32, /* Begin following a target |System ID (of the FOLLOW_TARGET beacon). Send 0 to disable follow-me and return to the default position hold mode.| Reserved| Reserved| Altitude mode: 0: Keep current altitude, 1: keep altitude difference to target, 2: go to a fixed altitude above home.| Altitude above home. (used if mode=2)| Reserved| Time to land in which the MAV should go to the default position hold mode after a message RX timeout.| */
+ MAV_CMD_DO_FOLLOW_REPOSITION=33, /* Reposition the MAV after a follow target command has been sent |Camera q1 (where 0 is on the ray from the camera to the tracking device)| Camera q2| Camera q3| Camera q4| altitude offset from target| X offset from target| Y offset from target| */
+ MAV_CMD_DO_ORBIT=34, /* Start orbiting on the circumference of a circle defined by the parameters. Setting values to NaN/INT32_MAX (as appropriate) results in using defaults. |Radius of the circle. Positive: orbit clockwise. Negative: orbit counter-clockwise. NaN: Use vehicle default radius, or current radius if already orbiting.| Tangential Velocity. NaN: Use vehicle default velocity, or current velocity if already orbiting.| Yaw behavior of the vehicle.| Orbit around the centre point for this many radians (i.e. for a three-quarter orbit set 270*Pi/180). 0: Orbit forever. NaN: Use vehicle default, or current value if already orbiting.| Center point latitude (if no MAV_FRAME specified) / X coordinate according to MAV_FRAME. INT32_MAX (or NaN if sent in COMMAND_LONG): Use current vehicle position, or current center if already orbiting.| Center point longitude (if no MAV_FRAME specified) / Y coordinate according to MAV_FRAME. INT32_MAX (or NaN if sent in COMMAND_LONG): Use current vehicle position, or current center if already orbiting.| Center point altitude (MSL) (if no MAV_FRAME specified) / Z coordinate according to MAV_FRAME. NaN: Use current vehicle altitude.| */
+ MAV_CMD_DO_FIGURE_EIGHT=35, /* Fly a figure eight path as defined by the parameters.
+ Set parameters to NaN/INT32_MAX (as appropriate) to use system-default values.
+ The command is intended for fixed wing vehicles (and VTOL hybrids flying in fixed-wing mode), allowing POI tracking for gimbals that don't support infinite rotation.
+ This command only defines the flight path. Speed should be set independently (use e.g. MAV_CMD_DO_CHANGE_SPEED).
+ Yaw and other degrees of freedom are not specified, and will be flight-stack specific (on vehicles where they can be controlled independent of the heading).
+ |Major axis radius of the figure eight. Positive: orbit the north circle clockwise. Negative: orbit the north circle counter-clockwise.
+ NaN: The radius will be set to 2.5 times the minor radius and direction is clockwise.
+ Must be greater or equal to two times the minor radius for feasible values.| Minor axis radius of the figure eight. Defines the radius of the two circles that make up the figure. Negative value has no effect.
+ NaN: The radius will be set to the default loiter radius.| Reserved (default:NaN)| Orientation of the figure eight major axis with respect to true north (range: [-pi,pi]). NaN: use default orientation aligned to true north.| Center point latitude/X coordinate according to MAV_FRAME. If no MAV_FRAME specified, MAV_FRAME_GLOBAL is assumed.
+ INT32_MAX or NaN: Use current vehicle position, or current center if already loitering.| Center point longitude/Y coordinate according to MAV_FRAME. If no MAV_FRAME specified, MAV_FRAME_GLOBAL is assumed.
+ INT32_MAX or NaN: Use current vehicle position, or current center if already loitering.| Center point altitude MSL/Z coordinate according to MAV_FRAME. If no MAV_FRAME specified, MAV_FRAME_GLOBAL is assumed.
+ INT32_MAX or NaN: Use current vehicle altitude.| */
+ MAV_CMD_NAV_ARC_WAYPOINT=36, /* Circular arc path waypoint.
+ This defines the end/exit point and angle (param1) of an arc path from the previous waypoint. A position is required before this command to define the start of the arc (e.g. current position, a MAV_CMD_NAV_WAYPOINT, or a MAV_CMD_NAV_ARC_WAYPOINT).
+ The resulting path is a circular arc in the NE frame, with the difference in height being defined by the difference in waypoint altitudes.
+ |The angle in degrees from the starting position to the exit position of the arc in the NE frame. Positive values are CW arcs and negative values are CCW arcs.| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Latitude| Longitude| Altitude| */
+ MAV_CMD_NAV_ROI=80, /* Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicle's control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Region of interest mode.| Waypoint index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z| */
+ MAV_CMD_NAV_PATHPLANNING=81, /* Control autonomous path planning on the MAV. |0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning| 0: Disable full path planning (without resetting map), 1: Enable, 2: Enable and reset map/occupancy grid, 3: Enable and reset planned route, but not occupancy grid| Empty| Yaw angle at goal| Latitude/X of goal| Longitude/Y of goal| Altitude/Z of goal| */
+ MAV_CMD_NAV_SPLINE_WAYPOINT=82, /* Navigate to waypoint using a spline path. |Hold time. (ignored by fixed wing, time to stay at waypoint for rotary wing)| Empty| Empty| Empty| Latitude/X of goal| Longitude/Y of goal| Altitude/Z of goal| */
+ MAV_CMD_NAV_ALTITUDE_WAIT=83, /* Mission command to wait for an altitude or downwards vertical speed. This is meant for high altitude balloon launches, allowing the aircraft to be idle until either an altitude is reached or a negative vertical speed is reached (indicating early balloon burst). The wiggle time is how often to wiggle the control surfaces to prevent them seizing up. |Altitude.| Descent speed.| How long to wiggle the control surfaces to prevent them seizing up.| Empty.| Empty.| Empty.| Empty.| */
+ MAV_CMD_NAV_VTOL_TAKEOFF=84, /* Takeoff from ground using VTOL mode, and transition to forward flight with specified heading. The command should be ignored by vehicles that dont support both VTOL and fixed-wing flight (multicopters, boats,etc.). |Empty| Front transition heading.| Empty| Yaw angle. NaN to use the current system yaw heading mode (e.g. yaw towards next waypoint, yaw to home, etc.).| Latitude| Longitude| Altitude| */
+ MAV_CMD_NAV_VTOL_LAND=85, /* Land using VTOL mode |Landing behaviour.| Empty| Approach altitude (with the same reference as the Altitude field). NaN if unspecified.| Yaw angle. NaN to use the current system yaw heading mode (e.g. yaw towards next waypoint, yaw to home, etc.).| Latitude| Longitude| Altitude (ground level) relative to the current coordinate frame. NaN to use system default landing altitude (ignore value).| */
+ MAV_CMD_NAV_GUIDED_ENABLE=92, /* Hand control over to an external controller |Guided mode on (MAV_BOOL_FALSE: Off). Values not equal to 0 or 1 are invalid.| Empty| Empty| Empty| Empty| Empty| Empty| */
+ MAV_CMD_NAV_DELAY=93, /* Delay the next navigation command a number of seconds or until a specified time |Delay (-1 to enable time-of-day fields)| hour (24h format, UTC, -1 to ignore)| minute (24h format, UTC, -1 to ignore)| second (24h format, UTC, -1 to ignore)| Empty| Empty| Empty| */
+ MAV_CMD_NAV_PAYLOAD_PLACE=94, /* Descend and place payload. Vehicle moves to specified location, descends until it detects a hanging payload has reached the ground, and then releases the payload. If ground is not detected before the reaching the maximum descent value (param1), the command will complete without releasing the payload. |Maximum distance to descend.| Empty| Empty| Empty| Latitude| Longitude| Altitude| */
+ MAV_CMD_NAV_LAST=95, /* NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */
+ MAV_CMD_CONDITION_DELAY=112, /* Delay mission state machine. |Delay| Empty| Empty| Empty| Empty| Empty| Empty| */
+ MAV_CMD_CONDITION_CHANGE_ALT=113, /* Ascend/descend to target altitude at specified rate. Delay mission state machine until desired altitude reached. |Descent / Ascend rate.| Empty| Empty| Empty| Empty| Empty| Target Altitude| */
+ MAV_CMD_CONDITION_DISTANCE=114, /* Delay mission state machine until within desired distance of next NAV point. |Distance.| Empty| Empty| Empty| Empty| Empty| Empty| */
+ MAV_CMD_CONDITION_YAW=115, /* Reach a certain target angle. |target angle [0-360]. Absolute angles: 0 is north. Relative angle: 0 is initial yaw. Direction set by param3.| angular speed| direction: -1: counter clockwise, 0: shortest direction, 1: clockwise| Relative offset (MAV_BOOL_FALSE: absolute angle). Values not equal to 0 or 1 are invalid.| Empty| Empty| Empty| */
+ MAV_CMD_CONDITION_LAST=159, /* NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */
+ MAV_CMD_DO_SET_MODE=176, /* Set system mode. |Mode flags. MAV_MODE values can be used to set some mode flag combinations.| Custom system-specific mode (see target autopilot specifications for mode information). If MAV_MODE_FLAG_CUSTOM_MODE_ENABLED is set in param1 (mode) this mode is used: otherwise the field is ignored.| Custom sub mode - this is system specific, please refer to the individual autopilot specifications for details.| Empty| Empty| Empty| Empty| */
+ MAV_CMD_DO_JUMP=177, /* Jump to the desired command in the mission list. Repeat this action only the specified number of times |Sequence number| Repeat count| Empty| Empty| Empty| Empty| Empty| */
+ MAV_CMD_DO_CHANGE_SPEED=178, /* Change speed and/or throttle set points. The value persists until it is overridden or there is a mode change |Speed type of value set in param2 (such as airspeed, ground speed, and so on)| Speed (-1 indicates no change, -2 indicates return to default vehicle speed)| Throttle (-1 indicates no change, -2 indicates return to default vehicle throttle value)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */
+ MAV_CMD_DO_SET_HOME=179, /*
+ Sets the home position to either to the current position or a specified position.
+ The home position is the default position that the system will return to and land on.
+ The position is set automatically by the system during the takeoff (and may also be set using this command).
+ Note: the current home position may be emitted in a HOME_POSITION message on request (using MAV_CMD_REQUEST_MESSAGE with param1=242).
+ |Use current location (MAV_BOOL_FALSE: use specified location). Values not equal to 0 or 1 are invalid.| Roll angle (of surface). Range: -180..180 degrees. NAN or 0 means value not set. 0.01 indicates zero roll.| Pitch angle (of surface). Range: -90..90 degrees. NAN or 0 means value not set. 0.01 means zero pitch.| Yaw angle. NaN to use default heading. Range: -180..180 degrees.| Latitude| Longitude| Altitude| */
+ MAV_CMD_DO_SET_PARAMETER=180, /* Set a system parameter. Caution! Use of this command requires knowledge of the numeric enumeration value of the parameter. |Parameter number| Parameter value| Empty| Empty| Empty| Empty| Empty| */
+ MAV_CMD_DO_SET_RELAY=181, /* Set a relay to a condition. The current value may optionally be reported using RELAY_STATUS. |Relay instance number.| Setting. (1=on, 0=off, others possible depending on system hardware)| Empty| Empty| Empty| Empty| Empty| */
+ MAV_CMD_DO_REPEAT_RELAY=182, /* Cycle a relay on and off for a desired number of cycles with a desired period. |Relay instance number.| Cycle count.| Cycle time.| Empty| Empty| Empty| Empty| */
+ MAV_CMD_DO_SET_SERVO=183, /* Set a servo to a desired PWM value. |Servo instance number.| Pulse Width Modulation.| Empty| Empty| Empty| Empty| Empty| */
+ MAV_CMD_DO_REPEAT_SERVO=184, /* Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period. |Servo instance number.| Pulse Width Modulation.| Cycle count.| Cycle time.| Empty| Empty| Empty| */
+ MAV_CMD_DO_FLIGHTTERMINATION=185, /* Terminate flight immediately.
+ Flight termination immediately and irreversibly terminates the current flight, returning the vehicle to ground.
+ The vehicle will ignore RC or other input until it has been power-cycled.
+ Termination may trigger safety measures, including: disabling motors and deployment of parachute on multicopters, and setting flight surfaces to initiate a landing pattern on fixed-wing).
+ On multicopters without a parachute it may trigger a crash landing.
+ Support for this command can be tested using the protocol bit: MAV_PROTOCOL_CAPABILITY_FLIGHT_TERMINATION.
+ Support for this command can also be tested by sending the command with param1=0 (< 0.5); the ACK should be either MAV_RESULT_FAILED or MAV_RESULT_UNSUPPORTED.
+ |Flight termination activated if > 0.5. Otherwise not activated and ACK with MAV_RESULT_FAILED.| Empty| Empty| Empty| Empty| Empty| Empty| */
+ MAV_CMD_DO_CHANGE_ALTITUDE=186, /* Change altitude set point. |Altitude.| Frame of new altitude.| Empty| Empty| Empty| Empty| Empty| */
+ MAV_CMD_DO_SET_ACTUATOR=187, /* Sets actuators (e.g. servos) to a desired value. The actuator numbers are mapped to specific outputs (e.g. on any MAIN or AUX PWM or UAVCAN) using a flight-stack specific mechanism (i.e. a parameter). |Actuator 1 value, scaled from [-1 to 1]. NaN to ignore.| Actuator 2 value, scaled from [-1 to 1]. NaN to ignore.| Actuator 3 value, scaled from [-1 to 1]. NaN to ignore.| Actuator 4 value, scaled from [-1 to 1]. NaN to ignore.| Actuator 5 value, scaled from [-1 to 1]. NaN to ignore.| Actuator 6 value, scaled from [-1 to 1]. NaN to ignore.| Index of actuator set (i.e if set to 1, Actuator 1 becomes Actuator 7)| */
+ MAV_CMD_DO_RETURN_PATH_START=188, /* Mission item to specify the start of a failsafe/landing return-path segment (the end of the segment is the next MAV_CMD_DO_LAND_START item).
+ A vehicle that is using missions for landing (e.g. in a return mode) will join the mission on the closest path of the return-path segment (instead of MAV_CMD_DO_LAND_START or the nearest waypoint).
+ The main use case is to minimize the failsafe flight path in corridor missions, where the inbound/outbound paths are constrained (by geofences) to the same particular path.
+ The MAV_CMD_NAV_RETURN_PATH_START would be placed at the start of the return path.
+ If a failsafe occurs on the outbound path the vehicle will move to the nearest point on the return path (which is parallel for this kind of mission), effectively turning round and following the shortest path to landing.
+ If a failsafe occurs on the inbound path the vehicle is already on the return segment and will continue to landing.
+ The Latitude/Longitude/Altitude are optional, and may be set to 0 if not needed.
+ If specified, the item defines the waypoint at which the return segment starts.
+ If sent using as a command, the vehicle will perform a mission landing (using the land segment if defined) or reject the command if mission landings are not supported, or no mission landing is defined. When used as a command any position information in the command is ignored.
+ |Empty| Empty| Empty| Empty| Latitudee. 0: not used.| Longitudee. 0: not used.| Altitudee. 0: not used.| */
+ MAV_CMD_DO_LAND_START=189, /* Mission item to mark the start of a mission landing pattern, or a command to land with a mission landing pattern.
+
+ When used in a mission, this is a marker for the start of a sequence of mission items that represent a landing pattern.
+ It should be followed by a navigation item that defines the first waypoint of the landing sequence.
+ The start marker positional params are used only for selecting what landing pattern to use if several are defined in the mission (the selected pattern will be the one with the marker position that is closest to the vehicle when a landing is commanded).
+ If the marker item position has zero-values for latitude, longitude, and altitude, then landing pattern selection is instead based on the position of the first waypoint in the landing sequence.
+
+ When sent as a command it triggers a landing using a mission landing pattern.
+ The location parameters are not used in this case, and should be set to 0.
+ |Empty| Empty| Empty| Empty| Latitude for landing sequence selection, or 0 (see description). Ignored in commands (set 0).| Longitude for landing sequence selection, or 0 (see description). Ignored in commands (set 0).| Altitude for landing sequence selection, or 0 (see description). Ignored in commands (set 0).| */
+ MAV_CMD_DO_RALLY_LAND=190, /* Mission command to perform a landing from a rally point. |Break altitude| Landing speed| Empty| Empty| Empty| Empty| Empty| */
+ MAV_CMD_DO_GO_AROUND=191, /* Mission command to safely abort an autonomous landing. |Altitude| Empty| Empty| Empty| Empty| Empty| Empty| */
+ MAV_CMD_DO_REPOSITION=192, /* Reposition the vehicle to a specific WGS84 global position. This command is intended for guided commands (for missions use MAV_CMD_NAV_WAYPOINT instead). |Ground speed, less than 0 (-1) for default| Bitmask of option flags.| Loiter radius for planes. Positive values only, direction is controlled by Yaw value. A value of zero or NaN is ignored. | Yaw heading (heading reference defined in Bitmask field). NaN to use the current system yaw heading mode (e.g. yaw towards next waypoint, yaw to home, etc.). For planes indicates loiter direction (0: clockwise, 1: counter clockwise)| Latitude| Longitude| Altitude| */
+ MAV_CMD_DO_PAUSE_CONTINUE=193, /* If in a GPS controlled position mode, hold the current position or continue. |Continue mission (MAV_BOOL_TRUE), Pause current mission or reposition command, hold current position (MAV_BOOL_FALSE). Values not equal to 0 or 1 are invalid. A VTOL capable vehicle should enter hover mode (multicopter and VTOL planes). A plane should loiter with the default loiter radius.| Reserved| Reserved| Reserved| Reserved| Reserved| Reserved| */
+ MAV_CMD_DO_SET_REVERSE=194, /* Set moving direction to forward or reverse. |Reverse direction (MAV_BOOL_FALSE: Forward direction). Values not equal to 0 or 1 are invalid.| Empty| Empty| Empty| Empty| Empty| Empty| */
+ MAV_CMD_DO_SET_ROI_LOCATION=195, /* Sets the region of interest (ROI) to a location. This can then be used by the vehicle's control system to control the vehicle attitude and the attitude of various sensors such as cameras. This command can be sent to a gimbal manager but not to a gimbal device. A gimbal is not to react to this message. |Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals).| Empty| Empty| Empty| Latitude of ROI location| Longitude of ROI location| Altitude of ROI location| */
+ MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET=196, /* Sets the region of interest (ROI) to be toward next waypoint, with optional pitch/roll/yaw offset. This can then be used by the vehicle's control system to control the vehicle attitude and the attitude of various sensors such as cameras. This command can be sent to a gimbal manager but not to a gimbal device. A gimbal device is not to react to this message. |Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals).| Empty| Empty| Empty| Pitch offset from next waypoint, positive pitching up| Roll offset from next waypoint, positive rolling to the right| Yaw offset from next waypoint, positive yawing to the right| */
+ MAV_CMD_DO_SET_ROI_NONE=197, /* Cancels any previous ROI command returning the vehicle/sensors to default flight characteristics. This can then be used by the vehicle's control system to control the vehicle attitude and the attitude of various sensors such as cameras. This command can be sent to a gimbal manager but not to a gimbal device. A gimbal device is not to react to this message. After this command the gimbal manager should go back to manual input if available, and otherwise assume a neutral position. |Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals).| Empty| Empty| Empty| Empty| Empty| Empty| */
+ MAV_CMD_DO_SET_ROI_SYSID=198, /* Mount tracks system with specified system ID. Determination of target vehicle position may be done with GLOBAL_POSITION_INT or any other means. This command can be sent to a gimbal manager but not to a gimbal device. A gimbal device is not to react to this message. |System ID| Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals).| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */
+ MAV_CMD_DO_CONTROL_VIDEO=200, /* Control onboard camera system. |Camera ID (-1 for all)| Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw| Transmission mode: 0: video stream, >0: single images every n seconds| Recording: 0: disabled, 1: enabled compressed, 2: enabled raw| Empty| Empty| Empty| */
+ MAV_CMD_DO_SET_ROI=201, /* Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicle's control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Region of interest mode.| Waypoint index/ target ID (depends on param 1).| Region of interest index. (allows a vehicle to manage multiple ROI's)| Empty| MAV_ROI_WPNEXT: pitch offset from next waypoint, MAV_ROI_LOCATION: latitude| MAV_ROI_WPNEXT: roll offset from next waypoint, MAV_ROI_LOCATION: longitude| MAV_ROI_WPNEXT: yaw offset from next waypoint, MAV_ROI_LOCATION: altitude| */
+ MAV_CMD_DO_DIGICAM_CONFIGURE=202, /* Configure digital camera. This is a fallback message for systems that have not yet implemented PARAM_EXT_XXX messages and camera definition files (see https://mavlink.io/en/services/camera_def.html ). |Modes: P, TV, AV, M, Etc.| Shutter speed: Divisor number for one second.| Aperture: F stop number.| ISO number e.g. 80, 100, 200, Etc.| Exposure type enumerator.| Command Identity.| Main engine cut-off time before camera trigger. (0 means no cut-off)| */
+ MAV_CMD_DO_DIGICAM_CONTROL=203, /* Control digital camera. This is a fallback message for systems that have not yet implemented PARAM_EXT_XXX messages and camera definition files (see https://mavlink.io/en/services/camera_def.html ). |Session control e.g. show/hide lens| Zoom's absolute position| Zooming step value to offset zoom from the current position| Focus Locking, Unlocking or Re-locking| Shooting Command| Command Identity| Test shot identifier. If set to 1, image will only be captured, but not counted towards internal frame count.| */
+ MAV_CMD_DO_MOUNT_CONFIGURE=204, /* Mission command to configure a camera or antenna mount |Mount operation mode| Stabilize roll (MAV_BOOL_TRUE). Values not equal to 0 or 1 are invalid.| Stabilize pitch (MAV_BOOL_TRUE). Values not equal to 0 or 1 are invalid.| Stabilize yaw (MAV_BOOL_TRUE). Values not equal to 0 or 1 are invalid.| Roll input (0 = angle body frame, 1 = angular rate, 2 = angle absolute frame)| Pitch input (0 = angle body frame, 1 = angular rate, 2 = angle absolute frame)| Yaw input (0 = angle body frame, 1 = angular rate, 2 = angle absolute frame)| */
+ MAV_CMD_DO_MOUNT_CONTROL=205, /* Mission command to control a camera or antenna mount |pitch depending on mount mode (degrees or degrees/second depending on pitch input).| roll depending on mount mode (degrees or degrees/second depending on roll input).| yaw depending on mount mode (degrees or degrees/second depending on yaw input).| altitude depending on mount mode.| latitude, set if appropriate mount mode.| longitude, set if appropriate mount mode.| Mount mode.| */
+ MAV_CMD_DO_SET_CAM_TRIGG_DIST=206, /* Mission command to set camera trigger distance for this flight. The camera is triggered each time this distance is exceeded. This command can also be used to set the shutter integration time for the camera. |Camera trigger distance. 0 to stop triggering.| Camera shutter integration time. -1 or 0 to ignore| Trigger camera once, immediately (MAV_BOOL_TRUE). Values not equal to 0 or 1 are invalid.| Target camera ID. 7 to 255: MAVLink camera component id. 1 to 6 for cameras attached to the autopilot, which don't have a distinct component id. 0: all cameras. This is used to target specific autopilot-connected cameras. It is also used to target specific cameras when the MAV_CMD is used in a mission.| Empty| Empty| Empty| */
+ MAV_CMD_DO_FENCE_ENABLE=207, /*
+ Enable the geofence.
+ This can be used in a mission or via the command protocol.
+ The persistence/lifetime of the setting is undefined.
+ Depending on flight stack implementation it may persist until superseded, or it may revert to a system default at the end of a mission.
+ Flight stacks typically reset the setting to system defaults on reboot.
+ |enable? (0=disable, 1=enable, 2=disable_floor_only)| Fence types to enable or disable as a bitmask. 0: field is unused/all fences should be enabled or disabled (for compatibility reasons). Parameter is ignored if param1=2.| Empty| Empty| Empty| Empty| Empty| */
+ MAV_CMD_DO_PARACHUTE=208, /* Mission item/command to release a parachute or enable/disable auto release. |Action| Empty| Empty| Empty| Empty| Empty| Empty| */
+ MAV_CMD_DO_MOTOR_TEST=209, /* Command to perform motor test. |Motor instance number (from 1 to max number of motors on the vehicle).| Throttle type (whether the Throttle Value in param3 is a percentage, PWM value, etc.)| Throttle value.| Timeout between tests that are run in sequence.| Motor count. Number of motors to test in sequence: 0/1=one motor, 2= two motors, etc. The Timeout (param4) is used between tests.| Motor test order.| Empty| */
+ MAV_CMD_DO_INVERTED_FLIGHT=210, /* Change to/from inverted flight. |Inverted flight (MAV_BOOL_False: normal flight). Values not equal to 0 or 1 are invalid.| Empty| Empty| Empty| Empty| Empty| Empty| */
+ MAV_CMD_DO_GRIPPER=211, /* Mission command to operate a gripper. |Gripper ID. 1-6 for an autopilot connected gripper. In missions this may be set to 1-6 for an autopilot gripper, or the gripper component id for a MAVLink gripper. 0 targets all grippers.| Gripper action to perform.| Empty| Empty| Empty| Empty| Empty| */
+ MAV_CMD_DO_AUTOTUNE_ENABLE=212, /* Enable/disable autotune. |Enable autotune (MAV_BOOL_FALSE: disable autotune). Values not equal to 0 or 1 are invalid.| Specify axes for which autotuning is enabled/disabled. 0 indicates the field is unused (for compatibility reasons). If 0 the autopilot will follow its default behaviour, which is usually to tune all axes.| Empty.| Empty.| Empty.| Empty.| Empty.| */
+ MAV_CMD_NAV_SET_YAW_SPEED=213, /* Sets a desired vehicle turn angle and speed change. |Yaw angle to adjust steering by.| Speed.| Relative final angle (MAV_BOOL_FALSE: Absolute angle). Values not equal to 0 or 1 are invalid.| Empty| Empty| Empty| Empty| */
+ MAV_CMD_DO_SET_CAM_TRIGG_INTERVAL=214, /* Mission command to set camera trigger interval for this flight. If triggering is enabled, the camera is triggered each time this interval expires. This command can also be used to set the shutter integration time for the camera. |Camera trigger cycle time. -1 or 0 to ignore.| Camera shutter integration time. Should be less than trigger cycle time. -1 or 0 to ignore.| Target camera ID. 7 to 255: MAVLink camera component id. 1 to 6 for cameras attached to the autopilot, which don't have a distinct component id. 0: all cameras. This is used to target specific autopilot-connected cameras. It is also used to target specific cameras when the MAV_CMD is used in a mission.| Empty| Empty| Empty| Empty| */
+ MAV_CMD_DO_SET_RESUME_REPEAT_DIST=215, /* Set the distance to be repeated on mission resume |Distance.| Empty.| Empty.| Empty.| Empty.| Empty.| Empty.| */
+ MAV_CMD_DO_SPRAYER=216, /* Control attached liquid sprayer |0: disable sprayer. 1: enable sprayer.| Empty.| Empty.| Empty.| Empty.| Empty.| Empty.| */
+ MAV_CMD_DO_SEND_SCRIPT_MESSAGE=217, /* Pass instructions onto scripting, a script should be checking for a new command |uint16 ID value to be passed to scripting| float value to be passed to scripting| float value to be passed to scripting| float value to be passed to scripting| Empty.| Empty.| Empty.| */
+ MAV_CMD_DO_AUX_FUNCTION=218, /* Execute auxiliary function |Auxiliary Function.| Switch Level.| Empty.| Empty.| Empty.| Empty.| Empty.| */
+ MAV_CMD_DO_MOUNT_CONTROL_QUAT=220, /* Mission command to control a camera or antenna mount, using a quaternion as reference. |quaternion param q1, w (1 in null-rotation)| quaternion param q2, x (0 in null-rotation)| quaternion param q3, y (0 in null-rotation)| quaternion param q4, z (0 in null-rotation)| Empty| Empty| Empty| */
+ MAV_CMD_DO_GUIDED_MASTER=221, /* set id of master controller |System ID| Component ID| Empty| Empty| Empty| Empty| Empty| */
+ MAV_CMD_DO_GUIDED_LIMITS=222, /* Set limits for external control |Timeout - maximum time that external controller will be allowed to control vehicle. 0 means no timeout.| Altitude (MSL) min - if vehicle moves below this alt, the command will be aborted and the mission will continue. 0 means no lower altitude limit.| Altitude (MSL) max - if vehicle moves above this alt, the command will be aborted and the mission will continue. 0 means no upper altitude limit.| Horizontal move limit - if vehicle moves more than this distance from its location at the moment the command was executed, the command will be aborted and the mission will continue. 0 means no horizontal move limit.| Empty| Empty| Empty| */
+ MAV_CMD_DO_ENGINE_CONTROL=223, /* Control vehicle engine. This is interpreted by the vehicles engine controller to change the target engine state. It is intended for vehicles with internal combustion engines |Start engine (MAV_BOOL_False: Stop engine). Values not equal to 0 or 1 are invalid.| Cold start engine (MAV_BOOL_FALSE: Warm start). Values not equal to 0 or 1 are invalid. Controls use of choke where applicable| Height delay. This is for commanding engine start only after the vehicle has gained the specified height. Used in VTOL vehicles during takeoff to start engine after the aircraft is off the ground. Zero for no delay.| A bitmask of options for engine control| Empty| Empty| Empty| */
+ MAV_CMD_DO_SET_MISSION_CURRENT=224, /*
+ Set the mission item with sequence number seq as the current item and emit MISSION_CURRENT (whether or not the mission number changed).
+ If a mission is currently being executed, the system will continue to this new mission item on the shortest path, skipping any intermediate mission items.
+ Note that mission jump repeat counters are not reset unless param2 is set (see MAV_CMD_DO_JUMP param2).
+
+ This command may trigger a mission state-machine change on some systems: for example from MISSION_STATE_NOT_STARTED or MISSION_STATE_PAUSED to MISSION_STATE_ACTIVE.
+ If the system is in mission mode, on those systems this command might therefore start, restart or resume the mission.
+ If the system is not in mission mode this command must not trigger a switch to mission mode.
+
+ The mission may be "reset" using param2.
+ Resetting sets jump counters to initial values (to reset counters without changing the current mission item set the param1 to `-1`).
+ Resetting also explicitly changes a mission state of MISSION_STATE_COMPLETE to MISSION_STATE_PAUSED or MISSION_STATE_ACTIVE, potentially allowing it to resume when it is (next) in a mission mode.
+
+ The command will ACK with MAV_RESULT_FAILED if the sequence number is out of range (including if there is no mission item).
+ |Mission sequence value to set. -1 for the current mission item (use to reset mission without changing current mission item).| Reset mission (MAV_BOOL_TRUE). Values not equal to 0 or 1 are invalid. Resets jump counters to initial values and changes mission state "completed" to be "active" or "paused".| Empty| Empty| Empty| Empty| Empty| */
+ MAV_CMD_DO_LAST=240, /* NOP - This command is only used to mark the upper limit of the DO commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */
+ MAV_CMD_PREFLIGHT_CALIBRATION=241, /* Trigger calibration. This command will be only accepted if in pre-flight mode. Except for Temperature Calibration, only one sensor should be set in a single message and all others should be zero. |1: gyro calibration, 3: gyro temperature calibration| Magnetometer calibration action.| Ground pressure calibration. Values not equal to 0 or 1 are invalid.| 1: radio RC calibration, 2: RC trim calibration| Accelerometer calibration action.| 1: APM: compass/motor interference calibration (PX4: airspeed calibration, deprecated), 2: airspeed calibration| 1: ESC calibration, 3: barometer temperature calibration| */
+ MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS=242, /* Set sensor offsets. This command will be only accepted if in pre-flight mode. |Sensor to adjust the offsets for: 0: gyros, 1: accelerometer, 2: magnetometer, 3: barometer, 4: optical flow, 5: second magnetometer, 6: third magnetometer| X axis offset (or generic dimension 1), in the sensor's raw units| Y axis offset (or generic dimension 2), in the sensor's raw units| Z axis offset (or generic dimension 3), in the sensor's raw units| Generic dimension 4, in the sensor's raw units| Generic dimension 5, in the sensor's raw units| Generic dimension 6, in the sensor's raw units| */
+ MAV_CMD_PREFLIGHT_UAVCAN=243, /* Trigger UAVCAN configuration (actuator ID assignment and direction mapping). Note that this maps to the legacy UAVCAN v0 function UAVCAN_ENUMERATE, which is intended to be executed just once during initial vehicle configuration (it is not a normal pre-flight command and has been poorly named). |1: Trigger actuator ID assignment and direction mapping. 0: Cancel command.| Reserved| Reserved| Reserved| Reserved| Reserved| Reserved| */
+ MAV_CMD_PREFLIGHT_STORAGE=245, /* Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode. |Action to perform on the persistent parameter storage| Action to perform on the persistent mission storage| Onboard logging: 0: Ignore, 1: Start default rate logging, -1: Stop logging, > 1: logging rate (e.g. set to 1000 for 1000 Hz logging)| Reserved| Empty| Empty| Empty| */
+ MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN=246, /* Request the reboot or shutdown of system components. |Action to take for autopilot.| Action to take for onboard computer.| Action to take for component specified in param4.| MAVLink Component ID targeted in param3 (0 for all components).| Reserved (set to 0)| Conditions under which reboot/shutdown is allowed.| WIP: ID (e.g. camera ID -1 for all IDs)| */
+ MAV_CMD_OVERRIDE_GOTO=252, /* Override current mission with command to pause mission, pause mission and move to position, continue/resume mission. When param 1 indicates that the mission is paused (MAV_GOTO_DO_HOLD), param 2 defines whether it holds in place or moves to another position. |MAV_GOTO_DO_HOLD: pause mission and either hold or move to specified position (depending on param2), MAV_GOTO_DO_CONTINUE: resume mission.| MAV_GOTO_HOLD_AT_CURRENT_POSITION: hold at current position, MAV_GOTO_HOLD_AT_SPECIFIED_POSITION: hold at specified position.| Coordinate frame of hold point.| Desired yaw angle.| Latitude/X position.| Longitude/Y position.| Altitude/Z position.| */
+ MAV_CMD_OBLIQUE_SURVEY=260, /* Mission command to set a Camera Auto Mount Pivoting Oblique Survey (Replaces CAM_TRIGG_DIST for this purpose). The camera is triggered each time this distance is exceeded, then the mount moves to the next position. Params 4~6 set-up the angle limits and number of positions for oblique survey, where mount-enabled vehicles automatically roll the camera between shots to emulate an oblique camera setup (providing an increased HFOV). This command can also be used to set the shutter integration time for the camera. |Camera trigger distance. 0 to stop triggering.| Camera shutter integration time. 0 to ignore| The minimum interval in which the camera is capable of taking subsequent pictures repeatedly. 0 to ignore.| Total number of roll positions at which the camera will capture photos (images captures spread evenly across the limits defined by param5).| Angle limits that the camera can be rolled to left and right of center.| Fixed pitch angle that the camera will hold in oblique mode if the mount is actuated in the pitch axis.| Empty| */
+ MAV_CMD_DO_SET_STANDARD_MODE=262, /* Enable the specified standard MAVLink mode.
+ If the specified mode is not supported, the vehicle should ACK with MAV_RESULT_FAILED.
+ See https://mavlink.io/en/services/standard_modes.html
+ |The mode to set.| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:NaN)| */
+ MAV_CMD_MISSION_START=300, /* start running a mission |first_item: the first mission item to run| last_item: the last mission item to run (after this item is run, the mission ends)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */
+ MAV_CMD_ACTUATOR_TEST=310, /* Actuator testing command. This is similar to MAV_CMD_DO_MOTOR_TEST but operates on the level of output functions, i.e. it is possible to test Motor1 independent from which output it is configured on. Autopilots must NACK this command with MAV_RESULT_TEMPORARILY_REJECTED while armed. |Output value: 1 means maximum positive output, 0 to center servos or minimum motor thrust (expected to spin), -1 for maximum negative (if not supported by the motors, i.e. motor is not reversible, smaller than 0 maps to NaN). And NaN maps to disarmed (stop the motors).| Timeout after which the test command expires and the output is restored to the previous value. A timeout has to be set for safety reasons. A timeout of 0 means to restore the previous value immediately.| Reserved (default:0)| Reserved (default:0)| Actuator Output function| Reserved (default:0)| Reserved (default:0)| */
+ MAV_CMD_CONFIGURE_ACTUATOR=311, /* Actuator configuration command. |Actuator configuration action| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Actuator Output function| Reserved (default:0)| Reserved (default:0)| */
+ MAV_CMD_COMPONENT_ARM_DISARM=400, /* Arms / Disarms a component |Arm (MAV_BOOL_FALSE: disarm). Values not equal to 0 or 1 are invalid.| 0: arm-disarm unless prevented by safety checks (i.e. when landed), 21196: force arming/disarming (e.g. allow arming to override preflight checks and disarming in flight)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */
+ MAV_CMD_RUN_PREARM_CHECKS=401, /* Instructs a target system to run pre-arm checks.
+ This allows preflight checks to be run on demand, which may be useful on systems that normally run them at low rate, or which do not trigger checks when the armable state might have changed.
+ This command should return MAV_RESULT_ACCEPTED if it will run the checks.
+ The results of the checks are usually then reported in SYS_STATUS messages (this is system-specific).
+ The command should return MAV_RESULT_TEMPORARILY_REJECTED if the system is already armed.
+ |Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */
+ MAV_CMD_ILLUMINATOR_ON_OFF=405, /* Turns illuminators ON/OFF. An illuminator is a light source that is used for lighting up dark areas external to the system: e.g. a torch or searchlight (as opposed to a light source for illuminating the system itself, e.g. an indicator light). |Illuminators on/off (MAV_BOOL_TRUE: illuminators on). Values not equal to 0 or 1 are invalid.| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */
+ MAV_CMD_DO_ILLUMINATOR_CONFIGURE=406, /* Configures illuminator settings. An illuminator is a light source that is used for lighting up dark areas external to the system: e.g. a torch or searchlight (as opposed to a light source for illuminating the system itself, e.g. an indicator light). |Mode| 0%: Off, 100%: Max Brightness| Strobe period in seconds where 0 means strobing is not used| Strobe duty cycle where 100% means it is on constantly and 0 means strobing is not used| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */
+ MAV_CMD_GET_HOME_POSITION=410, /* Request the home position from the vehicle.
+ The vehicle will ACK the command and emit the HOME_POSITION message. |Reserved| Reserved| Reserved| Reserved| Reserved| Reserved| Reserved| */
+ MAV_CMD_INJECT_FAILURE=420, /* Inject artificial failure for testing purposes. Note that autopilots should implement an additional protection before accepting this command such as a specific param setting. |The unit which is affected by the failure.| The type how the failure manifests itself.| Instance affected by failure (0 to signal all).| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */
+ MAV_CMD_START_RX_PAIR=500, /* Starts receiver pairing. |RC type.| RC sub type.| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */
+ MAV_CMD_GET_MESSAGE_INTERVAL=510, /*
+ Request the interval between messages for a particular MAVLink message ID.
+ The receiver should ACK the command and then emit its response in a MESSAGE_INTERVAL message.
+ |The MAVLink message ID| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */
+ MAV_CMD_SET_MESSAGE_INTERVAL=511, /* Set the interval between messages for a particular MAVLink message ID. This interface replaces REQUEST_DATA_STREAM. |The MAVLink message ID| The interval between two messages. -1: disable. 0: request default rate (which may be zero).| Use for index ID, if required. Otherwise, the use of this parameter (if any) must be defined in the requested message. By default assumed not used (0). When used as an index ID, 0 means "all instances", "1" means the first instance in the sequence (the emitted message will have an id of 0 if message ids are 0-indexed, or 1 if index numbers start from one).| The use of this parameter (if any), must be defined in the requested message. By default assumed not used (0).| The use of this parameter (if any), must be defined in the requested message. By default assumed not used (0/NaN).| The use of this parameter (if any), must be defined in the requested message. By default assumed not used (0/NaN).| Target address of message stream (if message has target address fields). 0: Flight-stack default (recommended), 1: address of requester, 2: broadcast.| */
+ MAV_CMD_REQUEST_MESSAGE=512, /* Request the target system(s) emit a single instance of a specified message (i.e. a "one-shot" version of MAV_CMD_SET_MESSAGE_INTERVAL). |The MAVLink message ID of the requested message.| Use for index ID, if required. Otherwise, the use of this parameter (if any) must be defined in the requested message. By default assumed not used (0).| The use of this parameter (if any), must be defined in the requested message. By default assumed not used (0).| The use of this parameter (if any), must be defined in the requested message. By default assumed not used (0).| The use of this parameter (if any), must be defined in the requested message. By default assumed not used (0).| The use of this parameter (if any), must be defined in the requested message. By default assumed not used (0).| Target address for requested message (if message has target address fields). 0: Flight-stack default, 1: address of requester, 2: broadcast.| */
+ MAV_CMD_REQUEST_PROTOCOL_VERSION=519, /* Request MAVLink protocol version compatibility. All receivers should ACK the command and then emit their capabilities in an PROTOCOL_VERSION message |Request supported protocol versions by all nodes on the network (MAV_BOOL_TRUE). Values not equal to 0 or 1 are invalid.| Reserved (all remaining params)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */
+ MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES=520, /* Request autopilot capabilities. The receiver should ACK the command and then emit its capabilities in an AUTOPILOT_VERSION message |Request autopilot version (MAV_BOOL_TRUE). Values not equal to 0 or 1 are invalid.| Reserved (all remaining params)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */
+ MAV_CMD_REQUEST_CAMERA_INFORMATION=521, /* Request camera information (CAMERA_INFORMATION). |Request camera capabilities (MAV_BOOL_TRUE). Values not equal to 0 or 1 are invalid.| Reserved (all remaining params)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */
+ MAV_CMD_REQUEST_CAMERA_SETTINGS=522, /* Request camera settings (CAMERA_SETTINGS). |Request camera settings (MAV_BOOL_TRUE). Values not equal to 0 or 1 are invalid.| Reserved (all remaining params)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */
+ MAV_CMD_REQUEST_STORAGE_INFORMATION=525, /* Request storage information (STORAGE_INFORMATION). Use the command's target_component to target a specific component's storage. |Storage ID (0 for all, 1 for first, 2 for second, etc.)| Request storage information (MAV_BOOL_TRUE). Values not equal to 0 or 1 are invalid.| Reserved (all remaining params)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */
+ MAV_CMD_STORAGE_FORMAT=526, /* Format a storage medium. Once format is complete, a STORAGE_INFORMATION message is sent. Use the command's target_component to target a specific component's storage. |Storage ID (1 for first, 2 for second, etc.)| Format storage (and reset image log). Values not equal to 0 or 1 are invalid.| Reset Image Log (without formatting storage medium). This will reset CAMERA_CAPTURE_STATUS.image_count and CAMERA_IMAGE_CAPTURED.image_index. Values not equal to 0 or 1 are invalid.| Reserved (all remaining params)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */
+ MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS=527, /* Request camera capture status (CAMERA_CAPTURE_STATUS) |Request camera capture status (MAV_BOOL_TRUE). Values not equal to 0 or 1 are invalid.| Reserved (all remaining params)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */
+ MAV_CMD_REQUEST_FLIGHT_INFORMATION=528, /* Request flight information (FLIGHT_INFORMATION) |Request flight information (MAV_BOOL_TRUE). Values not equal to 0 or 1 are invalid.| Reserved (all remaining params)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */
+ MAV_CMD_RESET_CAMERA_SETTINGS=529, /* Reset all camera settings to Factory Default |Reset all settings (MAV_BOOL_TRUE). Values not equal to 0 or 1 are invalid.| Target camera ID. 7 to 255: MAVLink camera component id. 1 to 6 for cameras attached to the autopilot, which don't have a distinct component id. 0: all cameras. This is used to target specific autopilot-connected cameras. It is also used to target specific cameras when the MAV_CMD is used in a mission.| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */
+ MAV_CMD_SET_CAMERA_MODE=530, /* Set camera running mode. Use NaN for reserved values. GCS will send a MAV_CMD_REQUEST_VIDEO_STREAM_STATUS command after a mode change if the camera supports video streaming. |Target camera ID. 7 to 255: MAVLink camera component id. 1 to 6 for cameras attached to the autopilot, which don't have a distinct component id. 0: all cameras. This is used to target specific autopilot-connected cameras. It is also used to target specific cameras when the MAV_CMD is used in a mission.| Camera mode| Reserved (default:NaN)| Reserved (default:NaN)| Reserved (default:0)| Reserved (default:0)| Reserved (default:NaN)| */
+ MAV_CMD_SET_CAMERA_ZOOM=531, /* Set camera zoom. Camera must respond with a CAMERA_SETTINGS message (on success). |Zoom type| Zoom value. The range of valid values depend on the zoom type.| Target camera ID. 7 to 255: MAVLink camera component id. 1 to 6 for cameras attached to the autopilot, which don't have a distinct component id. 0: all cameras. This is used to target specific autopilot-connected cameras. It is also used to target specific cameras when the MAV_CMD is used in a mission.| Reserved (default:NaN)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */
+ MAV_CMD_SET_CAMERA_FOCUS=532, /* Set camera focus. Camera must respond with a CAMERA_SETTINGS message (on success). |Focus type| Focus value| Target camera ID. 7 to 255: MAVLink camera component id. 1 to 6 for cameras attached to the autopilot, which don't have a distinct component id. 0: all cameras. This is used to target specific autopilot-connected cameras. It is also used to target specific cameras when the MAV_CMD is used in a mission.| Reserved (default:NaN)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */
+ MAV_CMD_SET_STORAGE_USAGE=533, /* Set that a particular storage is the preferred location for saving photos, videos, and/or other media (e.g. to set that an SD card is used for storing videos).
+ There can only be one preferred save location for each particular media type: setting a media usage flag will clear/reset that same flag if set on any other storage.
+ If no flag is set the system should use its default storage.
+ A target system can choose to always use default storage, in which case it should ACK the command with MAV_RESULT_UNSUPPORTED.
+ A target system can choose to not allow a particular storage to be set as preferred storage, in which case it should ACK the command with MAV_RESULT_DENIED. |Storage ID (1 for first, 2 for second, etc.)| Usage flags| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */
+ MAV_CMD_SET_CAMERA_SOURCE=534, /* Set camera source. Changes the camera's active sources on cameras with multiple image sensors. |Component Id of camera to address or 1-6 for non-MAVLink cameras, 0 for all cameras.| Primary Source| Secondary Source. If non-zero the second source will be displayed as picture-in-picture.| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */
+ MAV_CMD_JUMP_TAG=600, /* Tagged jump target. Can be jumped to with MAV_CMD_DO_JUMP_TAG. |Tag.| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */
+ MAV_CMD_DO_JUMP_TAG=601, /* Jump to the matching tag in the mission list. Repeat this action for the specified number of times. A mission should contain a single matching tag for each jump. If this is not the case then a jump to a missing tag should complete the mission, and a jump where there are multiple matching tags should always select the one with the lowest mission sequence number. |Target tag to jump to.| Repeat count.| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */
+ MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW=1000, /* Set gimbal manager pitch/yaw setpoints (low rate command). It is possible to set combinations of the values below. E.g. an angle as well as a desired angular rate can be used to get to this angle at a certain angular rate, or an angular rate only will result in continuous turning. NaN is to be used to signal unset. Note: only the gimbal manager will react to this command - it will be ignored by a gimbal device. Use GIMBAL_MANAGER_SET_PITCHYAW if you need to stream pitch/yaw setpoints at higher rate. |Pitch angle (positive to pitch up, relative to vehicle for FOLLOW mode, relative to world horizon for LOCK mode).| Yaw angle (positive to yaw to the right, relative to vehicle for FOLLOW mode, absolute to North for LOCK mode).| Pitch rate (positive to pitch up).| Yaw rate (positive to yaw to the right).| Gimbal manager flags to use.| Reserved (default:0)| Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals).| */
+ MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE=1001, /* Gimbal configuration to set which sysid/compid is in primary and secondary control. |Sysid for primary control (0: no one in control, -1: leave unchanged, -2: set itself in control (for missions where the own sysid is still unknown), -3: remove control if currently in control).| Compid for primary control (0: no one in control, -1: leave unchanged, -2: set itself in control (for missions where the own sysid is still unknown), -3: remove control if currently in control).| Sysid for secondary control (0: no one in control, -1: leave unchanged, -2: set itself in control (for missions where the own sysid is still unknown), -3: remove control if currently in control).| Compid for secondary control (0: no one in control, -1: leave unchanged, -2: set itself in control (for missions where the own sysid is still unknown), -3: remove control if currently in control).| Reserved (default:0)| Reserved (default:0)| Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals).| */
+ MAV_CMD_IMAGE_START_CAPTURE=2000, /* Start image capture sequence. CAMERA_IMAGE_CAPTURED must be emitted after each capture.
+
+ Param1 (id) may be used to specify the target camera: 0: all cameras, 1 to 6: autopilot-connected cameras, 7-255: MAVLink camera component ID.
+ It is needed in order to target specific cameras connected to the autopilot, or specific sensors in a multi-sensor camera (neither of which have a distinct MAVLink component ID).
+ It is also needed to specify the target camera in missions.
+
+ When used in a mission, an autopilot should execute the MAV_CMD for a specified local camera (param1 = 1-6), or resend it as a command if it is intended for a MAVLink camera (param1 = 7 - 255), setting the command's target_component as the param1 value (and setting param1 in the command to zero).
+ If the param1 is 0 the autopilot should do both.
+
+ When sent in a command the target MAVLink address is set using target_component.
+ If addressed specifically to an autopilot: param1 should be used in the same way as it is for missions (though command should NACK with MAV_RESULT_DENIED if a specified local camera does not exist).
+ If addressed to a MAVLink camera, param 1 can be used to address all cameras (0), or to separately address 1 to 7 individual sensors. Other values should be NACKed with MAV_RESULT_DENIED.
+ If the command is broadcast (target_component is 0) then param 1 should be set to 0 (any other value should be NACKED with MAV_RESULT_DENIED). An autopilot would trigger any local cameras and forward the command to all channels.
+ |Target camera ID. 7 to 255: MAVLink camera component id. 1 to 6 for cameras attached to the autopilot, which don't have a distinct component id. 0: all cameras. This is used to target specific autopilot-connected cameras. It is also used to target specific cameras when the MAV_CMD is used in a mission.| Desired elapsed time between two consecutive pictures (in seconds). Minimum values depend on hardware (typically greater than 2 seconds).| Total number of images to capture. 0 to capture forever/until MAV_CMD_IMAGE_STOP_CAPTURE.| Capture sequence number starting from 1. This is only valid for single-capture (param3 == 1), otherwise set to 0. Increment the capture ID for each capture command to prevent double captures when a command is re-transmitted.| Reserved (default:0)| Reserved (default:0)| Reserved (default:NaN)| */
+ MAV_CMD_IMAGE_STOP_CAPTURE=2001, /* Stop image capture sequence.
+
+ Param1 (id) may be used to specify the target camera: 0: all cameras, 1 to 6: autopilot-connected cameras, 7-255: MAVLink camera component ID.
+ It is needed in order to target specific cameras connected to the autopilot, or specific sensors in a multi-sensor camera (neither of which have a distinct MAVLink component ID).
+ It is also needed to specify the target camera in missions.
+
+ When used in a mission, an autopilot should execute the MAV_CMD for a specified local camera (param1 = 1-6), or resend it as a command if it is intended for a MAVLink camera (param1 = 7 - 255), setting the command's target_component as the param1 value (and setting param1 in the command to zero).
+ If the param1 is 0 the autopilot should do both.
+
+ When sent in a command the target MAVLink address is set using target_component.
+ If addressed specifically to an autopilot: param1 should be used in the same way as it is for missions (though command should NACK with MAV_RESULT_DENIED if a specified local camera does not exist).
+ If addressed to a MAVLink camera, param1 can be used to address all cameras (0), or to separately address 1 to 7 individual sensors. Other values should be NACKed with MAV_RESULT_DENIED.
+ If the command is broadcast (target_component is 0) then param 1 should be set to 0 (any other value should be NACKED with MAV_RESULT_DENIED). An autopilot would trigger any local cameras and forward the command to all channels.
+ |Target camera ID. 7 to 255: MAVLink camera component id. 1 to 6 for cameras attached to the autopilot, which don't have a distinct component id. 0: all cameras. This is used to target specific autopilot-connected cameras. It is also used to target specific cameras when the MAV_CMD is used in a mission.| Reserved (default:NaN)| Reserved (default:NaN)| Reserved (default:NaN)| Reserved (default:0)| Reserved (default:0)| Reserved (default:NaN)| */
+ MAV_CMD_REQUEST_CAMERA_IMAGE_CAPTURE=2002, /* Re-request a CAMERA_IMAGE_CAPTURED message. |Sequence number for missing CAMERA_IMAGE_CAPTURED message| Reserved (default:NaN)| Reserved (default:NaN)| Reserved (default:NaN)| Reserved (default:0)| Reserved (default:0)| Reserved (default:NaN)| */
+ MAV_CMD_DO_TRIGGER_CONTROL=2003, /* Enable or disable on-board camera triggering system. |Trigger enable/disable (0 for disable, 1 for start), -1 to ignore| 1 to reset the trigger sequence, -1 or 0 to ignore| 1 to pause triggering, but without switching the camera off or retracting it. -1 to ignore| Target camera ID. 7 to 255: MAVLink camera component id. 1 to 6 for cameras attached to the autopilot, which don't have a distinct component id. 0: all cameras. This is used to target specific autopilot-connected cameras. It is also used to target specific cameras when the MAV_CMD is used in a mission.| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */
+ MAV_CMD_CAMERA_TRACK_POINT=2004, /* If the camera supports point visual tracking (CAMERA_CAP_FLAGS_HAS_TRACKING_POINT is set), this command allows to initiate the tracking. |Point to track x value (normalized 0..1, 0 is left, 1 is right).| Point to track y value (normalized 0..1, 0 is top, 1 is bottom).| Point radius (normalized 0..1, 0 is one pixel, 1 is full image width).| Target camera ID. 7 to 255: MAVLink camera component id. 1 to 6 for cameras attached to the autopilot, which don't have a distinct component id. 0: all cameras. This is used to target specific autopilot-connected cameras. It is also used to target specific cameras when the MAV_CMD is used in a mission.| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */
+ MAV_CMD_CAMERA_TRACK_RECTANGLE=2005, /* If the camera supports rectangle visual tracking (CAMERA_CAP_FLAGS_HAS_TRACKING_RECTANGLE is set), this command allows to initiate the tracking. |Top left corner of rectangle x value (normalized 0..1, 0 is left, 1 is right).| Top left corner of rectangle y value (normalized 0..1, 0 is top, 1 is bottom).| Bottom right corner of rectangle x value (normalized 0..1, 0 is left, 1 is right).| Bottom right corner of rectangle y value (normalized 0..1, 0 is top, 1 is bottom).| Target camera ID. 7 to 255: MAVLink camera component id. 1 to 6 for cameras attached to the autopilot, which don't have a distinct component id. 0: all cameras. This is used to target specific autopilot-connected cameras. It is also used to target specific cameras when the MAV_CMD is used in a mission.| Reserved (default:0)| Reserved (default:0)| */
+ MAV_CMD_CAMERA_STOP_TRACKING=2010, /* Stops ongoing tracking. |Target camera ID. 7 to 255: MAVLink camera component id. 1 to 6 for cameras attached to the autopilot, which don't have a distinct component id. 0: all cameras. This is used to target specific autopilot-connected cameras. It is also used to target specific cameras when the MAV_CMD is used in a mission.| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */
+ MAV_CMD_VIDEO_START_CAPTURE=2500, /* Starts video capture (recording). |Video Stream ID (0 for all streams)| Frequency CAMERA_CAPTURE_STATUS messages should be sent while recording (0 for no messages, otherwise frequency)| Target camera ID. 7 to 255: MAVLink camera component id. 1 to 6 for cameras attached to the autopilot, which don't have a distinct component id. 0: all cameras. This is used to target specific autopilot-connected cameras. It is also used to target specific cameras when the MAV_CMD is used in a mission.| Reserved (default:NaN)| Reserved (default:0)| Reserved (default:0)| Reserved (default:NaN)| */
+ MAV_CMD_VIDEO_STOP_CAPTURE=2501, /* Stop the current video capture (recording). |Video Stream ID (0 for all streams)| Target camera ID. 7 to 255: MAVLink camera component id. 1 to 6 for cameras attached to the autopilot, which don't have a distinct component id. 0: all cameras. This is used to target specific autopilot-connected cameras. It is also used to target specific cameras when the MAV_CMD is used in a mission.| Reserved (default:NaN)| Reserved (default:NaN)| Reserved (default:0)| Reserved (default:0)| Reserved (default:NaN)| */
+ MAV_CMD_VIDEO_START_STREAMING=2502, /* Start video streaming |Video Stream ID (0 for all streams, 1 for first, 2 for second, etc.)| Target camera ID. 7 to 255: MAVLink camera component id. 1 to 6 for cameras attached to the autopilot, which don't have a distinct component id. 0: all cameras. This is used to target specific autopilot-connected cameras. It is also used to target specific cameras when the MAV_CMD is used in a mission.| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */
+ MAV_CMD_VIDEO_STOP_STREAMING=2503, /* Stop the given video stream |Video Stream ID (0 for all streams, 1 for first, 2 for second, etc.)| Target camera ID. 7 to 255: MAVLink camera component id. 1 to 6 for cameras attached to the autopilot, which don't have a distinct component id. 0: all cameras. This is used to target specific autopilot-connected cameras. It is also used to target specific cameras when the MAV_CMD is used in a mission.| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */
+ MAV_CMD_REQUEST_VIDEO_STREAM_INFORMATION=2504, /* Request video stream information (VIDEO_STREAM_INFORMATION) |Video Stream ID (0 for all streams, 1 for first, 2 for second, etc.)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */
+ MAV_CMD_REQUEST_VIDEO_STREAM_STATUS=2505, /* Request video stream status (VIDEO_STREAM_STATUS) |Video Stream ID (0 for all streams, 1 for first, 2 for second, etc.)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */
+ MAV_CMD_LOGGING_START=2510, /* Request to start streaming logging data over MAVLink (see also LOGGING_DATA message) |Format: 0: ULog| Reserved (set to 0)| Reserved (set to 0)| Reserved (set to 0)| Reserved (set to 0)| Reserved (set to 0)| Reserved (set to 0)| */
+ MAV_CMD_LOGGING_STOP=2511, /* Request to stop streaming log data over MAVLink |Reserved (set to 0)| Reserved (set to 0)| Reserved (set to 0)| Reserved (set to 0)| Reserved (set to 0)| Reserved (set to 0)| Reserved (set to 0)| */
+ MAV_CMD_AIRFRAME_CONFIGURATION=2520, /* |Landing gear ID (default: 0, -1 for all)| Landing gear position (Down: 0, Up: 1, NaN for no change)| Reserved (default:NaN)| Reserved (default:NaN)| Reserved (default:0)| Reserved (default:0)| Reserved (default:NaN)| */
+ MAV_CMD_CONTROL_HIGH_LATENCY=2600, /* Request to start/stop transmitting over the high latency telemetry |Start transmission over high latency telemetry (MAV_BOOL_FALSE: stop transmission). Values not equal to 0 or 1 are invalid.| Empty| Empty| Empty| Empty| Empty| Empty| */
+ MAV_CMD_PANORAMA_CREATE=2800, /* Create a panorama at the current position |Viewing angle horizontal of the panorama (+- 0.5 the total angle)| Viewing angle vertical of panorama.| Speed of the horizontal rotation.| Speed of the vertical rotation.| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */
+ MAV_CMD_DO_VTOL_TRANSITION=3000, /* Request VTOL transition |The target VTOL state. For normal transitions, only MAV_VTOL_STATE_MC and MAV_VTOL_STATE_FW can be used.| Force immediate transition to the specified MAV_VTOL_STATE. 1: Force immediate, 0: normal transition. Can be used, for example, to trigger an emergency "Quadchute". Caution: Can be dangerous/damage vehicle, depending on autopilot implementation of this command.| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */
+ MAV_CMD_ARM_AUTHORIZATION_REQUEST=3001, /* Request authorization to arm the vehicle to a external entity, the arm authorizer is responsible to request all data that is needs from the vehicle before authorize or deny the request.
+ If approved the COMMAND_ACK message progress field should be set with period of time that this authorization is valid in seconds.
+ If the authorization is denied COMMAND_ACK.result_param2 should be set with one of the reasons in MAV_ARM_AUTH_DENIED_REASON.
+ |Vehicle system id, this way ground station can request arm authorization on behalf of any vehicle| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */
+ MAV_CMD_SET_GUIDED_SUBMODE_STANDARD=4000, /* This command sets the submode to standard guided when vehicle is in guided mode. The vehicle holds position and altitude and the user can input the desired velocities along all three axes.
+ |Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */
+ MAV_CMD_SET_GUIDED_SUBMODE_CIRCLE=4001, /* This command sets submode circle when vehicle is in guided mode. Vehicle flies along a circle facing the center of the circle. The user can input the velocity along the circle and change the radius. If no input is given the vehicle will hold position.
+ |Radius of desired circle in CIRCLE_MODE| User defined| User defined| User defined| Target latitude of center of circle in CIRCLE_MODE| Target longitude of center of circle in CIRCLE_MODE| Reserved (default:0)| */
+ MAV_CMD_CONDITION_GATE=4501, /* Delay mission state machine until gate has been reached. |Geometry: 0: orthogonal to path between previous and next waypoint.| Use altitude (MAV_BOOL_FALSE: ignore altitude). Values not equal to 0 or 1 are invalid.| Empty| Empty| Latitude| Longitude| Altitude| */
+ MAV_CMD_NAV_FENCE_RETURN_POINT=5000, /* Fence return point (there can only be one such point in a geofence definition). If rally points are supported they should be used instead. |Reserved| Reserved| Reserved| Reserved| Latitude| Longitude| Altitude| */
+ MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION=5001, /* Fence vertex for an inclusion polygon (the polygon must not be self-intersecting). The vehicle must stay within this area. Minimum of 3 vertices required.
+ The vertices for a polygon must be sent sequentially, each with param1 set to the total number of vertices in the polygon.
+ |Polygon vertex count. This is the number of vertices in the current polygon (all vertices will have the same number).| Vehicle must be inside ALL inclusion zones in a single group, vehicle must be inside at least one group, must be the same for all points in each polygon| Reserved| Reserved| Latitude| Longitude| Reserved| */
+ MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION=5002, /* Fence vertex for an exclusion polygon (the polygon must not be self-intersecting). The vehicle must stay outside this area. Minimum of 3 vertices required.
+ The vertices for a polygon must be sent sequentially, each with param1 set to the total number of vertices in the polygon.
+ |Polygon vertex count. This is the number of vertices in the current polygon (all vertices will have the same number).| Reserved| Reserved| Reserved| Latitude| Longitude| Reserved| */
+ MAV_CMD_NAV_FENCE_CIRCLE_INCLUSION=5003, /* Circular fence area. The vehicle must stay inside this area.
+ |Radius.| Vehicle must be inside ALL inclusion zones in a single group, vehicle must be inside at least one group| Reserved| Reserved| Latitude| Longitude| Reserved| */
+ MAV_CMD_NAV_FENCE_CIRCLE_EXCLUSION=5004, /* Circular fence area. The vehicle must stay outside this area.
+ |Radius.| Reserved| Reserved| Reserved| Latitude| Longitude| Reserved| */
+ MAV_CMD_NAV_RALLY_POINT=5100, /* Rally point. You can have multiple rally points defined.
+ |Reserved| Reserved| Reserved| Reserved| Latitude| Longitude| Altitude| */
+ MAV_CMD_UAVCAN_GET_NODE_INFO=5200, /* Commands the vehicle to respond with a sequence of messages UAVCAN_NODE_INFO, one message per every UAVCAN node that is online. Note that some of the response messages can be lost, which the receiver can detect easily by checking whether every received UAVCAN_NODE_STATUS has a matching message UAVCAN_NODE_INFO received earlier; if not, this command should be sent again in order to request re-transmission of the node information messages. |Reserved (set to 0)| Reserved (set to 0)| Reserved (set to 0)| Reserved (set to 0)| Reserved (set to 0)| Reserved (set to 0)| Reserved (set to 0)| */
+ MAV_CMD_DO_SET_SAFETY_SWITCH_STATE=5300, /* Change state of safety switch. |New safety switch state.| Empty.| Empty.| Empty| Empty.| Empty.| Empty.| */
+ MAV_CMD_DO_ADSB_OUT_IDENT=10001, /* Trigger the start of an ADSB-out IDENT. This should only be used when requested to do so by an Air Traffic Controller in controlled airspace. This starts the IDENT which is then typically held for 18 seconds by the hardware per the Mode A, C, and S transponder spec. |Reserved (set to 0)| Reserved (set to 0)| Reserved (set to 0)| Reserved (set to 0)| Reserved (set to 0)| Reserved (set to 0)| Reserved (set to 0)| */
+ MAV_CMD_LOWEHEISER_SET_STATE=10151, /* Set Loweheiser desired states |EFI Index| Desired Engine/EFI State (0: Power Off, 1:Running)| Desired Governor State (0:manual throttle, 1:Governed throttle)| Manual throttle level, 0% - 100%| Electronic Start up (0:Off, 1:On)| Empty| Empty| */
+ MAV_CMD_PAYLOAD_PREPARE_DEPLOY=30001, /* Deploy payload on a Lat / Lon / Alt position. This includes the navigation to reach the required release position and velocity. |Operation mode. 0: prepare single payload deploy (overwriting previous requests), but do not execute it. 1: execute payload deploy immediately (rejecting further deploy commands during execution, but allowing abort). 2: add payload deploy to existing deployment list.| Desired approach vector in compass heading. A negative value indicates the system can define the approach vector at will.| Desired ground speed at release time. This can be overridden by the airframe in case it needs to meet minimum airspeed. A negative value indicates the system can define the ground speed at will.| Minimum altitude clearance to the release position. A negative value indicates the system can define the clearance at will.| Latitude.| Longitude.| Altitude (MSL)| */
+ MAV_CMD_PAYLOAD_CONTROL_DEPLOY=30002, /* Control the payload deployment. |Operation mode. 0: Abort deployment, continue normal mission. 1: switch to payload deployment mode. 100: delete first payload deployment request. 101: delete all payload deployment requests.| Reserved| Reserved| Reserved| Reserved| Reserved| Reserved| */
+ MAV_CMD_WAYPOINT_USER_1=31000, /* User defined waypoint item. Ground Station will show the Vehicle as flying through this item. |User defined| User defined| User defined| User defined| Latitude unscaled| Longitude unscaled| Altitude (MSL)| */
+ MAV_CMD_WAYPOINT_USER_2=31001, /* User defined waypoint item. Ground Station will show the Vehicle as flying through this item. |User defined| User defined| User defined| User defined| Latitude unscaled| Longitude unscaled| Altitude (MSL)| */
+ MAV_CMD_WAYPOINT_USER_3=31002, /* User defined waypoint item. Ground Station will show the Vehicle as flying through this item. |User defined| User defined| User defined| User defined| Latitude unscaled| Longitude unscaled| Altitude (MSL)| */
+ MAV_CMD_WAYPOINT_USER_4=31003, /* User defined waypoint item. Ground Station will show the Vehicle as flying through this item. |User defined| User defined| User defined| User defined| Latitude unscaled| Longitude unscaled| Altitude (MSL)| */
+ MAV_CMD_WAYPOINT_USER_5=31004, /* User defined waypoint item. Ground Station will show the Vehicle as flying through this item. |User defined| User defined| User defined| User defined| Latitude unscaled| Longitude unscaled| Altitude (MSL)| */
+ MAV_CMD_SPATIAL_USER_1=31005, /* User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item. |User defined| User defined| User defined| User defined| Latitude unscaled| Longitude unscaled| Altitude (MSL)| */
+ MAV_CMD_SPATIAL_USER_2=31006, /* User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item. |User defined| User defined| User defined| User defined| Latitude unscaled| Longitude unscaled| Altitude (MSL)| */
+ MAV_CMD_SPATIAL_USER_3=31007, /* User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item. |User defined| User defined| User defined| User defined| Latitude unscaled| Longitude unscaled| Altitude (MSL)| */
+ MAV_CMD_SPATIAL_USER_4=31008, /* User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item. |User defined| User defined| User defined| User defined| Latitude unscaled| Longitude unscaled| Altitude (MSL)| */
+ MAV_CMD_SPATIAL_USER_5=31009, /* User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item. |User defined| User defined| User defined| User defined| Latitude unscaled| Longitude unscaled| Altitude (MSL)| */
+ MAV_CMD_USER_1=31010, /* User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item. |User defined| User defined| User defined| User defined| User defined| User defined| User defined| */
+ MAV_CMD_USER_2=31011, /* User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item. |User defined| User defined| User defined| User defined| User defined| User defined| User defined| */
+ MAV_CMD_USER_3=31012, /* User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item. |User defined| User defined| User defined| User defined| User defined| User defined| User defined| */
+ MAV_CMD_USER_4=31013, /* User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item. |User defined| User defined| User defined| User defined| User defined| User defined| User defined| */
+ MAV_CMD_USER_5=31014, /* User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item. |User defined| User defined| User defined| User defined| User defined| User defined| User defined| */
+ MAV_CMD_CAN_FORWARD=32000, /* Request forwarding of CAN packets from the given CAN bus to this component via this MAVLink channel. CAN Frames are sent using CAN_FRAME and CANFD_FRAME messages |Bus number (0 to disable forwarding, 1 for first bus, 2 for 2nd bus, 3 for 3rd bus).| Empty.| Empty.| Empty.| Empty.| Empty.| Empty.| */
+ MAV_CMD_POWER_OFF_INITIATED=42000, /* A system wide power-off event has been initiated. |Empty.| Empty.| Empty.| Empty.| Empty.| Empty.| Empty.| */
+ MAV_CMD_SOLO_BTN_FLY_CLICK=42001, /* FLY button has been clicked. |Empty.| Empty.| Empty.| Empty.| Empty.| Empty.| Empty.| */
+ MAV_CMD_SOLO_BTN_FLY_HOLD=42002, /* FLY button has been held for 1.5 seconds. |Takeoff altitude.| Empty.| Empty.| Empty.| Empty.| Empty.| Empty.| */
+ MAV_CMD_SOLO_BTN_PAUSE_CLICK=42003, /* PAUSE button has been clicked. |1 if Solo is in a shot mode, 0 otherwise.| Empty.| Empty.| Empty.| Empty.| Empty.| Empty.| */
+ MAV_CMD_FIXED_MAG_CAL=42004, /* Magnetometer calibration based on fixed position
+ in earth field given by inclination, declination and intensity. |Magnetic declination.| Magnetic inclination.| Magnetic intensity.| Yaw.| Empty.| Empty.| Empty.| */
+ MAV_CMD_FIXED_MAG_CAL_FIELD=42005, /* Magnetometer calibration based on fixed expected field values. |Field strength X.| Field strength Y.| Field strength Z.| Empty.| Empty.| Empty.| Empty.| */
+ MAV_CMD_FIXED_MAG_CAL_YAW=42006, /* Magnetometer calibration based on provided known yaw. This allows for fast calibration using WMM field tables in the vehicle, given only the known yaw of the vehicle. If Latitude and longitude are both zero then use the current vehicle location. |Yaw of vehicle in earth frame.| CompassMask, 0 for all.| Latitude.| Longitude.| Empty.| Empty.| Empty.| */
+ MAV_CMD_SET_EKF_SOURCE_SET=42007, /* Set EKF sensor source set. |Source Set Id.| Empty.| Empty.| Empty.| Empty.| Empty.| Empty.| */
+ MAV_CMD_DO_START_MAG_CAL=42424, /* Initiate a magnetometer calibration. |Bitmask of magnetometers to calibrate. Use 0 to calibrate all sensors that can be started (sensors may not start if disabled, unhealthy, etc.). The command will NACK if calibration does not start for a sensor explicitly specified by the bitmask.| Automatically retry on failure (0=no retry, 1=retry).| Save without user input (0=require input, 1=autosave).| Delay.| Autoreboot (0=user reboot, 1=autoreboot).| Empty.| Empty.| */
+ MAV_CMD_DO_ACCEPT_MAG_CAL=42425, /* Accept a magnetometer calibration. |Bitmask of magnetometers that calibration is accepted (0 means all).| Empty.| Empty.| Empty.| Empty.| Empty.| Empty.| */
+ MAV_CMD_DO_CANCEL_MAG_CAL=42426, /* Cancel a running magnetometer calibration. |Bitmask of magnetometers to cancel a running calibration (0 means all).| Empty.| Empty.| Empty.| Empty.| Empty.| Empty.| */
+ MAV_CMD_SET_FACTORY_TEST_MODE=42427, /* Command autopilot to get into factory test/diagnostic mode. |0: activate test mode, 1: exit test mode.| Empty.| Empty.| Empty.| Empty.| Empty.| Empty.| */
+ MAV_CMD_DO_SEND_BANNER=42428, /* Reply with the version banner. |Empty.| Empty.| Empty.| Empty.| Empty.| Empty.| Empty.| */
+ MAV_CMD_ACCELCAL_VEHICLE_POS=42429, /* Used when doing accelerometer calibration. When sent to the GCS tells it what position to put the vehicle in. When sent to the vehicle says what position the vehicle is in. |Position.| Empty.| Empty.| Empty.| Empty.| Empty.| Empty.| */
+ MAV_CMD_GIMBAL_RESET=42501, /* Causes the gimbal to reset and boot as if it was just powered on. |Empty.| Empty.| Empty.| Empty.| Empty.| Empty.| Empty.| */
+ MAV_CMD_GIMBAL_AXIS_CALIBRATION_STATUS=42502, /* Reports progress and success or failure of gimbal axis calibration procedure. |Gimbal axis we're reporting calibration progress for.| Current calibration progress for this axis.| Status of the calibration.| Empty.| Empty.| Empty.| Empty.| */
+ MAV_CMD_GIMBAL_REQUEST_AXIS_CALIBRATION=42503, /* Starts commutation calibration on the gimbal. |Empty.| Empty.| Empty.| Empty.| Empty.| Empty.| Empty.| */
+ MAV_CMD_GIMBAL_FULL_RESET=42505, /* Erases gimbal application and parameters. |Magic number.| Magic number.| Magic number.| Magic number.| Magic number.| Magic number.| Magic number.| */
+ MAV_CMD_DO_WINCH=42600, /* Command to operate winch. |Winch instance number.| Action to perform.| Length of line to release (negative to wind).| Release rate (negative to wind).| Empty.| Empty.| Empty.| */
+ MAV_CMD_FLASH_BOOTLOADER=42650, /* Update the bootloader |Empty| Empty| Empty| Empty| Magic number - set to 290876 to actually flash| Empty| Empty| */
+ MAV_CMD_BATTERY_RESET=42651, /* Reset battery capacity for batteries that accumulate consumed battery via integration. |Bitmask of batteries to reset. Least significant bit is for the first battery.| Battery percentage remaining to set.| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */
+ MAV_CMD_DEBUG_TRAP=42700, /* Issue a trap signal to the autopilot process, presumably to enter the debugger. |Magic number - set to 32451 to actually trap.| Empty.| Empty.| Empty.| Empty.| Empty.| Empty.| */
+ MAV_CMD_SCRIPTING=42701, /* Control onboard scripting. |Scripting command to execute| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */
+ MAV_CMD_NAV_SCRIPT_TIME=42702, /* Scripting command as NAV command with wait for completion. |integer command number (0 to 255)| timeout for operation in seconds. Zero means no timeout (0 to 255)| argument1.| argument2.| argument3.| argument4.| Empty| */
+ MAV_CMD_NAV_ATTITUDE_TIME=42703, /* Maintain an attitude for a specified time. |Time to maintain specified attitude and climb rate| Roll angle in degrees (positive is lean right, negative is lean left)| Pitch angle in degrees (positive is lean back, negative is lean forward)| Yaw angle| Climb rate| Empty| Empty| */
+ MAV_CMD_GUIDED_CHANGE_SPEED=43000, /* Change flight speed at a given rate. This slews the vehicle at a controllable rate between it's previous speed and the new one. (affects GUIDED only. Outside GUIDED, aircraft ignores these commands. Designed for onboard companion-computer command-and-control, not normally operator/GCS control.) |Airspeed or groundspeed.| Target Speed| Acceleration rate, 0 to take effect instantly| Empty| Empty| Empty| Empty| */
+ MAV_CMD_GUIDED_CHANGE_ALTITUDE=43001, /* Change target altitude at a given rate. This slews the vehicle at a controllable rate between it's previous altitude and the new one. (affects GUIDED only. Outside GUIDED, aircraft ignores these commands. Designed for onboard companion-computer command-and-control, not normally operator/GCS control.) |Empty| Empty| Rate of change, toward new altitude. 0 for maximum rate change. Positive numbers only, as negative numbers will not converge on the new target alt.| Empty| Empty| Empty| Target Altitude| */
+ MAV_CMD_GUIDED_CHANGE_HEADING=43002, /* Change to target heading at a given rate, overriding previous heading/s. This slews the vehicle at a controllable rate between it's previous heading and the new one. (affects GUIDED only. Exiting GUIDED returns aircraft to normal behaviour defined elsewhere. Designed for onboard companion-computer command-and-control, not normally operator/GCS control.) |course-over-ground or raw vehicle heading.| Target heading.| Maximum centripetal accelearation, ie rate of change, toward new heading.| Empty| Empty| Empty| Empty| */
+ MAV_CMD_EXTERNAL_POSITION_ESTIMATE=43003, /* Provide an external position estimate for use when dead-reckoning. This is meant to be used for occasional position resets that may be provided by a external system such as a remote pilot using landmarks over a video link. |Timestamp that this message was sent as a time in the transmitters time domain. The sender should wrap this time back to zero based on required timing accuracy for the application and the limitations of a 32 bit float. For example, wrapping at 10 hours would give approximately 1ms accuracy. Recipient must handle time wrap in any timing jitter correction applied to this field. Wrap rollover time should not be at not more than 250 seconds, which would give approximately 10 microsecond accuracy.| The time spent in processing the sensor data that is the basis for this position. The recipient can use this to improve time alignment of the data. Set to zero if not known.| estimated one standard deviation accuracy of the measurement. Set to NaN if not known.| Empty| Latitude| Longitude| Altitude, not used. Should be sent as NaN. May be supported in a future version of this message.| */
+ MAV_CMD_SET_HAGL=43005, /* Provide a value for height above ground level. This can be used for things like fixed wing and VTOL landing. |Height above ground level.| estimated one standard deviation accuracy of the measurement. Set to NaN if not known.| Timeout for this data. The flight controller should only consider this data valid within the timeout window.| Empty| Empty| Empty| Empty| */
+ MAV_CMD_STORM32_DO_GIMBAL_MANAGER_CONTROL_PITCHYAW=60002, /* Command to a gimbal manager to control the gimbal tilt and pan angles. It is possible to set combinations of the values below. E.g. an angle as well as a desired angular rate can be used to get to this angle at a certain angular rate, or an angular rate only will result in continuous turning. NaN is to be used to signal unset. A gimbal device is never to react to this command. |Pitch/tilt angle (positive: tilt up). NaN to be ignored.| Yaw/pan angle (positive: pan to the right). NaN to be ignored. The frame is determined by the GIMBAL_DEVICE_FLAGS_YAW_IN_xxx_FRAME flags.| Pitch/tilt rate (positive: tilt up). NaN to be ignored.| Yaw/pan rate (positive: pan to the right). NaN to be ignored. The frame is determined by the GIMBAL_DEVICE_FLAGS_YAW_IN_xxx_FRAME flags.| Gimbal device flags to be applied.| Gimbal manager flags to be applied.| Gimbal ID of the gimbal manager to address (component ID or 1-6 for non-MAVLink gimbal, 0 for all gimbals). Send command multiple times for more than one but not all gimbals. The client is copied into bits 8-15.| */
+ MAV_CMD_STORM32_DO_GIMBAL_MANAGER_SETUP=60010, /* Command to configure a gimbal manager. A gimbal device is never to react to this command. The selected profile is reported in the STORM32_GIMBAL_MANAGER_STATUS message. |Gimbal manager profile (0 = default).| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Gimbal ID of the gimbal manager to address (component ID or 1-6 for non-MAVLink gimbal, 0 for all gimbals). Send command multiple times for more than one but not all gimbals.| */
+ MAV_CMD_QSHOT_DO_CONFIGURE=60020, /* Command to set the shot manager mode. |Set shot mode.| Set shot state or command. The allowed values are specific to the selected shot mode.| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| Reserved (default:0)| */
+ MAV_CMD_ENUM_END=60021, /* | */
+} MAV_CMD;
+#endif
+
+/** @brief RADIO_LINK_STATS flags (bitmask).
+ The RX_RECEIVE and TX_RECEIVE flags indicate from which antenna the received data are taken for processing.
+ If a flag is set then the data received on antenna2 is processed, else the data received on antenna1 is used.
+ The RX_TRANSMIT and TX_TRANSMIT flags specify which antenna are transmitting data.
+ Both antenna 1 and antenna 2 transmit flags can be set simultaneously, e.g., in case of dual-band or dual-frequency systems.
+ If neither flag is set then antenna 1 should be assumed.
+ */
+#ifndef HAVE_ENUM_MLRS_RADIO_LINK_STATS_FLAGS
+#define HAVE_ENUM_MLRS_RADIO_LINK_STATS_FLAGS
+typedef enum MLRS_RADIO_LINK_STATS_FLAGS
+{
+ MLRS_RADIO_LINK_STATS_FLAGS_RSSI_DBM=1, /* Rssi values are in negative dBm. Values 1..254 corresponds to -1..-254 dBm. 0: no reception, UINT8_MAX: unknown. | */
+ MLRS_RADIO_LINK_STATS_FLAGS_RX_RECEIVE_ANTENNA2=2, /* Rx receive antenna. When set the data received on antenna 2 are taken, else the data stems from antenna 1. | */
+ MLRS_RADIO_LINK_STATS_FLAGS_RX_TRANSMIT_ANTENNA1=4, /* Rx transmit antenna. Data are transmitted on antenna 1. | */
+ MLRS_RADIO_LINK_STATS_FLAGS_RX_TRANSMIT_ANTENNA2=8, /* Rx transmit antenna. Data are transmitted on antenna 2. | */
+ MLRS_RADIO_LINK_STATS_FLAGS_TX_RECEIVE_ANTENNA2=16, /* Tx receive antenna. When set the data received on antenna 2 are taken, else the data stems from antenna 1. | */
+ MLRS_RADIO_LINK_STATS_FLAGS_TX_TRANSMIT_ANTENNA1=32, /* Tx transmit antenna. Data are transmitted on antenna 1. | */
+ MLRS_RADIO_LINK_STATS_FLAGS_TX_TRANSMIT_ANTENNA2=64, /* Tx transmit antenna. Data are transmitted on antenna 2. | */
+ MLRS_RADIO_LINK_STATS_FLAGS_ENUM_END=65, /* | */
+} MLRS_RADIO_LINK_STATS_FLAGS;
+#endif
+
+/** @brief RADIO_LINK_TYPE enum. */
+#ifndef HAVE_ENUM_MLRS_RADIO_LINK_TYPE
+#define HAVE_ENUM_MLRS_RADIO_LINK_TYPE
+typedef enum MLRS_RADIO_LINK_TYPE
+{
+ MLRS_RADIO_LINK_TYPE_GENERIC=0, /* Unknown radio link type. | */
+ MLRS_RADIO_LINK_TYPE_HERELINK=1, /* Radio link is HereLink. | */
+ MLRS_RADIO_LINK_TYPE_DRAGONLINK=2, /* Radio link is Dragon Link. | */
+ MLRS_RADIO_LINK_TYPE_RFD900=3, /* Radio link is RFD900. | */
+ MLRS_RADIO_LINK_TYPE_CROSSFIRE=4, /* Radio link is Crossfire. | */
+ MLRS_RADIO_LINK_TYPE_EXPRESSLRS=5, /* Radio link is ExpressLRS. | */
+ MLRS_RADIO_LINK_TYPE_MLRS=6, /* Radio link is mLRS. | */
+ MLRS_RADIO_LINK_TYPE_ENUM_END=7, /* | */
+} MLRS_RADIO_LINK_TYPE;
+#endif
+
+// MAVLINK VERSION
+
+#ifndef MAVLINK_VERSION
+#define MAVLINK_VERSION 1
+#endif
+
+#if (MAVLINK_VERSION == 0)
+#undef MAVLINK_VERSION
+#define MAVLINK_VERSION 1
+#endif
+
+// MESSAGE DEFINITIONS
+#include "./mavlink_msg_storm32_gimbal_manager_information.h"
+#include "./mavlink_msg_storm32_gimbal_manager_status.h"
+#include "./mavlink_msg_storm32_gimbal_manager_control.h"
+#include "./mavlink_msg_storm32_gimbal_manager_control_pitchyaw.h"
+#include "./mavlink_msg_storm32_gimbal_manager_correct_roll.h"
+#include "./mavlink_msg_qshot_status.h"
+#include "./mavlink_msg_autopilot_state_for_gimbal_device_ext.h"
+#include "./mavlink_msg_frsky_passthrough_array.h"
+#include "./mavlink_msg_param_value_array.h"
+#include "./mavlink_msg_mlrs_radio_link_stats.h"
+#include "./mavlink_msg_mlrs_radio_link_information.h"
+#include "./mavlink_msg_mlrs_radio_link_flow_control.h"
+
+// base include
+#include "../ardupilotmega/ardupilotmega.h"
+
+
+#if MAVLINK_STORM32_XML_HASH == MAVLINK_PRIMARY_XML_HASH
+# define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_SYS_STATUS, MAVLINK_MESSAGE_INFO_SYSTEM_TIME, MAVLINK_MESSAGE_INFO_PING, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK, MAVLINK_MESSAGE_INFO_AUTH_KEY, MAVLINK_MESSAGE_INFO_LINK_NODE_STATUS, MAVLINK_MESSAGE_INFO_SET_MODE, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_VALUE, MAVLINK_MESSAGE_INFO_PARAM_SET, MAVLINK_MESSAGE_INFO_GPS_RAW_INT, MAVLINK_MESSAGE_INFO_GPS_STATUS, MAVLINK_MESSAGE_INFO_SCALED_IMU, MAVLINK_MESSAGE_INFO_RAW_IMU, MAVLINK_MESSAGE_INFO_RAW_PRESSURE, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE, MAVLINK_MESSAGE_INFO_ATTITUDE, MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT, MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED, MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW, MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_WRITE_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_ITEM, MAVLINK_MESSAGE_INFO_MISSION_REQUEST, MAVLINK_MESSAGE_INFO_MISSION_SET_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_LIST, MAVLINK_MESSAGE_INFO_MISSION_COUNT, MAVLINK_MESSAGE_INFO_MISSION_CLEAR_ALL, MAVLINK_MESSAGE_INFO_MISSION_ITEM_REACHED, MAVLINK_MESSAGE_INFO_MISSION_ACK, MAVLINK_MESSAGE_INFO_SET_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_PARAM_MAP_RC, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_INT, MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION_COV, MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT_COV, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_COV, MAVLINK_MESSAGE_INFO_RC_CHANNELS, MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM, MAVLINK_MESSAGE_INFO_DATA_STREAM, MAVLINK_MESSAGE_INFO_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE, MAVLINK_MESSAGE_INFO_MISSION_ITEM_INT, MAVLINK_MESSAGE_INFO_VFR_HUD, MAVLINK_MESSAGE_INFO_COMMAND_INT, MAVLINK_MESSAGE_INFO_COMMAND_LONG, MAVLINK_MESSAGE_INFO_COMMAND_ACK, MAVLINK_MESSAGE_INFO_COMMAND_CANCEL, MAVLINK_MESSAGE_INFO_MANUAL_SETPOINT, MAVLINK_MESSAGE_INFO_SET_ATTITUDE_TARGET, MAVLINK_MESSAGE_INFO_ATTITUDE_TARGET, MAVLINK_MESSAGE_INFO_SET_POSITION_TARGET_LOCAL_NED, MAVLINK_MESSAGE_INFO_POSITION_TARGET_LOCAL_NED, MAVLINK_MESSAGE_INFO_SET_POSITION_TARGET_GLOBAL_INT, MAVLINK_MESSAGE_INFO_POSITION_TARGET_GLOBAL_INT, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, MAVLINK_MESSAGE_INFO_HIL_STATE, MAVLINK_MESSAGE_INFO_HIL_CONTROLS, MAVLINK_MESSAGE_INFO_HIL_RC_INPUTS_RAW, MAVLINK_MESSAGE_INFO_HIL_ACTUATOR_CONTROLS, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_GLOBAL_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE, MAVLINK_MESSAGE_INFO_VICON_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_HIGHRES_IMU, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW_RAD, MAVLINK_MESSAGE_INFO_HIL_SENSOR, MAVLINK_MESSAGE_INFO_SIM_STATE, MAVLINK_MESSAGE_INFO_RADIO_STATUS, MAVLINK_MESSAGE_INFO_FILE_TRANSFER_PROTOCOL, MAVLINK_MESSAGE_INFO_TIMESYNC, MAVLINK_MESSAGE_INFO_CAMERA_TRIGGER, MAVLINK_MESSAGE_INFO_HIL_GPS, MAVLINK_MESSAGE_INFO_HIL_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_HIL_STATE_QUATERNION, MAVLINK_MESSAGE_INFO_SCALED_IMU2, MAVLINK_MESSAGE_INFO_LOG_REQUEST_LIST, MAVLINK_MESSAGE_INFO_LOG_ENTRY, MAVLINK_MESSAGE_INFO_LOG_REQUEST_DATA, MAVLINK_MESSAGE_INFO_LOG_DATA, MAVLINK_MESSAGE_INFO_LOG_ERASE, MAVLINK_MESSAGE_INFO_LOG_REQUEST_END, MAVLINK_MESSAGE_INFO_GPS_INJECT_DATA, MAVLINK_MESSAGE_INFO_GPS2_RAW, MAVLINK_MESSAGE_INFO_POWER_STATUS, MAVLINK_MESSAGE_INFO_SERIAL_CONTROL, MAVLINK_MESSAGE_INFO_GPS_RTK, MAVLINK_MESSAGE_INFO_GPS2_RTK, MAVLINK_MESSAGE_INFO_SCALED_IMU3, MAVLINK_MESSAGE_INFO_DATA_TRANSMISSION_HANDSHAKE, MAVLINK_MESSAGE_INFO_ENCAPSULATED_DATA, MAVLINK_MESSAGE_INFO_DISTANCE_SENSOR, MAVLINK_MESSAGE_INFO_TERRAIN_REQUEST, MAVLINK_MESSAGE_INFO_TERRAIN_DATA, MAVLINK_MESSAGE_INFO_TERRAIN_CHECK, MAVLINK_MESSAGE_INFO_TERRAIN_REPORT, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE2, MAVLINK_MESSAGE_INFO_ATT_POS_MOCAP, MAVLINK_MESSAGE_INFO_SET_ACTUATOR_CONTROL_TARGET, MAVLINK_MESSAGE_INFO_ACTUATOR_CONTROL_TARGET, MAVLINK_MESSAGE_INFO_ALTITUDE, MAVLINK_MESSAGE_INFO_RESOURCE_REQUEST, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE3, MAVLINK_MESSAGE_INFO_FOLLOW_TARGET, MAVLINK_MESSAGE_INFO_CONTROL_SYSTEM_STATE, MAVLINK_MESSAGE_INFO_BATTERY_STATUS, MAVLINK_MESSAGE_INFO_AUTOPILOT_VERSION, MAVLINK_MESSAGE_INFO_LANDING_TARGET, MAVLINK_MESSAGE_INFO_SENSOR_OFFSETS, MAVLINK_MESSAGE_INFO_SET_MAG_OFFSETS, MAVLINK_MESSAGE_INFO_MEMINFO, MAVLINK_MESSAGE_INFO_AP_ADC, MAVLINK_MESSAGE_INFO_DIGICAM_CONFIGURE, MAVLINK_MESSAGE_INFO_DIGICAM_CONTROL, MAVLINK_MESSAGE_INFO_MOUNT_CONFIGURE, MAVLINK_MESSAGE_INFO_MOUNT_CONTROL, MAVLINK_MESSAGE_INFO_MOUNT_STATUS, MAVLINK_MESSAGE_INFO_FENCE_POINT, MAVLINK_MESSAGE_INFO_FENCE_FETCH_POINT, MAVLINK_MESSAGE_INFO_FENCE_STATUS, MAVLINK_MESSAGE_INFO_AHRS, MAVLINK_MESSAGE_INFO_SIMSTATE, MAVLINK_MESSAGE_INFO_HWSTATUS, MAVLINK_MESSAGE_INFO_RADIO, MAVLINK_MESSAGE_INFO_LIMITS_STATUS, MAVLINK_MESSAGE_INFO_WIND, MAVLINK_MESSAGE_INFO_DATA16, MAVLINK_MESSAGE_INFO_DATA32, MAVLINK_MESSAGE_INFO_DATA64, MAVLINK_MESSAGE_INFO_DATA96, MAVLINK_MESSAGE_INFO_RANGEFINDER, MAVLINK_MESSAGE_INFO_AIRSPEED_AUTOCAL, MAVLINK_MESSAGE_INFO_RALLY_POINT, MAVLINK_MESSAGE_INFO_RALLY_FETCH_POINT, MAVLINK_MESSAGE_INFO_COMPASSMOT_STATUS, MAVLINK_MESSAGE_INFO_AHRS2, MAVLINK_MESSAGE_INFO_CAMERA_STATUS, MAVLINK_MESSAGE_INFO_CAMERA_FEEDBACK, MAVLINK_MESSAGE_INFO_BATTERY2, MAVLINK_MESSAGE_INFO_AHRS3, MAVLINK_MESSAGE_INFO_AUTOPILOT_VERSION_REQUEST, MAVLINK_MESSAGE_INFO_REMOTE_LOG_DATA_BLOCK, MAVLINK_MESSAGE_INFO_REMOTE_LOG_BLOCK_STATUS, MAVLINK_MESSAGE_INFO_LED_CONTROL, MAVLINK_MESSAGE_INFO_MAG_CAL_PROGRESS, MAVLINK_MESSAGE_INFO_MAG_CAL_REPORT, MAVLINK_MESSAGE_INFO_EKF_STATUS_REPORT, MAVLINK_MESSAGE_INFO_PID_TUNING, MAVLINK_MESSAGE_INFO_DEEPSTALL, MAVLINK_MESSAGE_INFO_GIMBAL_REPORT, MAVLINK_MESSAGE_INFO_GIMBAL_CONTROL, MAVLINK_MESSAGE_INFO_GIMBAL_TORQUE_CMD_REPORT, MAVLINK_MESSAGE_INFO_GOPRO_HEARTBEAT, MAVLINK_MESSAGE_INFO_GOPRO_GET_REQUEST, MAVLINK_MESSAGE_INFO_GOPRO_GET_RESPONSE, MAVLINK_MESSAGE_INFO_GOPRO_SET_REQUEST, MAVLINK_MESSAGE_INFO_GOPRO_SET_RESPONSE, MAVLINK_MESSAGE_INFO_EFI_STATUS, MAVLINK_MESSAGE_INFO_RPM, MAVLINK_MESSAGE_INFO_ESTIMATOR_STATUS, MAVLINK_MESSAGE_INFO_WIND_COV, MAVLINK_MESSAGE_INFO_GPS_INPUT, MAVLINK_MESSAGE_INFO_GPS_RTCM_DATA, MAVLINK_MESSAGE_INFO_HIGH_LATENCY, MAVLINK_MESSAGE_INFO_HIGH_LATENCY2, MAVLINK_MESSAGE_INFO_VIBRATION, MAVLINK_MESSAGE_INFO_HOME_POSITION, MAVLINK_MESSAGE_INFO_SET_HOME_POSITION, MAVLINK_MESSAGE_INFO_MESSAGE_INTERVAL, MAVLINK_MESSAGE_INFO_EXTENDED_SYS_STATE, MAVLINK_MESSAGE_INFO_ADSB_VEHICLE, MAVLINK_MESSAGE_INFO_COLLISION, MAVLINK_MESSAGE_INFO_V2_EXTENSION, MAVLINK_MESSAGE_INFO_MEMORY_VECT, MAVLINK_MESSAGE_INFO_DEBUG_VECT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT, MAVLINK_MESSAGE_INFO_STATUSTEXT, MAVLINK_MESSAGE_INFO_DEBUG, MAVLINK_MESSAGE_INFO_SETUP_SIGNING, MAVLINK_MESSAGE_INFO_BUTTON_CHANGE, MAVLINK_MESSAGE_INFO_PLAY_TUNE, MAVLINK_MESSAGE_INFO_CAMERA_INFORMATION, MAVLINK_MESSAGE_INFO_CAMERA_SETTINGS, MAVLINK_MESSAGE_INFO_STORAGE_INFORMATION, MAVLINK_MESSAGE_INFO_CAMERA_CAPTURE_STATUS, MAVLINK_MESSAGE_INFO_CAMERA_IMAGE_CAPTURED, MAVLINK_MESSAGE_INFO_FLIGHT_INFORMATION, MAVLINK_MESSAGE_INFO_MOUNT_ORIENTATION, MAVLINK_MESSAGE_INFO_LOGGING_DATA, MAVLINK_MESSAGE_INFO_LOGGING_DATA_ACKED, MAVLINK_MESSAGE_INFO_LOGGING_ACK, MAVLINK_MESSAGE_INFO_VIDEO_STREAM_INFORMATION, MAVLINK_MESSAGE_INFO_VIDEO_STREAM_STATUS, MAVLINK_MESSAGE_INFO_CAMERA_FOV_STATUS, MAVLINK_MESSAGE_INFO_CAMERA_TRACKING_IMAGE_STATUS, MAVLINK_MESSAGE_INFO_CAMERA_TRACKING_GEO_STATUS, MAVLINK_MESSAGE_INFO_CAMERA_THERMAL_RANGE, MAVLINK_MESSAGE_INFO_GIMBAL_MANAGER_INFORMATION, MAVLINK_MESSAGE_INFO_GIMBAL_MANAGER_STATUS, MAVLINK_MESSAGE_INFO_GIMBAL_MANAGER_SET_ATTITUDE, MAVLINK_MESSAGE_INFO_GIMBAL_DEVICE_INFORMATION, MAVLINK_MESSAGE_INFO_GIMBAL_DEVICE_SET_ATTITUDE, MAVLINK_MESSAGE_INFO_GIMBAL_DEVICE_ATTITUDE_STATUS, MAVLINK_MESSAGE_INFO_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE, MAVLINK_MESSAGE_INFO_GIMBAL_MANAGER_SET_PITCHYAW, MAVLINK_MESSAGE_INFO_GIMBAL_MANAGER_SET_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_ESC_INFO, MAVLINK_MESSAGE_INFO_ESC_STATUS, MAVLINK_MESSAGE_INFO_AIRSPEED, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_SENSOR, MAVLINK_MESSAGE_INFO_WIFI_CONFIG_AP, MAVLINK_MESSAGE_INFO_PROTOCOL_VERSION, MAVLINK_MESSAGE_INFO_AIS_VESSEL, MAVLINK_MESSAGE_INFO_UAVCAN_NODE_STATUS, MAVLINK_MESSAGE_INFO_UAVCAN_NODE_INFO, MAVLINK_MESSAGE_INFO_PARAM_EXT_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_EXT_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_EXT_VALUE, MAVLINK_MESSAGE_INFO_PARAM_EXT_SET, MAVLINK_MESSAGE_INFO_PARAM_EXT_ACK, MAVLINK_MESSAGE_INFO_OBSTACLE_DISTANCE, MAVLINK_MESSAGE_INFO_ODOMETRY, MAVLINK_MESSAGE_INFO_TRAJECTORY_REPRESENTATION_WAYPOINTS, MAVLINK_MESSAGE_INFO_TRAJECTORY_REPRESENTATION_BEZIER, MAVLINK_MESSAGE_INFO_CELLULAR_STATUS, MAVLINK_MESSAGE_INFO_ISBD_LINK_STATUS, MAVLINK_MESSAGE_INFO_CELLULAR_CONFIG, MAVLINK_MESSAGE_INFO_RAW_RPM, MAVLINK_MESSAGE_INFO_UTM_GLOBAL_POSITION, MAVLINK_MESSAGE_INFO_PARAM_ERROR, MAVLINK_MESSAGE_INFO_DEBUG_FLOAT_ARRAY, MAVLINK_MESSAGE_INFO_ORBIT_EXECUTION_STATUS, MAVLINK_MESSAGE_INFO_FIGURE_EIGHT_EXECUTION_STATUS, MAVLINK_MESSAGE_INFO_SMART_BATTERY_INFO, MAVLINK_MESSAGE_INFO_FUEL_STATUS, MAVLINK_MESSAGE_INFO_BATTERY_INFO, MAVLINK_MESSAGE_INFO_GENERATOR_STATUS, MAVLINK_MESSAGE_INFO_ACTUATOR_OUTPUT_STATUS, MAVLINK_MESSAGE_INFO_RELAY_STATUS, MAVLINK_MESSAGE_INFO_TIME_ESTIMATE_TO_TARGET, MAVLINK_MESSAGE_INFO_TUNNEL, MAVLINK_MESSAGE_INFO_CAN_FRAME, MAVLINK_MESSAGE_INFO_CANFD_FRAME, MAVLINK_MESSAGE_INFO_CAN_FILTER_MODIFY, MAVLINK_MESSAGE_INFO_ONBOARD_COMPUTER_STATUS, MAVLINK_MESSAGE_INFO_COMPONENT_INFORMATION, MAVLINK_MESSAGE_INFO_COMPONENT_INFORMATION_BASIC, MAVLINK_MESSAGE_INFO_COMPONENT_METADATA, MAVLINK_MESSAGE_INFO_PLAY_TUNE_V2, MAVLINK_MESSAGE_INFO_SUPPORTED_TUNES, MAVLINK_MESSAGE_INFO_EVENT, MAVLINK_MESSAGE_INFO_CURRENT_EVENT_SEQUENCE, MAVLINK_MESSAGE_INFO_REQUEST_EVENT, MAVLINK_MESSAGE_INFO_RESPONSE_EVENT_ERROR, MAVLINK_MESSAGE_INFO_AVAILABLE_MODES, MAVLINK_MESSAGE_INFO_CURRENT_MODE, MAVLINK_MESSAGE_INFO_AVAILABLE_MODES_MONITOR, MAVLINK_MESSAGE_INFO_ILLUMINATOR_STATUS, MAVLINK_MESSAGE_INFO_WHEEL_DISTANCE, MAVLINK_MESSAGE_INFO_WINCH_STATUS, MAVLINK_MESSAGE_INFO_UAVIONIX_ADSB_OUT_CFG, MAVLINK_MESSAGE_INFO_UAVIONIX_ADSB_OUT_DYNAMIC, MAVLINK_MESSAGE_INFO_UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT, MAVLINK_MESSAGE_INFO_UAVIONIX_ADSB_OUT_CFG_REGISTRATION, MAVLINK_MESSAGE_INFO_UAVIONIX_ADSB_OUT_CFG_FLIGHTID, MAVLINK_MESSAGE_INFO_UAVIONIX_ADSB_GET, MAVLINK_MESSAGE_INFO_UAVIONIX_ADSB_OUT_CONTROL, MAVLINK_MESSAGE_INFO_UAVIONIX_ADSB_OUT_STATUS, MAVLINK_MESSAGE_INFO_LOWEHEISER_GOV_EFI, MAVLINK_MESSAGE_INFO_DEVICE_OP_READ, MAVLINK_MESSAGE_INFO_DEVICE_OP_READ_REPLY, MAVLINK_MESSAGE_INFO_DEVICE_OP_WRITE, MAVLINK_MESSAGE_INFO_DEVICE_OP_WRITE_REPLY, MAVLINK_MESSAGE_INFO_SECURE_COMMAND, MAVLINK_MESSAGE_INFO_SECURE_COMMAND_REPLY, MAVLINK_MESSAGE_INFO_ADAP_TUNING, MAVLINK_MESSAGE_INFO_VISION_POSITION_DELTA, MAVLINK_MESSAGE_INFO_AOA_SSA, MAVLINK_MESSAGE_INFO_ESC_TELEMETRY_1_TO_4, MAVLINK_MESSAGE_INFO_ESC_TELEMETRY_5_TO_8, MAVLINK_MESSAGE_INFO_ESC_TELEMETRY_9_TO_12, MAVLINK_MESSAGE_INFO_OSD_PARAM_CONFIG, MAVLINK_MESSAGE_INFO_OSD_PARAM_CONFIG_REPLY, MAVLINK_MESSAGE_INFO_OSD_PARAM_SHOW_CONFIG, MAVLINK_MESSAGE_INFO_OSD_PARAM_SHOW_CONFIG_REPLY, MAVLINK_MESSAGE_INFO_OBSTACLE_DISTANCE_3D, MAVLINK_MESSAGE_INFO_WATER_DEPTH, MAVLINK_MESSAGE_INFO_MCU_STATUS, MAVLINK_MESSAGE_INFO_ESC_TELEMETRY_13_TO_16, MAVLINK_MESSAGE_INFO_ESC_TELEMETRY_17_TO_20, MAVLINK_MESSAGE_INFO_ESC_TELEMETRY_21_TO_24, MAVLINK_MESSAGE_INFO_ESC_TELEMETRY_25_TO_28, MAVLINK_MESSAGE_INFO_ESC_TELEMETRY_29_TO_32, MAVLINK_MESSAGE_INFO_NAMED_VALUE_STRING, MAVLINK_MESSAGE_INFO_OPEN_DRONE_ID_BASIC_ID, MAVLINK_MESSAGE_INFO_OPEN_DRONE_ID_LOCATION, MAVLINK_MESSAGE_INFO_OPEN_DRONE_ID_AUTHENTICATION, MAVLINK_MESSAGE_INFO_OPEN_DRONE_ID_SELF_ID, MAVLINK_MESSAGE_INFO_OPEN_DRONE_ID_SYSTEM, MAVLINK_MESSAGE_INFO_OPEN_DRONE_ID_OPERATOR_ID, MAVLINK_MESSAGE_INFO_OPEN_DRONE_ID_MESSAGE_PACK, MAVLINK_MESSAGE_INFO_OPEN_DRONE_ID_ARM_STATUS, MAVLINK_MESSAGE_INFO_OPEN_DRONE_ID_SYSTEM_UPDATE, MAVLINK_MESSAGE_INFO_HYGROMETER_SENSOR, MAVLINK_MESSAGE_INFO_ICAROUS_HEARTBEAT, MAVLINK_MESSAGE_INFO_ICAROUS_KINEMATIC_BANDS, MAVLINK_MESSAGE_INFO_CUBEPILOT_RAW_RC, MAVLINK_MESSAGE_INFO_HERELINK_VIDEO_STREAM_INFORMATION, MAVLINK_MESSAGE_INFO_HERELINK_TELEM, MAVLINK_MESSAGE_INFO_CUBEPILOT_FIRMWARE_UPDATE_START, MAVLINK_MESSAGE_INFO_CUBEPILOT_FIRMWARE_UPDATE_RESP, MAVLINK_MESSAGE_INFO_AIRLINK_AUTH, MAVLINK_MESSAGE_INFO_AIRLINK_AUTH_RESPONSE, MAVLINK_MESSAGE_INFO_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_EXT, MAVLINK_MESSAGE_INFO_STORM32_GIMBAL_MANAGER_INFORMATION, MAVLINK_MESSAGE_INFO_STORM32_GIMBAL_MANAGER_STATUS, MAVLINK_MESSAGE_INFO_STORM32_GIMBAL_MANAGER_CONTROL, MAVLINK_MESSAGE_INFO_STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW, MAVLINK_MESSAGE_INFO_STORM32_GIMBAL_MANAGER_CORRECT_ROLL, MAVLINK_MESSAGE_INFO_QSHOT_STATUS, MAVLINK_MESSAGE_INFO_FRSKY_PASSTHROUGH_ARRAY, MAVLINK_MESSAGE_INFO_PARAM_VALUE_ARRAY, MAVLINK_MESSAGE_INFO_MLRS_RADIO_LINK_STATS, MAVLINK_MESSAGE_INFO_MLRS_RADIO_LINK_INFORMATION, MAVLINK_MESSAGE_INFO_MLRS_RADIO_LINK_FLOW_CONTROL}
+# define MAVLINK_MESSAGE_NAMES {{ "ACTUATOR_CONTROL_TARGET", 140 }, { "ACTUATOR_OUTPUT_STATUS", 375 }, { "ADAP_TUNING", 11010 }, { "ADSB_VEHICLE", 246 }, { "AHRS", 163 }, { "AHRS2", 178 }, { "AHRS3", 182 }, { "AIRLINK_AUTH", 52000 }, { "AIRLINK_AUTH_RESPONSE", 52001 }, { "AIRSPEED", 295 }, { "AIRSPEED_AUTOCAL", 174 }, { "AIS_VESSEL", 301 }, { "ALTITUDE", 141 }, { "AOA_SSA", 11020 }, { "AP_ADC", 153 }, { "ATTITUDE", 30 }, { "ATTITUDE_QUATERNION", 31 }, { "ATTITUDE_QUATERNION_COV", 61 }, { "ATTITUDE_TARGET", 83 }, { "ATT_POS_MOCAP", 138 }, { "AUTH_KEY", 7 }, { "AUTOPILOT_STATE_FOR_GIMBAL_DEVICE", 286 }, { "AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_EXT", 60000 }, { "AUTOPILOT_VERSION", 148 }, { "AUTOPILOT_VERSION_REQUEST", 183 }, { "AVAILABLE_MODES", 435 }, { "AVAILABLE_MODES_MONITOR", 437 }, { "BATTERY2", 181 }, { "BATTERY_INFO", 372 }, { "BATTERY_STATUS", 147 }, { "BUTTON_CHANGE", 257 }, { "CAMERA_CAPTURE_STATUS", 262 }, { "CAMERA_FEEDBACK", 180 }, { "CAMERA_FOV_STATUS", 271 }, { "CAMERA_IMAGE_CAPTURED", 263 }, { "CAMERA_INFORMATION", 259 }, { "CAMERA_SETTINGS", 260 }, { "CAMERA_STATUS", 179 }, { "CAMERA_THERMAL_RANGE", 277 }, { "CAMERA_TRACKING_GEO_STATUS", 276 }, { "CAMERA_TRACKING_IMAGE_STATUS", 275 }, { "CAMERA_TRIGGER", 112 }, { "CANFD_FRAME", 387 }, { "CAN_FILTER_MODIFY", 388 }, { "CAN_FRAME", 386 }, { "CELLULAR_CONFIG", 336 }, { "CELLULAR_STATUS", 334 }, { "CHANGE_OPERATOR_CONTROL", 5 }, { "CHANGE_OPERATOR_CONTROL_ACK", 6 }, { "COLLISION", 247 }, { "COMMAND_ACK", 77 }, { "COMMAND_CANCEL", 80 }, { "COMMAND_INT", 75 }, { "COMMAND_LONG", 76 }, { "COMPASSMOT_STATUS", 177 }, { "COMPONENT_INFORMATION", 395 }, { "COMPONENT_INFORMATION_BASIC", 396 }, { "COMPONENT_METADATA", 397 }, { "CONTROL_SYSTEM_STATE", 146 }, { "CUBEPILOT_FIRMWARE_UPDATE_RESP", 50005 }, { "CUBEPILOT_FIRMWARE_UPDATE_START", 50004 }, { "CUBEPILOT_RAW_RC", 50001 }, { "CURRENT_EVENT_SEQUENCE", 411 }, { "CURRENT_MODE", 436 }, { "DATA16", 169 }, { "DATA32", 170 }, { "DATA64", 171 }, { "DATA96", 172 }, { "DATA_STREAM", 67 }, { "DATA_TRANSMISSION_HANDSHAKE", 130 }, { "DEBUG", 254 }, { "DEBUG_FLOAT_ARRAY", 350 }, { "DEBUG_VECT", 250 }, { "DEEPSTALL", 195 }, { "DEVICE_OP_READ", 11000 }, { "DEVICE_OP_READ_REPLY", 11001 }, { "DEVICE_OP_WRITE", 11002 }, { "DEVICE_OP_WRITE_REPLY", 11003 }, { "DIGICAM_CONFIGURE", 154 }, { "DIGICAM_CONTROL", 155 }, { "DISTANCE_SENSOR", 132 }, { "EFI_STATUS", 225 }, { "EKF_STATUS_REPORT", 193 }, { "ENCAPSULATED_DATA", 131 }, { "ESC_INFO", 290 }, { "ESC_STATUS", 291 }, { "ESC_TELEMETRY_13_TO_16", 11040 }, { "ESC_TELEMETRY_17_TO_20", 11041 }, { "ESC_TELEMETRY_1_TO_4", 11030 }, { "ESC_TELEMETRY_21_TO_24", 11042 }, { "ESC_TELEMETRY_25_TO_28", 11043 }, { "ESC_TELEMETRY_29_TO_32", 11044 }, { "ESC_TELEMETRY_5_TO_8", 11031 }, { "ESC_TELEMETRY_9_TO_12", 11032 }, { "ESTIMATOR_STATUS", 230 }, { "EVENT", 410 }, { "EXTENDED_SYS_STATE", 245 }, { "FENCE_FETCH_POINT", 161 }, { "FENCE_POINT", 160 }, { "FENCE_STATUS", 162 }, { "FIGURE_EIGHT_EXECUTION_STATUS", 361 }, { "FILE_TRANSFER_PROTOCOL", 110 }, { "FLIGHT_INFORMATION", 264 }, { "FOLLOW_TARGET", 144 }, { "FRSKY_PASSTHROUGH_ARRAY", 60040 }, { "FUEL_STATUS", 371 }, { "GENERATOR_STATUS", 373 }, { "GIMBAL_CONTROL", 201 }, { "GIMBAL_DEVICE_ATTITUDE_STATUS", 285 }, { "GIMBAL_DEVICE_INFORMATION", 283 }, { "GIMBAL_DEVICE_SET_ATTITUDE", 284 }, { "GIMBAL_MANAGER_INFORMATION", 280 }, { "GIMBAL_MANAGER_SET_ATTITUDE", 282 }, { "GIMBAL_MANAGER_SET_MANUAL_CONTROL", 288 }, { "GIMBAL_MANAGER_SET_PITCHYAW", 287 }, { "GIMBAL_MANAGER_STATUS", 281 }, { "GIMBAL_REPORT", 200 }, { "GIMBAL_TORQUE_CMD_REPORT", 214 }, { "GLOBAL_POSITION_INT", 33 }, { "GLOBAL_POSITION_INT_COV", 63 }, { "GLOBAL_POSITION_SENSOR", 296 }, { "GLOBAL_VISION_POSITION_ESTIMATE", 101 }, { "GOPRO_GET_REQUEST", 216 }, { "GOPRO_GET_RESPONSE", 217 }, { "GOPRO_HEARTBEAT", 215 }, { "GOPRO_SET_REQUEST", 218 }, { "GOPRO_SET_RESPONSE", 219 }, { "GPS2_RAW", 124 }, { "GPS2_RTK", 128 }, { "GPS_GLOBAL_ORIGIN", 49 }, { "GPS_INJECT_DATA", 123 }, { "GPS_INPUT", 232 }, { "GPS_RAW_INT", 24 }, { "GPS_RTCM_DATA", 233 }, { "GPS_RTK", 127 }, { "GPS_STATUS", 25 }, { "HEARTBEAT", 0 }, { "HERELINK_TELEM", 50003 }, { "HERELINK_VIDEO_STREAM_INFORMATION", 50002 }, { "HIGHRES_IMU", 105 }, { "HIGH_LATENCY", 234 }, { "HIGH_LATENCY2", 235 }, { "HIL_ACTUATOR_CONTROLS", 93 }, { "HIL_CONTROLS", 91 }, { "HIL_GPS", 113 }, { "HIL_OPTICAL_FLOW", 114 }, { "HIL_RC_INPUTS_RAW", 92 }, { "HIL_SENSOR", 107 }, { "HIL_STATE", 90 }, { "HIL_STATE_QUATERNION", 115 }, { "HOME_POSITION", 242 }, { "HWSTATUS", 165 }, { "HYGROMETER_SENSOR", 12920 }, { "ICAROUS_HEARTBEAT", 42000 }, { "ICAROUS_KINEMATIC_BANDS", 42001 }, { "ILLUMINATOR_STATUS", 440 }, { "ISBD_LINK_STATUS", 335 }, { "LANDING_TARGET", 149 }, { "LED_CONTROL", 186 }, { "LIMITS_STATUS", 167 }, { "LINK_NODE_STATUS", 8 }, { "LOCAL_POSITION_NED", 32 }, { "LOCAL_POSITION_NED_COV", 64 }, { "LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET", 89 }, { "LOGGING_ACK", 268 }, { "LOGGING_DATA", 266 }, { "LOGGING_DATA_ACKED", 267 }, { "LOG_DATA", 120 }, { "LOG_ENTRY", 118 }, { "LOG_ERASE", 121 }, { "LOG_REQUEST_DATA", 119 }, { "LOG_REQUEST_END", 122 }, { "LOG_REQUEST_LIST", 117 }, { "LOWEHEISER_GOV_EFI", 10151 }, { "MAG_CAL_PROGRESS", 191 }, { "MAG_CAL_REPORT", 192 }, { "MANUAL_CONTROL", 69 }, { "MANUAL_SETPOINT", 81 }, { "MCU_STATUS", 11039 }, { "MEMINFO", 152 }, { "MEMORY_VECT", 249 }, { "MESSAGE_INTERVAL", 244 }, { "MISSION_ACK", 47 }, { "MISSION_CLEAR_ALL", 45 }, { "MISSION_COUNT", 44 }, { "MISSION_CURRENT", 42 }, { "MISSION_ITEM", 39 }, { "MISSION_ITEM_INT", 73 }, { "MISSION_ITEM_REACHED", 46 }, { "MISSION_REQUEST", 40 }, { "MISSION_REQUEST_INT", 51 }, { "MISSION_REQUEST_LIST", 43 }, { "MISSION_REQUEST_PARTIAL_LIST", 37 }, { "MISSION_SET_CURRENT", 41 }, { "MISSION_WRITE_PARTIAL_LIST", 38 }, { "MLRS_RADIO_LINK_FLOW_CONTROL", 60047 }, { "MLRS_RADIO_LINK_INFORMATION", 60046 }, { "MLRS_RADIO_LINK_STATS", 60045 }, { "MOUNT_CONFIGURE", 156 }, { "MOUNT_CONTROL", 157 }, { "MOUNT_ORIENTATION", 265 }, { "MOUNT_STATUS", 158 }, { "NAMED_VALUE_FLOAT", 251 }, { "NAMED_VALUE_INT", 252 }, { "NAMED_VALUE_STRING", 11060 }, { "NAV_CONTROLLER_OUTPUT", 62 }, { "OBSTACLE_DISTANCE", 330 }, { "OBSTACLE_DISTANCE_3D", 11037 }, { "ODOMETRY", 331 }, { "ONBOARD_COMPUTER_STATUS", 390 }, { "OPEN_DRONE_ID_ARM_STATUS", 12918 }, { "OPEN_DRONE_ID_AUTHENTICATION", 12902 }, { "OPEN_DRONE_ID_BASIC_ID", 12900 }, { "OPEN_DRONE_ID_LOCATION", 12901 }, { "OPEN_DRONE_ID_MESSAGE_PACK", 12915 }, { "OPEN_DRONE_ID_OPERATOR_ID", 12905 }, { "OPEN_DRONE_ID_SELF_ID", 12903 }, { "OPEN_DRONE_ID_SYSTEM", 12904 }, { "OPEN_DRONE_ID_SYSTEM_UPDATE", 12919 }, { "OPTICAL_FLOW", 100 }, { "OPTICAL_FLOW_RAD", 106 }, { "ORBIT_EXECUTION_STATUS", 360 }, { "OSD_PARAM_CONFIG", 11033 }, { "OSD_PARAM_CONFIG_REPLY", 11034 }, { "OSD_PARAM_SHOW_CONFIG", 11035 }, { "OSD_PARAM_SHOW_CONFIG_REPLY", 11036 }, { "PARAM_ERROR", 345 }, { "PARAM_EXT_ACK", 324 }, { "PARAM_EXT_REQUEST_LIST", 321 }, { "PARAM_EXT_REQUEST_READ", 320 }, { "PARAM_EXT_SET", 323 }, { "PARAM_EXT_VALUE", 322 }, { "PARAM_MAP_RC", 50 }, { "PARAM_REQUEST_LIST", 21 }, { "PARAM_REQUEST_READ", 20 }, { "PARAM_SET", 23 }, { "PARAM_VALUE", 22 }, { "PARAM_VALUE_ARRAY", 60041 }, { "PID_TUNING", 194 }, { "PING", 4 }, { "PLAY_TUNE", 258 }, { "PLAY_TUNE_V2", 400 }, { "POSITION_TARGET_GLOBAL_INT", 87 }, { "POSITION_TARGET_LOCAL_NED", 85 }, { "POWER_STATUS", 125 }, { "PROTOCOL_VERSION", 300 }, { "QSHOT_STATUS", 60020 }, { "RADIO", 166 }, { "RADIO_STATUS", 109 }, { "RALLY_FETCH_POINT", 176 }, { "RALLY_POINT", 175 }, { "RANGEFINDER", 173 }, { "RAW_IMU", 27 }, { "RAW_PRESSURE", 28 }, { "RAW_RPM", 339 }, { "RC_CHANNELS", 65 }, { "RC_CHANNELS_OVERRIDE", 70 }, { "RC_CHANNELS_RAW", 35 }, { "RC_CHANNELS_SCALED", 34 }, { "RELAY_STATUS", 376 }, { "REMOTE_LOG_BLOCK_STATUS", 185 }, { "REMOTE_LOG_DATA_BLOCK", 184 }, { "REQUEST_DATA_STREAM", 66 }, { "REQUEST_EVENT", 412 }, { "RESOURCE_REQUEST", 142 }, { "RESPONSE_EVENT_ERROR", 413 }, { "RPM", 226 }, { "SAFETY_ALLOWED_AREA", 55 }, { "SAFETY_SET_ALLOWED_AREA", 54 }, { "SCALED_IMU", 26 }, { "SCALED_IMU2", 116 }, { "SCALED_IMU3", 129 }, { "SCALED_PRESSURE", 29 }, { "SCALED_PRESSURE2", 137 }, { "SCALED_PRESSURE3", 143 }, { "SECURE_COMMAND", 11004 }, { "SECURE_COMMAND_REPLY", 11005 }, { "SENSOR_OFFSETS", 150 }, { "SERIAL_CONTROL", 126 }, { "SERVO_OUTPUT_RAW", 36 }, { "SETUP_SIGNING", 256 }, { "SET_ACTUATOR_CONTROL_TARGET", 139 }, { "SET_ATTITUDE_TARGET", 82 }, { "SET_GPS_GLOBAL_ORIGIN", 48 }, { "SET_HOME_POSITION", 243 }, { "SET_MAG_OFFSETS", 151 }, { "SET_MODE", 11 }, { "SET_POSITION_TARGET_GLOBAL_INT", 86 }, { "SET_POSITION_TARGET_LOCAL_NED", 84 }, { "SIMSTATE", 164 }, { "SIM_STATE", 108 }, { "SMART_BATTERY_INFO", 370 }, { "STATUSTEXT", 253 }, { "STORAGE_INFORMATION", 261 }, { "STORM32_GIMBAL_MANAGER_CONTROL", 60012 }, { "STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW", 60013 }, { "STORM32_GIMBAL_MANAGER_CORRECT_ROLL", 60014 }, { "STORM32_GIMBAL_MANAGER_INFORMATION", 60010 }, { "STORM32_GIMBAL_MANAGER_STATUS", 60011 }, { "SUPPORTED_TUNES", 401 }, { "SYSTEM_TIME", 2 }, { "SYS_STATUS", 1 }, { "TERRAIN_CHECK", 135 }, { "TERRAIN_DATA", 134 }, { "TERRAIN_REPORT", 136 }, { "TERRAIN_REQUEST", 133 }, { "TIMESYNC", 111 }, { "TIME_ESTIMATE_TO_TARGET", 380 }, { "TRAJECTORY_REPRESENTATION_BEZIER", 333 }, { "TRAJECTORY_REPRESENTATION_WAYPOINTS", 332 }, { "TUNNEL", 385 }, { "UAVCAN_NODE_INFO", 311 }, { "UAVCAN_NODE_STATUS", 310 }, { "UAVIONIX_ADSB_GET", 10006 }, { "UAVIONIX_ADSB_OUT_CFG", 10001 }, { "UAVIONIX_ADSB_OUT_CFG_FLIGHTID", 10005 }, { "UAVIONIX_ADSB_OUT_CFG_REGISTRATION", 10004 }, { "UAVIONIX_ADSB_OUT_CONTROL", 10007 }, { "UAVIONIX_ADSB_OUT_DYNAMIC", 10002 }, { "UAVIONIX_ADSB_OUT_STATUS", 10008 }, { "UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT", 10003 }, { "UTM_GLOBAL_POSITION", 340 }, { "V2_EXTENSION", 248 }, { "VFR_HUD", 74 }, { "VIBRATION", 241 }, { "VICON_POSITION_ESTIMATE", 104 }, { "VIDEO_STREAM_INFORMATION", 269 }, { "VIDEO_STREAM_STATUS", 270 }, { "VISION_POSITION_DELTA", 11011 }, { "VISION_POSITION_ESTIMATE", 102 }, { "VISION_SPEED_ESTIMATE", 103 }, { "WATER_DEPTH", 11038 }, { "WHEEL_DISTANCE", 9000 }, { "WIFI_CONFIG_AP", 299 }, { "WINCH_STATUS", 9005 }, { "WIND", 168 }, { "WIND_COV", 231 }}
+# if MAVLINK_COMMAND_24BIT
+# include "../mavlink_get_info.h"
+# endif
+#endif
+
+#ifdef __cplusplus
+}
+#endif // __cplusplus
+#endif // MAVLINK_STORM32_H
diff --git a/lib/main/MAVLink/storm32/testsuite.h b/lib/main/MAVLink/storm32/testsuite.h
new file mode 100644
index 00000000000..81889265ee7
--- /dev/null
+++ b/lib/main/MAVLink/storm32/testsuite.h
@@ -0,0 +1,833 @@
+/** @file
+ * @brief MAVLink comm protocol testsuite generated from storm32.xml
+ * @see https://mavlink.io/en/
+ */
+#pragma once
+#ifndef STORM32_TESTSUITE_H
+#define STORM32_TESTSUITE_H
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+#ifndef MAVLINK_TEST_ALL
+#define MAVLINK_TEST_ALL
+static void mavlink_test_ardupilotmega(uint8_t, uint8_t, mavlink_message_t *last_msg);
+static void mavlink_test_storm32(uint8_t, uint8_t, mavlink_message_t *last_msg);
+
+static void mavlink_test_all(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
+{
+ mavlink_test_ardupilotmega(system_id, component_id, last_msg);
+ mavlink_test_storm32(system_id, component_id, last_msg);
+}
+#endif
+
+#include "../ardupilotmega/testsuite.h"
+
+
+static void mavlink_test_storm32_gimbal_manager_information(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_STORM32_GIMBAL_MANAGER_INFORMATION >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_storm32_gimbal_manager_information_t packet_in = {
+ 963497464,963497672,73.0,101.0,129.0,157.0,185.0,213.0,101
+ };
+ mavlink_storm32_gimbal_manager_information_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.device_cap_flags = packet_in.device_cap_flags;
+ packet1.manager_cap_flags = packet_in.manager_cap_flags;
+ packet1.roll_min = packet_in.roll_min;
+ packet1.roll_max = packet_in.roll_max;
+ packet1.pitch_min = packet_in.pitch_min;
+ packet1.pitch_max = packet_in.pitch_max;
+ packet1.yaw_min = packet_in.yaw_min;
+ packet1.yaw_max = packet_in.yaw_max;
+ packet1.gimbal_id = packet_in.gimbal_id;
+
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_INFORMATION_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_INFORMATION_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_storm32_gimbal_manager_information_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_storm32_gimbal_manager_information_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_storm32_gimbal_manager_information_pack(system_id, component_id, &msg , packet1.gimbal_id , packet1.device_cap_flags , packet1.manager_cap_flags , packet1.roll_min , packet1.roll_max , packet1.pitch_min , packet1.pitch_max , packet1.yaw_min , packet1.yaw_max );
+ mavlink_msg_storm32_gimbal_manager_information_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_storm32_gimbal_manager_information_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.gimbal_id , packet1.device_cap_flags , packet1.manager_cap_flags , packet1.roll_min , packet1.roll_max , packet1.pitch_min , packet1.pitch_max , packet1.yaw_min , packet1.yaw_max );
+ mavlink_msg_storm32_gimbal_manager_information_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_STATUS >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_storm32_gimbal_manager_status_t packet_in = {
+ 17235,17339,17,84,151
+ };
+ mavlink_storm32_gimbal_manager_status_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.device_flags = packet_in.device_flags;
+ packet1.manager_flags = packet_in.manager_flags;
+ packet1.gimbal_id = packet_in.gimbal_id;
+ packet1.supervisor = packet_in.supervisor;
+ packet1.profile = packet_in.profile;
+
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_STATUS_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_STATUS_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_storm32_gimbal_manager_status_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_storm32_gimbal_manager_status_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_storm32_gimbal_manager_status_pack(system_id, component_id, &msg , packet1.gimbal_id , packet1.supervisor , packet1.device_flags , packet1.manager_flags , packet1.profile );
+ mavlink_msg_storm32_gimbal_manager_status_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_storm32_gimbal_manager_status_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.gimbal_id , packet1.supervisor , packet1.device_flags , packet1.manager_flags , packet1.profile );
+ mavlink_msg_storm32_gimbal_manager_status_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_storm32_gimbal_manager_control_t packet_in = {
+ { 17.0, 18.0, 19.0, 20.0 },129.0,157.0,185.0,18691,18795,101,168,235,46
+ };
+ mavlink_storm32_gimbal_manager_control_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.angular_velocity_x = packet_in.angular_velocity_x;
+ packet1.angular_velocity_y = packet_in.angular_velocity_y;
+ packet1.angular_velocity_z = packet_in.angular_velocity_z;
+ packet1.device_flags = packet_in.device_flags;
+ packet1.manager_flags = packet_in.manager_flags;
+ packet1.target_system = packet_in.target_system;
+ packet1.target_component = packet_in.target_component;
+ packet1.gimbal_id = packet_in.gimbal_id;
+ packet1.client = packet_in.client;
+
+ mav_array_memcpy(packet1.q, packet_in.q, sizeof(float)*4);
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_storm32_gimbal_manager_control_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_storm32_gimbal_manager_control_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_storm32_gimbal_manager_control_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.gimbal_id , packet1.client , packet1.device_flags , packet1.manager_flags , packet1.q , packet1.angular_velocity_x , packet1.angular_velocity_y , packet1.angular_velocity_z );
+ mavlink_msg_storm32_gimbal_manager_control_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_storm32_gimbal_manager_control_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.gimbal_id , packet1.client , packet1.device_flags , packet1.manager_flags , packet1.q , packet1.angular_velocity_x , packet1.angular_velocity_y , packet1.angular_velocity_z );
+ mavlink_msg_storm32_gimbal_manager_control_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_storm32_gimbal_manager_control_pitchyaw_t packet_in = {
+ 17.0,45.0,73.0,101.0,18067,18171,65,132,199,10
+ };
+ mavlink_storm32_gimbal_manager_control_pitchyaw_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.pitch = packet_in.pitch;
+ packet1.yaw = packet_in.yaw;
+ packet1.pitch_rate = packet_in.pitch_rate;
+ packet1.yaw_rate = packet_in.yaw_rate;
+ packet1.device_flags = packet_in.device_flags;
+ packet1.manager_flags = packet_in.manager_flags;
+ packet1.target_system = packet_in.target_system;
+ packet1.target_component = packet_in.target_component;
+ packet1.gimbal_id = packet_in.gimbal_id;
+ packet1.client = packet_in.client;
+
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CONTROL_PITCHYAW_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_storm32_gimbal_manager_control_pitchyaw_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_storm32_gimbal_manager_control_pitchyaw_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_storm32_gimbal_manager_control_pitchyaw_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.gimbal_id , packet1.client , packet1.device_flags , packet1.manager_flags , packet1.pitch , packet1.yaw , packet1.pitch_rate , packet1.yaw_rate );
+ mavlink_msg_storm32_gimbal_manager_control_pitchyaw_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_storm32_gimbal_manager_control_pitchyaw_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.gimbal_id , packet1.client , packet1.device_flags , packet1.manager_flags , packet1.pitch , packet1.yaw , packet1.pitch_rate , packet1.yaw_rate );
+ mavlink_msg_storm32_gimbal_manager_control_pitchyaw_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CORRECT_ROLL >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_storm32_gimbal_manager_correct_roll_t packet_in = {
+ 17.0,17,84,151,218
+ };
+ mavlink_storm32_gimbal_manager_correct_roll_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.roll = packet_in.roll;
+ packet1.target_system = packet_in.target_system;
+ packet1.target_component = packet_in.target_component;
+ packet1.gimbal_id = packet_in.gimbal_id;
+ packet1.client = packet_in.client;
+
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CORRECT_ROLL_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_STORM32_GIMBAL_MANAGER_CORRECT_ROLL_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_storm32_gimbal_manager_correct_roll_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_storm32_gimbal_manager_correct_roll_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_storm32_gimbal_manager_correct_roll_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.gimbal_id , packet1.client , packet1.roll );
+ mavlink_msg_storm32_gimbal_manager_correct_roll_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_storm32_gimbal_manager_correct_roll_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.gimbal_id , packet1.client , packet1.roll );
+ mavlink_msg_storm32_gimbal_manager_correct_roll_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_QSHOT_STATUS >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_qshot_status_t packet_in = {
+ 17235,17339
+ };
+ mavlink_qshot_status_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.mode = packet_in.mode;
+ packet1.shot_state = packet_in.shot_state;
+
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_QSHOT_STATUS_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_QSHOT_STATUS_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_qshot_status_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_qshot_status_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_qshot_status_pack(system_id, component_id, &msg , packet1.mode , packet1.shot_state );
+ mavlink_msg_qshot_status_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_qshot_status_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.mode , packet1.shot_state );
+ mavlink_msg_qshot_status_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_EXT >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_autopilot_state_for_gimbal_device_ext_t packet_in = {
+ 93372036854775807ULL,73.0,101.0,129.0,65,132
+ };
+ mavlink_autopilot_state_for_gimbal_device_ext_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.time_boot_us = packet_in.time_boot_us;
+ packet1.wind_x = packet_in.wind_x;
+ packet1.wind_y = packet_in.wind_y;
+ packet1.wind_correction_angle = packet_in.wind_correction_angle;
+ packet1.target_system = packet_in.target_system;
+ packet1.target_component = packet_in.target_component;
+
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_EXT_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_EXT_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_autopilot_state_for_gimbal_device_ext_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_autopilot_state_for_gimbal_device_ext_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_autopilot_state_for_gimbal_device_ext_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.time_boot_us , packet1.wind_x , packet1.wind_y , packet1.wind_correction_angle );
+ mavlink_msg_autopilot_state_for_gimbal_device_ext_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_autopilot_state_for_gimbal_device_ext_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.time_boot_us , packet1.wind_x , packet1.wind_y , packet1.wind_correction_angle );
+ mavlink_msg_autopilot_state_for_gimbal_device_ext_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_FRSKY_PASSTHROUGH_ARRAY >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_frsky_passthrough_array_t packet_in = {
+ 963497464,17,{ 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, 145, 146, 147, 148, 149, 150, 151, 152, 153, 154, 155, 156, 157, 158, 159, 160, 161, 162, 163, 164, 165, 166, 167, 168, 169, 170, 171, 172, 173, 174, 175, 176, 177, 178, 179, 180, 181, 182, 183, 184, 185, 186, 187, 188, 189, 190, 191, 192, 193, 194, 195, 196, 197, 198, 199, 200, 201, 202, 203, 204, 205, 206, 207, 208, 209, 210, 211, 212, 213, 214, 215, 216, 217, 218, 219, 220, 221, 222, 223, 224, 225, 226, 227, 228, 229, 230, 231, 232, 233, 234, 235, 236, 237, 238, 239, 240, 241, 242, 243, 244, 245, 246, 247, 248, 249, 250, 251, 252, 253, 254, 255, 0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 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 }
+ };
+ mavlink_frsky_passthrough_array_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.time_boot_ms = packet_in.time_boot_ms;
+ packet1.count = packet_in.count;
+
+ mav_array_memcpy(packet1.packet_buf, packet_in.packet_buf, sizeof(uint8_t)*240);
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_FRSKY_PASSTHROUGH_ARRAY_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_FRSKY_PASSTHROUGH_ARRAY_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_frsky_passthrough_array_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_frsky_passthrough_array_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_frsky_passthrough_array_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.count , packet1.packet_buf );
+ mavlink_msg_frsky_passthrough_array_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_frsky_passthrough_array_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.count , packet1.packet_buf );
+ mavlink_msg_frsky_passthrough_array_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_PARAM_VALUE_ARRAY >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_param_value_array_t packet_in = {
+ 17235,17339,17443,151,{ 218, 219, 220, 221, 222, 223, 224, 225, 226, 227, 228, 229, 230, 231, 232, 233, 234, 235, 236, 237, 238, 239, 240, 241, 242, 243, 244, 245, 246, 247, 248, 249, 250, 251, 252, 253, 254, 255, 0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 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, 145, 146, 147, 148, 149, 150, 151, 152, 153, 154, 155, 156, 157, 158, 159, 160, 161, 162, 163, 164, 165, 166, 167, 168, 169, 170, 171, 172, 173, 174, 175, 176, 177, 178, 179, 180, 181, 182, 183, 184, 185, 186, 187, 188, 189, 190, 191, 192, 193, 194, 195, 196, 197, 198, 199, 200, 201, 202, 203, 204, 205, 206, 207, 208, 209 }
+ };
+ mavlink_param_value_array_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.param_count = packet_in.param_count;
+ packet1.param_index_first = packet_in.param_index_first;
+ packet1.flags = packet_in.flags;
+ packet1.param_array_len = packet_in.param_array_len;
+
+ mav_array_memcpy(packet1.packet_buf, packet_in.packet_buf, sizeof(uint8_t)*248);
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_PARAM_VALUE_ARRAY_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_PARAM_VALUE_ARRAY_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_param_value_array_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_param_value_array_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_param_value_array_pack(system_id, component_id, &msg , packet1.param_count , packet1.param_index_first , packet1.param_array_len , packet1.flags , packet1.packet_buf );
+ mavlink_msg_param_value_array_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_param_value_array_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.param_count , packet1.param_index_first , packet1.param_array_len , packet1.flags , packet1.packet_buf );
+ mavlink_msg_param_value_array_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_MLRS_RADIO_LINK_STATS >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_mlrs_radio_link_stats_t packet_in = {
+ 17235,139,206,17,84,151,218,29,96,163,230,41,108,175,122.0,150.0
+ };
+ mavlink_mlrs_radio_link_stats_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.flags = packet_in.flags;
+ packet1.target_system = packet_in.target_system;
+ packet1.target_component = packet_in.target_component;
+ packet1.rx_LQ_rc = packet_in.rx_LQ_rc;
+ packet1.rx_LQ_ser = packet_in.rx_LQ_ser;
+ packet1.rx_rssi1 = packet_in.rx_rssi1;
+ packet1.rx_snr1 = packet_in.rx_snr1;
+ packet1.tx_LQ_ser = packet_in.tx_LQ_ser;
+ packet1.tx_rssi1 = packet_in.tx_rssi1;
+ packet1.tx_snr1 = packet_in.tx_snr1;
+ packet1.rx_rssi2 = packet_in.rx_rssi2;
+ packet1.rx_snr2 = packet_in.rx_snr2;
+ packet1.tx_rssi2 = packet_in.tx_rssi2;
+ packet1.tx_snr2 = packet_in.tx_snr2;
+ packet1.frequency1 = packet_in.frequency1;
+ packet1.frequency2 = packet_in.frequency2;
+
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_MLRS_RADIO_LINK_STATS_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_MLRS_RADIO_LINK_STATS_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_mlrs_radio_link_stats_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_mlrs_radio_link_stats_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_mlrs_radio_link_stats_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.flags , packet1.rx_LQ_rc , packet1.rx_LQ_ser , packet1.rx_rssi1 , packet1.rx_snr1 , packet1.tx_LQ_ser , packet1.tx_rssi1 , packet1.tx_snr1 , packet1.rx_rssi2 , packet1.rx_snr2 , packet1.tx_rssi2 , packet1.tx_snr2 , packet1.frequency1 , packet1.frequency2 );
+ mavlink_msg_mlrs_radio_link_stats_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_mlrs_radio_link_stats_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.flags , packet1.rx_LQ_rc , packet1.rx_LQ_ser , packet1.rx_rssi1 , packet1.rx_snr1 , packet1.tx_LQ_ser , packet1.tx_rssi1 , packet1.tx_snr1 , packet1.rx_rssi2 , packet1.rx_snr2 , packet1.tx_rssi2 , packet1.tx_snr2 , packet1.frequency1 , packet1.frequency2 );
+ mavlink_msg_mlrs_radio_link_stats_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_MLRS_RADIO_LINK_INFORMATION >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_mlrs_radio_link_information_t packet_in = {
+ 17235,17339,17443,17547,29,96,163,230,41,108,"OPQRS","UVWXY",211,22
+ };
+ mavlink_mlrs_radio_link_information_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.tx_frame_rate = packet_in.tx_frame_rate;
+ packet1.rx_frame_rate = packet_in.rx_frame_rate;
+ packet1.tx_ser_data_rate = packet_in.tx_ser_data_rate;
+ packet1.rx_ser_data_rate = packet_in.rx_ser_data_rate;
+ packet1.target_system = packet_in.target_system;
+ packet1.target_component = packet_in.target_component;
+ packet1.type = packet_in.type;
+ packet1.mode = packet_in.mode;
+ packet1.tx_power = packet_in.tx_power;
+ packet1.rx_power = packet_in.rx_power;
+ packet1.tx_receive_sensitivity = packet_in.tx_receive_sensitivity;
+ packet1.rx_receive_sensitivity = packet_in.rx_receive_sensitivity;
+
+ mav_array_memcpy(packet1.mode_str, packet_in.mode_str, sizeof(char)*6);
+ mav_array_memcpy(packet1.band_str, packet_in.band_str, sizeof(char)*6);
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_MLRS_RADIO_LINK_INFORMATION_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_MLRS_RADIO_LINK_INFORMATION_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_mlrs_radio_link_information_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_mlrs_radio_link_information_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_mlrs_radio_link_information_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.type , packet1.mode , packet1.tx_power , packet1.rx_power , packet1.tx_frame_rate , packet1.rx_frame_rate , packet1.mode_str , packet1.band_str , packet1.tx_ser_data_rate , packet1.rx_ser_data_rate , packet1.tx_receive_sensitivity , packet1.rx_receive_sensitivity );
+ mavlink_msg_mlrs_radio_link_information_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_mlrs_radio_link_information_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.type , packet1.mode , packet1.tx_power , packet1.rx_power , packet1.tx_frame_rate , packet1.rx_frame_rate , packet1.mode_str , packet1.band_str , packet1.tx_ser_data_rate , packet1.rx_ser_data_rate , packet1.tx_receive_sensitivity , packet1.rx_receive_sensitivity );
+ mavlink_msg_mlrs_radio_link_information_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_MLRS_RADIO_LINK_FLOW_CONTROL >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_mlrs_radio_link_flow_control_t packet_in = {
+ 17235,17339,17,84,151
+ };
+ mavlink_mlrs_radio_link_flow_control_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.tx_ser_rate = packet_in.tx_ser_rate;
+ packet1.rx_ser_rate = packet_in.rx_ser_rate;
+ packet1.tx_used_ser_bandwidth = packet_in.tx_used_ser_bandwidth;
+ packet1.rx_used_ser_bandwidth = packet_in.rx_used_ser_bandwidth;
+ packet1.txbuf = packet_in.txbuf;
+
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_MLRS_RADIO_LINK_FLOW_CONTROL_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_MLRS_RADIO_LINK_FLOW_CONTROL_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_mlrs_radio_link_flow_control_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_mlrs_radio_link_flow_control_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_mlrs_radio_link_flow_control_pack(system_id, component_id, &msg , packet1.tx_ser_rate , packet1.rx_ser_rate , packet1.tx_used_ser_bandwidth , packet1.rx_used_ser_bandwidth , packet1.txbuf );
+ mavlink_msg_mlrs_radio_link_flow_control_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_mlrs_radio_link_flow_control_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.tx_ser_rate , packet1.rx_ser_rate , packet1.tx_used_ser_bandwidth , packet1.rx_used_ser_bandwidth , packet1.txbuf );
+ mavlink_msg_mlrs_radio_link_flow_control_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; imsgid = MAVLINK_MSG_ID_UAVIONIX_ADSB_GET;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_UAVIONIX_ADSB_GET_MIN_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_GET_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_GET_CRC);
+}
+
+/**
+ * @brief Pack a uavionix_adsb_get 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 ReqMessageId Message ID to request. Supports any message in this 10000-10099 range
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_uavionix_adsb_get_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ uint32_t ReqMessageId)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_UAVIONIX_ADSB_GET_LEN];
+ _mav_put_uint32_t(buf, 0, ReqMessageId);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_UAVIONIX_ADSB_GET_LEN);
+#else
+ mavlink_uavionix_adsb_get_t packet;
+ packet.ReqMessageId = ReqMessageId;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_UAVIONIX_ADSB_GET_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_UAVIONIX_ADSB_GET;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_UAVIONIX_ADSB_GET_MIN_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_GET_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_GET_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_UAVIONIX_ADSB_GET_MIN_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_GET_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a uavionix_adsb_get 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 ReqMessageId Message ID to request. Supports any message in this 10000-10099 range
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_uavionix_adsb_get_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint32_t ReqMessageId)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_UAVIONIX_ADSB_GET_LEN];
+ _mav_put_uint32_t(buf, 0, ReqMessageId);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_UAVIONIX_ADSB_GET_LEN);
+#else
+ mavlink_uavionix_adsb_get_t packet;
+ packet.ReqMessageId = ReqMessageId;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_UAVIONIX_ADSB_GET_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_UAVIONIX_ADSB_GET;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_UAVIONIX_ADSB_GET_MIN_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_GET_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_GET_CRC);
+}
+
+/**
+ * @brief Encode a uavionix_adsb_get 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 uavionix_adsb_get C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_uavionix_adsb_get_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_uavionix_adsb_get_t* uavionix_adsb_get)
+{
+ return mavlink_msg_uavionix_adsb_get_pack(system_id, component_id, msg, uavionix_adsb_get->ReqMessageId);
+}
+
+/**
+ * @brief Encode a uavionix_adsb_get 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 uavionix_adsb_get C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_uavionix_adsb_get_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_uavionix_adsb_get_t* uavionix_adsb_get)
+{
+ return mavlink_msg_uavionix_adsb_get_pack_chan(system_id, component_id, chan, msg, uavionix_adsb_get->ReqMessageId);
+}
+
+/**
+ * @brief Encode a uavionix_adsb_get 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 uavionix_adsb_get C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_uavionix_adsb_get_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_uavionix_adsb_get_t* uavionix_adsb_get)
+{
+ return mavlink_msg_uavionix_adsb_get_pack_status(system_id, component_id, _status, msg, uavionix_adsb_get->ReqMessageId);
+}
+
+/**
+ * @brief Send a uavionix_adsb_get message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param ReqMessageId Message ID to request. Supports any message in this 10000-10099 range
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_uavionix_adsb_get_send(mavlink_channel_t chan, uint32_t ReqMessageId)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_UAVIONIX_ADSB_GET_LEN];
+ _mav_put_uint32_t(buf, 0, ReqMessageId);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_UAVIONIX_ADSB_GET, buf, MAVLINK_MSG_ID_UAVIONIX_ADSB_GET_MIN_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_GET_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_GET_CRC);
+#else
+ mavlink_uavionix_adsb_get_t packet;
+ packet.ReqMessageId = ReqMessageId;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_UAVIONIX_ADSB_GET, (const char *)&packet, MAVLINK_MSG_ID_UAVIONIX_ADSB_GET_MIN_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_GET_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_GET_CRC);
+#endif
+}
+
+/**
+ * @brief Send a uavionix_adsb_get message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_uavionix_adsb_get_send_struct(mavlink_channel_t chan, const mavlink_uavionix_adsb_get_t* uavionix_adsb_get)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_uavionix_adsb_get_send(chan, uavionix_adsb_get->ReqMessageId);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_UAVIONIX_ADSB_GET, (const char *)uavionix_adsb_get, MAVLINK_MSG_ID_UAVIONIX_ADSB_GET_MIN_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_GET_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_GET_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_UAVIONIX_ADSB_GET_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_uavionix_adsb_get_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t ReqMessageId)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint32_t(buf, 0, ReqMessageId);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_UAVIONIX_ADSB_GET, buf, MAVLINK_MSG_ID_UAVIONIX_ADSB_GET_MIN_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_GET_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_GET_CRC);
+#else
+ mavlink_uavionix_adsb_get_t *packet = (mavlink_uavionix_adsb_get_t *)msgbuf;
+ packet->ReqMessageId = ReqMessageId;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_UAVIONIX_ADSB_GET, (const char *)packet, MAVLINK_MSG_ID_UAVIONIX_ADSB_GET_MIN_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_GET_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_GET_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE UAVIONIX_ADSB_GET UNPACKING
+
+
+/**
+ * @brief Get field ReqMessageId from uavionix_adsb_get message
+ *
+ * @return Message ID to request. Supports any message in this 10000-10099 range
+ */
+static inline uint32_t mavlink_msg_uavionix_adsb_get_get_ReqMessageId(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint32_t(msg, 0);
+}
+
+/**
+ * @brief Decode a uavionix_adsb_get message into a struct
+ *
+ * @param msg The message to decode
+ * @param uavionix_adsb_get C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_uavionix_adsb_get_decode(const mavlink_message_t* msg, mavlink_uavionix_adsb_get_t* uavionix_adsb_get)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ uavionix_adsb_get->ReqMessageId = mavlink_msg_uavionix_adsb_get_get_ReqMessageId(msg);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_UAVIONIX_ADSB_GET_LEN? msg->len : MAVLINK_MSG_ID_UAVIONIX_ADSB_GET_LEN;
+ memset(uavionix_adsb_get, 0, MAVLINK_MSG_ID_UAVIONIX_ADSB_GET_LEN);
+ memcpy(uavionix_adsb_get, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/uAvionix/mavlink_msg_uavionix_adsb_out_cfg.h b/lib/main/MAVLink/uAvionix/mavlink_msg_uavionix_adsb_out_cfg.h
new file mode 100644
index 00000000000..62384bae462
--- /dev/null
+++ b/lib/main/MAVLink/uAvionix/mavlink_msg_uavionix_adsb_out_cfg.h
@@ -0,0 +1,446 @@
+#pragma once
+// MESSAGE UAVIONIX_ADSB_OUT_CFG PACKING
+
+#define MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG 10001
+
+
+typedef struct __mavlink_uavionix_adsb_out_cfg_t {
+ uint32_t ICAO; /*< Vehicle address (24 bit)*/
+ uint16_t stallSpeed; /*< [cm/s] Aircraft stall speed in cm/s*/
+ char callsign[9]; /*< Vehicle identifier (8 characters, null terminated, valid characters are A-Z, 0-9, " " only)*/
+ uint8_t emitterType; /*< Transmitting vehicle type. See ADSB_EMITTER_TYPE enum*/
+ uint8_t aircraftSize; /*< Aircraft length and width encoding (table 2-35 of DO-282B)*/
+ uint8_t gpsOffsetLat; /*< GPS antenna lateral offset (table 2-36 of DO-282B)*/
+ uint8_t gpsOffsetLon; /*< GPS antenna longitudinal offset from nose [if non-zero, take position (in meters) divide by 2 and add one] (table 2-37 DO-282B)*/
+ uint8_t rfSelect; /*< ADS-B transponder receiver and transmit enable flags*/
+} mavlink_uavionix_adsb_out_cfg_t;
+
+#define MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_LEN 20
+#define MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_MIN_LEN 20
+#define MAVLINK_MSG_ID_10001_LEN 20
+#define MAVLINK_MSG_ID_10001_MIN_LEN 20
+
+#define MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_CRC 209
+#define MAVLINK_MSG_ID_10001_CRC 209
+
+#define MAVLINK_MSG_UAVIONIX_ADSB_OUT_CFG_FIELD_CALLSIGN_LEN 9
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_UAVIONIX_ADSB_OUT_CFG { \
+ 10001, \
+ "UAVIONIX_ADSB_OUT_CFG", \
+ 8, \
+ { { "ICAO", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_uavionix_adsb_out_cfg_t, ICAO) }, \
+ { "callsign", NULL, MAVLINK_TYPE_CHAR, 9, 6, offsetof(mavlink_uavionix_adsb_out_cfg_t, callsign) }, \
+ { "emitterType", NULL, MAVLINK_TYPE_UINT8_T, 0, 15, offsetof(mavlink_uavionix_adsb_out_cfg_t, emitterType) }, \
+ { "aircraftSize", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_uavionix_adsb_out_cfg_t, aircraftSize) }, \
+ { "gpsOffsetLat", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_uavionix_adsb_out_cfg_t, gpsOffsetLat) }, \
+ { "gpsOffsetLon", NULL, MAVLINK_TYPE_UINT8_T, 0, 18, offsetof(mavlink_uavionix_adsb_out_cfg_t, gpsOffsetLon) }, \
+ { "stallSpeed", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_uavionix_adsb_out_cfg_t, stallSpeed) }, \
+ { "rfSelect", NULL, MAVLINK_TYPE_UINT8_T, 0, 19, offsetof(mavlink_uavionix_adsb_out_cfg_t, rfSelect) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_UAVIONIX_ADSB_OUT_CFG { \
+ "UAVIONIX_ADSB_OUT_CFG", \
+ 8, \
+ { { "ICAO", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_uavionix_adsb_out_cfg_t, ICAO) }, \
+ { "callsign", NULL, MAVLINK_TYPE_CHAR, 9, 6, offsetof(mavlink_uavionix_adsb_out_cfg_t, callsign) }, \
+ { "emitterType", NULL, MAVLINK_TYPE_UINT8_T, 0, 15, offsetof(mavlink_uavionix_adsb_out_cfg_t, emitterType) }, \
+ { "aircraftSize", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_uavionix_adsb_out_cfg_t, aircraftSize) }, \
+ { "gpsOffsetLat", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_uavionix_adsb_out_cfg_t, gpsOffsetLat) }, \
+ { "gpsOffsetLon", NULL, MAVLINK_TYPE_UINT8_T, 0, 18, offsetof(mavlink_uavionix_adsb_out_cfg_t, gpsOffsetLon) }, \
+ { "stallSpeed", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_uavionix_adsb_out_cfg_t, stallSpeed) }, \
+ { "rfSelect", NULL, MAVLINK_TYPE_UINT8_T, 0, 19, offsetof(mavlink_uavionix_adsb_out_cfg_t, rfSelect) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a uavionix_adsb_out_cfg 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 ICAO Vehicle address (24 bit)
+ * @param callsign Vehicle identifier (8 characters, null terminated, valid characters are A-Z, 0-9, " " only)
+ * @param emitterType Transmitting vehicle type. See ADSB_EMITTER_TYPE enum
+ * @param aircraftSize Aircraft length and width encoding (table 2-35 of DO-282B)
+ * @param gpsOffsetLat GPS antenna lateral offset (table 2-36 of DO-282B)
+ * @param gpsOffsetLon GPS antenna longitudinal offset from nose [if non-zero, take position (in meters) divide by 2 and add one] (table 2-37 DO-282B)
+ * @param stallSpeed [cm/s] Aircraft stall speed in cm/s
+ * @param rfSelect ADS-B transponder receiver and transmit enable flags
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_uavionix_adsb_out_cfg_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint32_t ICAO, const char *callsign, uint8_t emitterType, uint8_t aircraftSize, uint8_t gpsOffsetLat, uint8_t gpsOffsetLon, uint16_t stallSpeed, uint8_t rfSelect)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_LEN];
+ _mav_put_uint32_t(buf, 0, ICAO);
+ _mav_put_uint16_t(buf, 4, stallSpeed);
+ _mav_put_uint8_t(buf, 15, emitterType);
+ _mav_put_uint8_t(buf, 16, aircraftSize);
+ _mav_put_uint8_t(buf, 17, gpsOffsetLat);
+ _mav_put_uint8_t(buf, 18, gpsOffsetLon);
+ _mav_put_uint8_t(buf, 19, rfSelect);
+ _mav_put_char_array(buf, 6, callsign, 9);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_LEN);
+#else
+ mavlink_uavionix_adsb_out_cfg_t packet;
+ packet.ICAO = ICAO;
+ packet.stallSpeed = stallSpeed;
+ packet.emitterType = emitterType;
+ packet.aircraftSize = aircraftSize;
+ packet.gpsOffsetLat = gpsOffsetLat;
+ packet.gpsOffsetLon = gpsOffsetLon;
+ packet.rfSelect = rfSelect;
+ mav_array_assign_char(packet.callsign, callsign, 9);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_MIN_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_CRC);
+}
+
+/**
+ * @brief Pack a uavionix_adsb_out_cfg 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 ICAO Vehicle address (24 bit)
+ * @param callsign Vehicle identifier (8 characters, null terminated, valid characters are A-Z, 0-9, " " only)
+ * @param emitterType Transmitting vehicle type. See ADSB_EMITTER_TYPE enum
+ * @param aircraftSize Aircraft length and width encoding (table 2-35 of DO-282B)
+ * @param gpsOffsetLat GPS antenna lateral offset (table 2-36 of DO-282B)
+ * @param gpsOffsetLon GPS antenna longitudinal offset from nose [if non-zero, take position (in meters) divide by 2 and add one] (table 2-37 DO-282B)
+ * @param stallSpeed [cm/s] Aircraft stall speed in cm/s
+ * @param rfSelect ADS-B transponder receiver and transmit enable flags
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_uavionix_adsb_out_cfg_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ uint32_t ICAO, const char *callsign, uint8_t emitterType, uint8_t aircraftSize, uint8_t gpsOffsetLat, uint8_t gpsOffsetLon, uint16_t stallSpeed, uint8_t rfSelect)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_LEN];
+ _mav_put_uint32_t(buf, 0, ICAO);
+ _mav_put_uint16_t(buf, 4, stallSpeed);
+ _mav_put_uint8_t(buf, 15, emitterType);
+ _mav_put_uint8_t(buf, 16, aircraftSize);
+ _mav_put_uint8_t(buf, 17, gpsOffsetLat);
+ _mav_put_uint8_t(buf, 18, gpsOffsetLon);
+ _mav_put_uint8_t(buf, 19, rfSelect);
+ _mav_put_char_array(buf, 6, callsign, 9);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_LEN);
+#else
+ mavlink_uavionix_adsb_out_cfg_t packet;
+ packet.ICAO = ICAO;
+ packet.stallSpeed = stallSpeed;
+ packet.emitterType = emitterType;
+ packet.aircraftSize = aircraftSize;
+ packet.gpsOffsetLat = gpsOffsetLat;
+ packet.gpsOffsetLon = gpsOffsetLon;
+ packet.rfSelect = rfSelect;
+ mav_array_memcpy(packet.callsign, callsign, sizeof(char)*9);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_MIN_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_MIN_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a uavionix_adsb_out_cfg 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 ICAO Vehicle address (24 bit)
+ * @param callsign Vehicle identifier (8 characters, null terminated, valid characters are A-Z, 0-9, " " only)
+ * @param emitterType Transmitting vehicle type. See ADSB_EMITTER_TYPE enum
+ * @param aircraftSize Aircraft length and width encoding (table 2-35 of DO-282B)
+ * @param gpsOffsetLat GPS antenna lateral offset (table 2-36 of DO-282B)
+ * @param gpsOffsetLon GPS antenna longitudinal offset from nose [if non-zero, take position (in meters) divide by 2 and add one] (table 2-37 DO-282B)
+ * @param stallSpeed [cm/s] Aircraft stall speed in cm/s
+ * @param rfSelect ADS-B transponder receiver and transmit enable flags
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_uavionix_adsb_out_cfg_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint32_t ICAO,const char *callsign,uint8_t emitterType,uint8_t aircraftSize,uint8_t gpsOffsetLat,uint8_t gpsOffsetLon,uint16_t stallSpeed,uint8_t rfSelect)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_LEN];
+ _mav_put_uint32_t(buf, 0, ICAO);
+ _mav_put_uint16_t(buf, 4, stallSpeed);
+ _mav_put_uint8_t(buf, 15, emitterType);
+ _mav_put_uint8_t(buf, 16, aircraftSize);
+ _mav_put_uint8_t(buf, 17, gpsOffsetLat);
+ _mav_put_uint8_t(buf, 18, gpsOffsetLon);
+ _mav_put_uint8_t(buf, 19, rfSelect);
+ _mav_put_char_array(buf, 6, callsign, 9);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_LEN);
+#else
+ mavlink_uavionix_adsb_out_cfg_t packet;
+ packet.ICAO = ICAO;
+ packet.stallSpeed = stallSpeed;
+ packet.emitterType = emitterType;
+ packet.aircraftSize = aircraftSize;
+ packet.gpsOffsetLat = gpsOffsetLat;
+ packet.gpsOffsetLon = gpsOffsetLon;
+ packet.rfSelect = rfSelect;
+ mav_array_assign_char(packet.callsign, callsign, 9);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_MIN_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_CRC);
+}
+
+/**
+ * @brief Encode a uavionix_adsb_out_cfg 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 uavionix_adsb_out_cfg C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_uavionix_adsb_out_cfg_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_uavionix_adsb_out_cfg_t* uavionix_adsb_out_cfg)
+{
+ return mavlink_msg_uavionix_adsb_out_cfg_pack(system_id, component_id, msg, uavionix_adsb_out_cfg->ICAO, uavionix_adsb_out_cfg->callsign, uavionix_adsb_out_cfg->emitterType, uavionix_adsb_out_cfg->aircraftSize, uavionix_adsb_out_cfg->gpsOffsetLat, uavionix_adsb_out_cfg->gpsOffsetLon, uavionix_adsb_out_cfg->stallSpeed, uavionix_adsb_out_cfg->rfSelect);
+}
+
+/**
+ * @brief Encode a uavionix_adsb_out_cfg 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 uavionix_adsb_out_cfg C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_uavionix_adsb_out_cfg_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_uavionix_adsb_out_cfg_t* uavionix_adsb_out_cfg)
+{
+ return mavlink_msg_uavionix_adsb_out_cfg_pack_chan(system_id, component_id, chan, msg, uavionix_adsb_out_cfg->ICAO, uavionix_adsb_out_cfg->callsign, uavionix_adsb_out_cfg->emitterType, uavionix_adsb_out_cfg->aircraftSize, uavionix_adsb_out_cfg->gpsOffsetLat, uavionix_adsb_out_cfg->gpsOffsetLon, uavionix_adsb_out_cfg->stallSpeed, uavionix_adsb_out_cfg->rfSelect);
+}
+
+/**
+ * @brief Encode a uavionix_adsb_out_cfg 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 uavionix_adsb_out_cfg C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_uavionix_adsb_out_cfg_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_uavionix_adsb_out_cfg_t* uavionix_adsb_out_cfg)
+{
+ return mavlink_msg_uavionix_adsb_out_cfg_pack_status(system_id, component_id, _status, msg, uavionix_adsb_out_cfg->ICAO, uavionix_adsb_out_cfg->callsign, uavionix_adsb_out_cfg->emitterType, uavionix_adsb_out_cfg->aircraftSize, uavionix_adsb_out_cfg->gpsOffsetLat, uavionix_adsb_out_cfg->gpsOffsetLon, uavionix_adsb_out_cfg->stallSpeed, uavionix_adsb_out_cfg->rfSelect);
+}
+
+/**
+ * @brief Send a uavionix_adsb_out_cfg message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param ICAO Vehicle address (24 bit)
+ * @param callsign Vehicle identifier (8 characters, null terminated, valid characters are A-Z, 0-9, " " only)
+ * @param emitterType Transmitting vehicle type. See ADSB_EMITTER_TYPE enum
+ * @param aircraftSize Aircraft length and width encoding (table 2-35 of DO-282B)
+ * @param gpsOffsetLat GPS antenna lateral offset (table 2-36 of DO-282B)
+ * @param gpsOffsetLon GPS antenna longitudinal offset from nose [if non-zero, take position (in meters) divide by 2 and add one] (table 2-37 DO-282B)
+ * @param stallSpeed [cm/s] Aircraft stall speed in cm/s
+ * @param rfSelect ADS-B transponder receiver and transmit enable flags
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_uavionix_adsb_out_cfg_send(mavlink_channel_t chan, uint32_t ICAO, const char *callsign, uint8_t emitterType, uint8_t aircraftSize, uint8_t gpsOffsetLat, uint8_t gpsOffsetLon, uint16_t stallSpeed, uint8_t rfSelect)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_LEN];
+ _mav_put_uint32_t(buf, 0, ICAO);
+ _mav_put_uint16_t(buf, 4, stallSpeed);
+ _mav_put_uint8_t(buf, 15, emitterType);
+ _mav_put_uint8_t(buf, 16, aircraftSize);
+ _mav_put_uint8_t(buf, 17, gpsOffsetLat);
+ _mav_put_uint8_t(buf, 18, gpsOffsetLon);
+ _mav_put_uint8_t(buf, 19, rfSelect);
+ _mav_put_char_array(buf, 6, callsign, 9);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG, buf, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_MIN_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_CRC);
+#else
+ mavlink_uavionix_adsb_out_cfg_t packet;
+ packet.ICAO = ICAO;
+ packet.stallSpeed = stallSpeed;
+ packet.emitterType = emitterType;
+ packet.aircraftSize = aircraftSize;
+ packet.gpsOffsetLat = gpsOffsetLat;
+ packet.gpsOffsetLon = gpsOffsetLon;
+ packet.rfSelect = rfSelect;
+ mav_array_assign_char(packet.callsign, callsign, 9);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG, (const char *)&packet, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_MIN_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_CRC);
+#endif
+}
+
+/**
+ * @brief Send a uavionix_adsb_out_cfg message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_uavionix_adsb_out_cfg_send_struct(mavlink_channel_t chan, const mavlink_uavionix_adsb_out_cfg_t* uavionix_adsb_out_cfg)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_uavionix_adsb_out_cfg_send(chan, uavionix_adsb_out_cfg->ICAO, uavionix_adsb_out_cfg->callsign, uavionix_adsb_out_cfg->emitterType, uavionix_adsb_out_cfg->aircraftSize, uavionix_adsb_out_cfg->gpsOffsetLat, uavionix_adsb_out_cfg->gpsOffsetLon, uavionix_adsb_out_cfg->stallSpeed, uavionix_adsb_out_cfg->rfSelect);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG, (const char *)uavionix_adsb_out_cfg, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_MIN_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_uavionix_adsb_out_cfg_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t ICAO, const char *callsign, uint8_t emitterType, uint8_t aircraftSize, uint8_t gpsOffsetLat, uint8_t gpsOffsetLon, uint16_t stallSpeed, uint8_t rfSelect)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint32_t(buf, 0, ICAO);
+ _mav_put_uint16_t(buf, 4, stallSpeed);
+ _mav_put_uint8_t(buf, 15, emitterType);
+ _mav_put_uint8_t(buf, 16, aircraftSize);
+ _mav_put_uint8_t(buf, 17, gpsOffsetLat);
+ _mav_put_uint8_t(buf, 18, gpsOffsetLon);
+ _mav_put_uint8_t(buf, 19, rfSelect);
+ _mav_put_char_array(buf, 6, callsign, 9);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG, buf, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_MIN_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_CRC);
+#else
+ mavlink_uavionix_adsb_out_cfg_t *packet = (mavlink_uavionix_adsb_out_cfg_t *)msgbuf;
+ packet->ICAO = ICAO;
+ packet->stallSpeed = stallSpeed;
+ packet->emitterType = emitterType;
+ packet->aircraftSize = aircraftSize;
+ packet->gpsOffsetLat = gpsOffsetLat;
+ packet->gpsOffsetLon = gpsOffsetLon;
+ packet->rfSelect = rfSelect;
+ mav_array_assign_char(packet->callsign, callsign, 9);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG, (const char *)packet, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_MIN_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE UAVIONIX_ADSB_OUT_CFG UNPACKING
+
+
+/**
+ * @brief Get field ICAO from uavionix_adsb_out_cfg message
+ *
+ * @return Vehicle address (24 bit)
+ */
+static inline uint32_t mavlink_msg_uavionix_adsb_out_cfg_get_ICAO(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint32_t(msg, 0);
+}
+
+/**
+ * @brief Get field callsign from uavionix_adsb_out_cfg message
+ *
+ * @return Vehicle identifier (8 characters, null terminated, valid characters are A-Z, 0-9, " " only)
+ */
+static inline uint16_t mavlink_msg_uavionix_adsb_out_cfg_get_callsign(const mavlink_message_t* msg, char *callsign)
+{
+ return _MAV_RETURN_char_array(msg, callsign, 9, 6);
+}
+
+/**
+ * @brief Get field emitterType from uavionix_adsb_out_cfg message
+ *
+ * @return Transmitting vehicle type. See ADSB_EMITTER_TYPE enum
+ */
+static inline uint8_t mavlink_msg_uavionix_adsb_out_cfg_get_emitterType(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 15);
+}
+
+/**
+ * @brief Get field aircraftSize from uavionix_adsb_out_cfg message
+ *
+ * @return Aircraft length and width encoding (table 2-35 of DO-282B)
+ */
+static inline uint8_t mavlink_msg_uavionix_adsb_out_cfg_get_aircraftSize(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 16);
+}
+
+/**
+ * @brief Get field gpsOffsetLat from uavionix_adsb_out_cfg message
+ *
+ * @return GPS antenna lateral offset (table 2-36 of DO-282B)
+ */
+static inline uint8_t mavlink_msg_uavionix_adsb_out_cfg_get_gpsOffsetLat(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 17);
+}
+
+/**
+ * @brief Get field gpsOffsetLon from uavionix_adsb_out_cfg message
+ *
+ * @return GPS antenna longitudinal offset from nose [if non-zero, take position (in meters) divide by 2 and add one] (table 2-37 DO-282B)
+ */
+static inline uint8_t mavlink_msg_uavionix_adsb_out_cfg_get_gpsOffsetLon(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 18);
+}
+
+/**
+ * @brief Get field stallSpeed from uavionix_adsb_out_cfg message
+ *
+ * @return [cm/s] Aircraft stall speed in cm/s
+ */
+static inline uint16_t mavlink_msg_uavionix_adsb_out_cfg_get_stallSpeed(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 4);
+}
+
+/**
+ * @brief Get field rfSelect from uavionix_adsb_out_cfg message
+ *
+ * @return ADS-B transponder receiver and transmit enable flags
+ */
+static inline uint8_t mavlink_msg_uavionix_adsb_out_cfg_get_rfSelect(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 19);
+}
+
+/**
+ * @brief Decode a uavionix_adsb_out_cfg message into a struct
+ *
+ * @param msg The message to decode
+ * @param uavionix_adsb_out_cfg C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_uavionix_adsb_out_cfg_decode(const mavlink_message_t* msg, mavlink_uavionix_adsb_out_cfg_t* uavionix_adsb_out_cfg)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ uavionix_adsb_out_cfg->ICAO = mavlink_msg_uavionix_adsb_out_cfg_get_ICAO(msg);
+ uavionix_adsb_out_cfg->stallSpeed = mavlink_msg_uavionix_adsb_out_cfg_get_stallSpeed(msg);
+ mavlink_msg_uavionix_adsb_out_cfg_get_callsign(msg, uavionix_adsb_out_cfg->callsign);
+ uavionix_adsb_out_cfg->emitterType = mavlink_msg_uavionix_adsb_out_cfg_get_emitterType(msg);
+ uavionix_adsb_out_cfg->aircraftSize = mavlink_msg_uavionix_adsb_out_cfg_get_aircraftSize(msg);
+ uavionix_adsb_out_cfg->gpsOffsetLat = mavlink_msg_uavionix_adsb_out_cfg_get_gpsOffsetLat(msg);
+ uavionix_adsb_out_cfg->gpsOffsetLon = mavlink_msg_uavionix_adsb_out_cfg_get_gpsOffsetLon(msg);
+ uavionix_adsb_out_cfg->rfSelect = mavlink_msg_uavionix_adsb_out_cfg_get_rfSelect(msg);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_LEN? msg->len : MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_LEN;
+ memset(uavionix_adsb_out_cfg, 0, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_LEN);
+ memcpy(uavionix_adsb_out_cfg, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/uAvionix/mavlink_msg_uavionix_adsb_out_cfg_flightid.h b/lib/main/MAVLink/uAvionix/mavlink_msg_uavionix_adsb_out_cfg_flightid.h
new file mode 100644
index 00000000000..0801f60bf32
--- /dev/null
+++ b/lib/main/MAVLink/uAvionix/mavlink_msg_uavionix_adsb_out_cfg_flightid.h
@@ -0,0 +1,260 @@
+#pragma once
+// MESSAGE UAVIONIX_ADSB_OUT_CFG_FLIGHTID PACKING
+
+#define MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_FLIGHTID 10005
+
+
+typedef struct __mavlink_uavionix_adsb_out_cfg_flightid_t {
+ char flight_id[9]; /*< Flight Identification: 8 ASCII characters, '0' through '9', 'A' through 'Z' or space. Spaces (0x20) used as a trailing pad character, or when call sign is unavailable. Reflects Control message setting. This is null-terminated.*/
+} mavlink_uavionix_adsb_out_cfg_flightid_t;
+
+#define MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_FLIGHTID_LEN 9
+#define MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_FLIGHTID_MIN_LEN 9
+#define MAVLINK_MSG_ID_10005_LEN 9
+#define MAVLINK_MSG_ID_10005_MIN_LEN 9
+
+#define MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_FLIGHTID_CRC 103
+#define MAVLINK_MSG_ID_10005_CRC 103
+
+#define MAVLINK_MSG_UAVIONIX_ADSB_OUT_CFG_FLIGHTID_FIELD_FLIGHT_ID_LEN 9
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_UAVIONIX_ADSB_OUT_CFG_FLIGHTID { \
+ 10005, \
+ "UAVIONIX_ADSB_OUT_CFG_FLIGHTID", \
+ 1, \
+ { { "flight_id", NULL, MAVLINK_TYPE_CHAR, 9, 0, offsetof(mavlink_uavionix_adsb_out_cfg_flightid_t, flight_id) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_UAVIONIX_ADSB_OUT_CFG_FLIGHTID { \
+ "UAVIONIX_ADSB_OUT_CFG_FLIGHTID", \
+ 1, \
+ { { "flight_id", NULL, MAVLINK_TYPE_CHAR, 9, 0, offsetof(mavlink_uavionix_adsb_out_cfg_flightid_t, flight_id) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a uavionix_adsb_out_cfg_flightid 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 flight_id Flight Identification: 8 ASCII characters, '0' through '9', 'A' through 'Z' or space. Spaces (0x20) used as a trailing pad character, or when call sign is unavailable. Reflects Control message setting. This is null-terminated.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_uavionix_adsb_out_cfg_flightid_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ const char *flight_id)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_FLIGHTID_LEN];
+
+ _mav_put_char_array(buf, 0, flight_id, 9);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_FLIGHTID_LEN);
+#else
+ mavlink_uavionix_adsb_out_cfg_flightid_t packet;
+
+ mav_array_assign_char(packet.flight_id, flight_id, 9);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_FLIGHTID_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_FLIGHTID;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_FLIGHTID_MIN_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_FLIGHTID_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_FLIGHTID_CRC);
+}
+
+/**
+ * @brief Pack a uavionix_adsb_out_cfg_flightid 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 flight_id Flight Identification: 8 ASCII characters, '0' through '9', 'A' through 'Z' or space. Spaces (0x20) used as a trailing pad character, or when call sign is unavailable. Reflects Control message setting. This is null-terminated.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_uavionix_adsb_out_cfg_flightid_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ const char *flight_id)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_FLIGHTID_LEN];
+
+ _mav_put_char_array(buf, 0, flight_id, 9);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_FLIGHTID_LEN);
+#else
+ mavlink_uavionix_adsb_out_cfg_flightid_t packet;
+
+ mav_array_memcpy(packet.flight_id, flight_id, sizeof(char)*9);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_FLIGHTID_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_FLIGHTID;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_FLIGHTID_MIN_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_FLIGHTID_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_FLIGHTID_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_FLIGHTID_MIN_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_FLIGHTID_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a uavionix_adsb_out_cfg_flightid 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 flight_id Flight Identification: 8 ASCII characters, '0' through '9', 'A' through 'Z' or space. Spaces (0x20) used as a trailing pad character, or when call sign is unavailable. Reflects Control message setting. This is null-terminated.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_uavionix_adsb_out_cfg_flightid_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ const char *flight_id)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_FLIGHTID_LEN];
+
+ _mav_put_char_array(buf, 0, flight_id, 9);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_FLIGHTID_LEN);
+#else
+ mavlink_uavionix_adsb_out_cfg_flightid_t packet;
+
+ mav_array_assign_char(packet.flight_id, flight_id, 9);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_FLIGHTID_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_FLIGHTID;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_FLIGHTID_MIN_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_FLIGHTID_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_FLIGHTID_CRC);
+}
+
+/**
+ * @brief Encode a uavionix_adsb_out_cfg_flightid 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 uavionix_adsb_out_cfg_flightid C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_uavionix_adsb_out_cfg_flightid_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_uavionix_adsb_out_cfg_flightid_t* uavionix_adsb_out_cfg_flightid)
+{
+ return mavlink_msg_uavionix_adsb_out_cfg_flightid_pack(system_id, component_id, msg, uavionix_adsb_out_cfg_flightid->flight_id);
+}
+
+/**
+ * @brief Encode a uavionix_adsb_out_cfg_flightid 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 uavionix_adsb_out_cfg_flightid C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_uavionix_adsb_out_cfg_flightid_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_uavionix_adsb_out_cfg_flightid_t* uavionix_adsb_out_cfg_flightid)
+{
+ return mavlink_msg_uavionix_adsb_out_cfg_flightid_pack_chan(system_id, component_id, chan, msg, uavionix_adsb_out_cfg_flightid->flight_id);
+}
+
+/**
+ * @brief Encode a uavionix_adsb_out_cfg_flightid 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 uavionix_adsb_out_cfg_flightid C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_uavionix_adsb_out_cfg_flightid_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_uavionix_adsb_out_cfg_flightid_t* uavionix_adsb_out_cfg_flightid)
+{
+ return mavlink_msg_uavionix_adsb_out_cfg_flightid_pack_status(system_id, component_id, _status, msg, uavionix_adsb_out_cfg_flightid->flight_id);
+}
+
+/**
+ * @brief Send a uavionix_adsb_out_cfg_flightid message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param flight_id Flight Identification: 8 ASCII characters, '0' through '9', 'A' through 'Z' or space. Spaces (0x20) used as a trailing pad character, or when call sign is unavailable. Reflects Control message setting. This is null-terminated.
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_uavionix_adsb_out_cfg_flightid_send(mavlink_channel_t chan, const char *flight_id)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_FLIGHTID_LEN];
+
+ _mav_put_char_array(buf, 0, flight_id, 9);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_FLIGHTID, buf, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_FLIGHTID_MIN_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_FLIGHTID_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_FLIGHTID_CRC);
+#else
+ mavlink_uavionix_adsb_out_cfg_flightid_t packet;
+
+ mav_array_assign_char(packet.flight_id, flight_id, 9);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_FLIGHTID, (const char *)&packet, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_FLIGHTID_MIN_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_FLIGHTID_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_FLIGHTID_CRC);
+#endif
+}
+
+/**
+ * @brief Send a uavionix_adsb_out_cfg_flightid message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_uavionix_adsb_out_cfg_flightid_send_struct(mavlink_channel_t chan, const mavlink_uavionix_adsb_out_cfg_flightid_t* uavionix_adsb_out_cfg_flightid)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_uavionix_adsb_out_cfg_flightid_send(chan, uavionix_adsb_out_cfg_flightid->flight_id);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_FLIGHTID, (const char *)uavionix_adsb_out_cfg_flightid, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_FLIGHTID_MIN_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_FLIGHTID_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_FLIGHTID_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_FLIGHTID_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_uavionix_adsb_out_cfg_flightid_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, const char *flight_id)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+
+ _mav_put_char_array(buf, 0, flight_id, 9);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_FLIGHTID, buf, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_FLIGHTID_MIN_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_FLIGHTID_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_FLIGHTID_CRC);
+#else
+ mavlink_uavionix_adsb_out_cfg_flightid_t *packet = (mavlink_uavionix_adsb_out_cfg_flightid_t *)msgbuf;
+
+ mav_array_assign_char(packet->flight_id, flight_id, 9);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_FLIGHTID, (const char *)packet, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_FLIGHTID_MIN_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_FLIGHTID_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_FLIGHTID_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE UAVIONIX_ADSB_OUT_CFG_FLIGHTID UNPACKING
+
+
+/**
+ * @brief Get field flight_id from uavionix_adsb_out_cfg_flightid message
+ *
+ * @return Flight Identification: 8 ASCII characters, '0' through '9', 'A' through 'Z' or space. Spaces (0x20) used as a trailing pad character, or when call sign is unavailable. Reflects Control message setting. This is null-terminated.
+ */
+static inline uint16_t mavlink_msg_uavionix_adsb_out_cfg_flightid_get_flight_id(const mavlink_message_t* msg, char *flight_id)
+{
+ return _MAV_RETURN_char_array(msg, flight_id, 9, 0);
+}
+
+/**
+ * @brief Decode a uavionix_adsb_out_cfg_flightid message into a struct
+ *
+ * @param msg The message to decode
+ * @param uavionix_adsb_out_cfg_flightid C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_uavionix_adsb_out_cfg_flightid_decode(const mavlink_message_t* msg, mavlink_uavionix_adsb_out_cfg_flightid_t* uavionix_adsb_out_cfg_flightid)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_uavionix_adsb_out_cfg_flightid_get_flight_id(msg, uavionix_adsb_out_cfg_flightid->flight_id);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_FLIGHTID_LEN? msg->len : MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_FLIGHTID_LEN;
+ memset(uavionix_adsb_out_cfg_flightid, 0, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_FLIGHTID_LEN);
+ memcpy(uavionix_adsb_out_cfg_flightid, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/uAvionix/mavlink_msg_uavionix_adsb_out_cfg_registration.h b/lib/main/MAVLink/uAvionix/mavlink_msg_uavionix_adsb_out_cfg_registration.h
new file mode 100644
index 00000000000..86ef98a6aff
--- /dev/null
+++ b/lib/main/MAVLink/uAvionix/mavlink_msg_uavionix_adsb_out_cfg_registration.h
@@ -0,0 +1,260 @@
+#pragma once
+// MESSAGE UAVIONIX_ADSB_OUT_CFG_REGISTRATION PACKING
+
+#define MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_REGISTRATION 10004
+
+
+typedef struct __mavlink_uavionix_adsb_out_cfg_registration_t {
+ char registration[9]; /*< Aircraft Registration (ASCII string A-Z, 0-9 only), e.g. "N8644B ". Trailing spaces (0x20) only. This is null-terminated.*/
+} mavlink_uavionix_adsb_out_cfg_registration_t;
+
+#define MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_REGISTRATION_LEN 9
+#define MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_REGISTRATION_MIN_LEN 9
+#define MAVLINK_MSG_ID_10004_LEN 9
+#define MAVLINK_MSG_ID_10004_MIN_LEN 9
+
+#define MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_REGISTRATION_CRC 133
+#define MAVLINK_MSG_ID_10004_CRC 133
+
+#define MAVLINK_MSG_UAVIONIX_ADSB_OUT_CFG_REGISTRATION_FIELD_REGISTRATION_LEN 9
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_UAVIONIX_ADSB_OUT_CFG_REGISTRATION { \
+ 10004, \
+ "UAVIONIX_ADSB_OUT_CFG_REGISTRATION", \
+ 1, \
+ { { "registration", NULL, MAVLINK_TYPE_CHAR, 9, 0, offsetof(mavlink_uavionix_adsb_out_cfg_registration_t, registration) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_UAVIONIX_ADSB_OUT_CFG_REGISTRATION { \
+ "UAVIONIX_ADSB_OUT_CFG_REGISTRATION", \
+ 1, \
+ { { "registration", NULL, MAVLINK_TYPE_CHAR, 9, 0, offsetof(mavlink_uavionix_adsb_out_cfg_registration_t, registration) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a uavionix_adsb_out_cfg_registration 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 registration Aircraft Registration (ASCII string A-Z, 0-9 only), e.g. "N8644B ". Trailing spaces (0x20) only. This is null-terminated.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_uavionix_adsb_out_cfg_registration_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ const char *registration)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_REGISTRATION_LEN];
+
+ _mav_put_char_array(buf, 0, registration, 9);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_REGISTRATION_LEN);
+#else
+ mavlink_uavionix_adsb_out_cfg_registration_t packet;
+
+ mav_array_assign_char(packet.registration, registration, 9);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_REGISTRATION_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_REGISTRATION;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_REGISTRATION_MIN_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_REGISTRATION_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_REGISTRATION_CRC);
+}
+
+/**
+ * @brief Pack a uavionix_adsb_out_cfg_registration 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 registration Aircraft Registration (ASCII string A-Z, 0-9 only), e.g. "N8644B ". Trailing spaces (0x20) only. This is null-terminated.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_uavionix_adsb_out_cfg_registration_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ const char *registration)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_REGISTRATION_LEN];
+
+ _mav_put_char_array(buf, 0, registration, 9);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_REGISTRATION_LEN);
+#else
+ mavlink_uavionix_adsb_out_cfg_registration_t packet;
+
+ mav_array_memcpy(packet.registration, registration, sizeof(char)*9);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_REGISTRATION_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_REGISTRATION;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_REGISTRATION_MIN_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_REGISTRATION_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_REGISTRATION_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_REGISTRATION_MIN_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_REGISTRATION_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a uavionix_adsb_out_cfg_registration 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 registration Aircraft Registration (ASCII string A-Z, 0-9 only), e.g. "N8644B ". Trailing spaces (0x20) only. This is null-terminated.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_uavionix_adsb_out_cfg_registration_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ const char *registration)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_REGISTRATION_LEN];
+
+ _mav_put_char_array(buf, 0, registration, 9);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_REGISTRATION_LEN);
+#else
+ mavlink_uavionix_adsb_out_cfg_registration_t packet;
+
+ mav_array_assign_char(packet.registration, registration, 9);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_REGISTRATION_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_REGISTRATION;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_REGISTRATION_MIN_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_REGISTRATION_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_REGISTRATION_CRC);
+}
+
+/**
+ * @brief Encode a uavionix_adsb_out_cfg_registration 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 uavionix_adsb_out_cfg_registration C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_uavionix_adsb_out_cfg_registration_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_uavionix_adsb_out_cfg_registration_t* uavionix_adsb_out_cfg_registration)
+{
+ return mavlink_msg_uavionix_adsb_out_cfg_registration_pack(system_id, component_id, msg, uavionix_adsb_out_cfg_registration->registration);
+}
+
+/**
+ * @brief Encode a uavionix_adsb_out_cfg_registration 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 uavionix_adsb_out_cfg_registration C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_uavionix_adsb_out_cfg_registration_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_uavionix_adsb_out_cfg_registration_t* uavionix_adsb_out_cfg_registration)
+{
+ return mavlink_msg_uavionix_adsb_out_cfg_registration_pack_chan(system_id, component_id, chan, msg, uavionix_adsb_out_cfg_registration->registration);
+}
+
+/**
+ * @brief Encode a uavionix_adsb_out_cfg_registration 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 uavionix_adsb_out_cfg_registration C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_uavionix_adsb_out_cfg_registration_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_uavionix_adsb_out_cfg_registration_t* uavionix_adsb_out_cfg_registration)
+{
+ return mavlink_msg_uavionix_adsb_out_cfg_registration_pack_status(system_id, component_id, _status, msg, uavionix_adsb_out_cfg_registration->registration);
+}
+
+/**
+ * @brief Send a uavionix_adsb_out_cfg_registration message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param registration Aircraft Registration (ASCII string A-Z, 0-9 only), e.g. "N8644B ". Trailing spaces (0x20) only. This is null-terminated.
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_uavionix_adsb_out_cfg_registration_send(mavlink_channel_t chan, const char *registration)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_REGISTRATION_LEN];
+
+ _mav_put_char_array(buf, 0, registration, 9);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_REGISTRATION, buf, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_REGISTRATION_MIN_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_REGISTRATION_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_REGISTRATION_CRC);
+#else
+ mavlink_uavionix_adsb_out_cfg_registration_t packet;
+
+ mav_array_assign_char(packet.registration, registration, 9);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_REGISTRATION, (const char *)&packet, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_REGISTRATION_MIN_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_REGISTRATION_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_REGISTRATION_CRC);
+#endif
+}
+
+/**
+ * @brief Send a uavionix_adsb_out_cfg_registration message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_uavionix_adsb_out_cfg_registration_send_struct(mavlink_channel_t chan, const mavlink_uavionix_adsb_out_cfg_registration_t* uavionix_adsb_out_cfg_registration)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_uavionix_adsb_out_cfg_registration_send(chan, uavionix_adsb_out_cfg_registration->registration);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_REGISTRATION, (const char *)uavionix_adsb_out_cfg_registration, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_REGISTRATION_MIN_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_REGISTRATION_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_REGISTRATION_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_REGISTRATION_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_uavionix_adsb_out_cfg_registration_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, const char *registration)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+
+ _mav_put_char_array(buf, 0, registration, 9);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_REGISTRATION, buf, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_REGISTRATION_MIN_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_REGISTRATION_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_REGISTRATION_CRC);
+#else
+ mavlink_uavionix_adsb_out_cfg_registration_t *packet = (mavlink_uavionix_adsb_out_cfg_registration_t *)msgbuf;
+
+ mav_array_assign_char(packet->registration, registration, 9);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_REGISTRATION, (const char *)packet, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_REGISTRATION_MIN_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_REGISTRATION_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_REGISTRATION_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE UAVIONIX_ADSB_OUT_CFG_REGISTRATION UNPACKING
+
+
+/**
+ * @brief Get field registration from uavionix_adsb_out_cfg_registration message
+ *
+ * @return Aircraft Registration (ASCII string A-Z, 0-9 only), e.g. "N8644B ". Trailing spaces (0x20) only. This is null-terminated.
+ */
+static inline uint16_t mavlink_msg_uavionix_adsb_out_cfg_registration_get_registration(const mavlink_message_t* msg, char *registration)
+{
+ return _MAV_RETURN_char_array(msg, registration, 9, 0);
+}
+
+/**
+ * @brief Decode a uavionix_adsb_out_cfg_registration message into a struct
+ *
+ * @param msg The message to decode
+ * @param uavionix_adsb_out_cfg_registration C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_uavionix_adsb_out_cfg_registration_decode(const mavlink_message_t* msg, mavlink_uavionix_adsb_out_cfg_registration_t* uavionix_adsb_out_cfg_registration)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_uavionix_adsb_out_cfg_registration_get_registration(msg, uavionix_adsb_out_cfg_registration->registration);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_REGISTRATION_LEN? msg->len : MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_REGISTRATION_LEN;
+ memset(uavionix_adsb_out_cfg_registration, 0, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_REGISTRATION_LEN);
+ memcpy(uavionix_adsb_out_cfg_registration, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/uAvionix/mavlink_msg_uavionix_adsb_out_control.h b/lib/main/MAVLink/uAvionix/mavlink_msg_uavionix_adsb_out_control.h
new file mode 100644
index 00000000000..3dbf60001fc
--- /dev/null
+++ b/lib/main/MAVLink/uAvionix/mavlink_msg_uavionix_adsb_out_control.h
@@ -0,0 +1,390 @@
+#pragma once
+// MESSAGE UAVIONIX_ADSB_OUT_CONTROL PACKING
+
+#define MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CONTROL 10007
+
+
+typedef struct __mavlink_uavionix_adsb_out_control_t {
+ int32_t baroAltMSL; /*< [mbar] Barometric pressure altitude (MSL) relative to a standard atmosphere of 1013.2 mBar and NOT bar corrected altitude (m * 1E-3). (up +ve). If unknown set to INT32_MAX*/
+ uint16_t squawk; /*< Mode A code (typically 1200 [0x04B0] for VFR)*/
+ uint8_t state; /*< ADS-B transponder control state flags*/
+ uint8_t emergencyStatus; /*< Emergency status*/
+ char flight_id[8]; /*< Flight Identification: 8 ASCII characters, '0' through '9', 'A' through 'Z' or space. Spaces (0x20) used as a trailing pad character, or when call sign is unavailable.*/
+ uint8_t x_bit; /*< X-Bit enable (military transponders only)*/
+} mavlink_uavionix_adsb_out_control_t;
+
+#define MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CONTROL_LEN 17
+#define MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CONTROL_MIN_LEN 17
+#define MAVLINK_MSG_ID_10007_LEN 17
+#define MAVLINK_MSG_ID_10007_MIN_LEN 17
+
+#define MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CONTROL_CRC 71
+#define MAVLINK_MSG_ID_10007_CRC 71
+
+#define MAVLINK_MSG_UAVIONIX_ADSB_OUT_CONTROL_FIELD_FLIGHT_ID_LEN 8
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_UAVIONIX_ADSB_OUT_CONTROL { \
+ 10007, \
+ "UAVIONIX_ADSB_OUT_CONTROL", \
+ 6, \
+ { { "state", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_uavionix_adsb_out_control_t, state) }, \
+ { "baroAltMSL", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_uavionix_adsb_out_control_t, baroAltMSL) }, \
+ { "squawk", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_uavionix_adsb_out_control_t, squawk) }, \
+ { "emergencyStatus", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_uavionix_adsb_out_control_t, emergencyStatus) }, \
+ { "flight_id", NULL, MAVLINK_TYPE_CHAR, 8, 8, offsetof(mavlink_uavionix_adsb_out_control_t, flight_id) }, \
+ { "x_bit", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_uavionix_adsb_out_control_t, x_bit) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_UAVIONIX_ADSB_OUT_CONTROL { \
+ "UAVIONIX_ADSB_OUT_CONTROL", \
+ 6, \
+ { { "state", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_uavionix_adsb_out_control_t, state) }, \
+ { "baroAltMSL", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_uavionix_adsb_out_control_t, baroAltMSL) }, \
+ { "squawk", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_uavionix_adsb_out_control_t, squawk) }, \
+ { "emergencyStatus", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_uavionix_adsb_out_control_t, emergencyStatus) }, \
+ { "flight_id", NULL, MAVLINK_TYPE_CHAR, 8, 8, offsetof(mavlink_uavionix_adsb_out_control_t, flight_id) }, \
+ { "x_bit", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_uavionix_adsb_out_control_t, x_bit) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a uavionix_adsb_out_control 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 state ADS-B transponder control state flags
+ * @param baroAltMSL [mbar] Barometric pressure altitude (MSL) relative to a standard atmosphere of 1013.2 mBar and NOT bar corrected altitude (m * 1E-3). (up +ve). If unknown set to INT32_MAX
+ * @param squawk Mode A code (typically 1200 [0x04B0] for VFR)
+ * @param emergencyStatus Emergency status
+ * @param flight_id Flight Identification: 8 ASCII characters, '0' through '9', 'A' through 'Z' or space. Spaces (0x20) used as a trailing pad character, or when call sign is unavailable.
+ * @param x_bit X-Bit enable (military transponders only)
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_uavionix_adsb_out_control_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint8_t state, int32_t baroAltMSL, uint16_t squawk, uint8_t emergencyStatus, const char *flight_id, uint8_t x_bit)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CONTROL_LEN];
+ _mav_put_int32_t(buf, 0, baroAltMSL);
+ _mav_put_uint16_t(buf, 4, squawk);
+ _mav_put_uint8_t(buf, 6, state);
+ _mav_put_uint8_t(buf, 7, emergencyStatus);
+ _mav_put_uint8_t(buf, 16, x_bit);
+ _mav_put_char_array(buf, 8, flight_id, 8);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CONTROL_LEN);
+#else
+ mavlink_uavionix_adsb_out_control_t packet;
+ packet.baroAltMSL = baroAltMSL;
+ packet.squawk = squawk;
+ packet.state = state;
+ packet.emergencyStatus = emergencyStatus;
+ packet.x_bit = x_bit;
+ mav_array_assign_char(packet.flight_id, flight_id, 8);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CONTROL_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CONTROL;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CONTROL_MIN_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CONTROL_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CONTROL_CRC);
+}
+
+/**
+ * @brief Pack a uavionix_adsb_out_control 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 state ADS-B transponder control state flags
+ * @param baroAltMSL [mbar] Barometric pressure altitude (MSL) relative to a standard atmosphere of 1013.2 mBar and NOT bar corrected altitude (m * 1E-3). (up +ve). If unknown set to INT32_MAX
+ * @param squawk Mode A code (typically 1200 [0x04B0] for VFR)
+ * @param emergencyStatus Emergency status
+ * @param flight_id Flight Identification: 8 ASCII characters, '0' through '9', 'A' through 'Z' or space. Spaces (0x20) used as a trailing pad character, or when call sign is unavailable.
+ * @param x_bit X-Bit enable (military transponders only)
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_uavionix_adsb_out_control_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ uint8_t state, int32_t baroAltMSL, uint16_t squawk, uint8_t emergencyStatus, const char *flight_id, uint8_t x_bit)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CONTROL_LEN];
+ _mav_put_int32_t(buf, 0, baroAltMSL);
+ _mav_put_uint16_t(buf, 4, squawk);
+ _mav_put_uint8_t(buf, 6, state);
+ _mav_put_uint8_t(buf, 7, emergencyStatus);
+ _mav_put_uint8_t(buf, 16, x_bit);
+ _mav_put_char_array(buf, 8, flight_id, 8);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CONTROL_LEN);
+#else
+ mavlink_uavionix_adsb_out_control_t packet;
+ packet.baroAltMSL = baroAltMSL;
+ packet.squawk = squawk;
+ packet.state = state;
+ packet.emergencyStatus = emergencyStatus;
+ packet.x_bit = x_bit;
+ mav_array_memcpy(packet.flight_id, flight_id, sizeof(char)*8);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CONTROL_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CONTROL;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CONTROL_MIN_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CONTROL_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CONTROL_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CONTROL_MIN_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CONTROL_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a uavionix_adsb_out_control 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 state ADS-B transponder control state flags
+ * @param baroAltMSL [mbar] Barometric pressure altitude (MSL) relative to a standard atmosphere of 1013.2 mBar and NOT bar corrected altitude (m * 1E-3). (up +ve). If unknown set to INT32_MAX
+ * @param squawk Mode A code (typically 1200 [0x04B0] for VFR)
+ * @param emergencyStatus Emergency status
+ * @param flight_id Flight Identification: 8 ASCII characters, '0' through '9', 'A' through 'Z' or space. Spaces (0x20) used as a trailing pad character, or when call sign is unavailable.
+ * @param x_bit X-Bit enable (military transponders only)
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_uavionix_adsb_out_control_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint8_t state,int32_t baroAltMSL,uint16_t squawk,uint8_t emergencyStatus,const char *flight_id,uint8_t x_bit)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CONTROL_LEN];
+ _mav_put_int32_t(buf, 0, baroAltMSL);
+ _mav_put_uint16_t(buf, 4, squawk);
+ _mav_put_uint8_t(buf, 6, state);
+ _mav_put_uint8_t(buf, 7, emergencyStatus);
+ _mav_put_uint8_t(buf, 16, x_bit);
+ _mav_put_char_array(buf, 8, flight_id, 8);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CONTROL_LEN);
+#else
+ mavlink_uavionix_adsb_out_control_t packet;
+ packet.baroAltMSL = baroAltMSL;
+ packet.squawk = squawk;
+ packet.state = state;
+ packet.emergencyStatus = emergencyStatus;
+ packet.x_bit = x_bit;
+ mav_array_assign_char(packet.flight_id, flight_id, 8);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CONTROL_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CONTROL;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CONTROL_MIN_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CONTROL_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CONTROL_CRC);
+}
+
+/**
+ * @brief Encode a uavionix_adsb_out_control 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 uavionix_adsb_out_control C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_uavionix_adsb_out_control_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_uavionix_adsb_out_control_t* uavionix_adsb_out_control)
+{
+ return mavlink_msg_uavionix_adsb_out_control_pack(system_id, component_id, msg, uavionix_adsb_out_control->state, uavionix_adsb_out_control->baroAltMSL, uavionix_adsb_out_control->squawk, uavionix_adsb_out_control->emergencyStatus, uavionix_adsb_out_control->flight_id, uavionix_adsb_out_control->x_bit);
+}
+
+/**
+ * @brief Encode a uavionix_adsb_out_control 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 uavionix_adsb_out_control C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_uavionix_adsb_out_control_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_uavionix_adsb_out_control_t* uavionix_adsb_out_control)
+{
+ return mavlink_msg_uavionix_adsb_out_control_pack_chan(system_id, component_id, chan, msg, uavionix_adsb_out_control->state, uavionix_adsb_out_control->baroAltMSL, uavionix_adsb_out_control->squawk, uavionix_adsb_out_control->emergencyStatus, uavionix_adsb_out_control->flight_id, uavionix_adsb_out_control->x_bit);
+}
+
+/**
+ * @brief Encode a uavionix_adsb_out_control 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 uavionix_adsb_out_control C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_uavionix_adsb_out_control_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_uavionix_adsb_out_control_t* uavionix_adsb_out_control)
+{
+ return mavlink_msg_uavionix_adsb_out_control_pack_status(system_id, component_id, _status, msg, uavionix_adsb_out_control->state, uavionix_adsb_out_control->baroAltMSL, uavionix_adsb_out_control->squawk, uavionix_adsb_out_control->emergencyStatus, uavionix_adsb_out_control->flight_id, uavionix_adsb_out_control->x_bit);
+}
+
+/**
+ * @brief Send a uavionix_adsb_out_control message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param state ADS-B transponder control state flags
+ * @param baroAltMSL [mbar] Barometric pressure altitude (MSL) relative to a standard atmosphere of 1013.2 mBar and NOT bar corrected altitude (m * 1E-3). (up +ve). If unknown set to INT32_MAX
+ * @param squawk Mode A code (typically 1200 [0x04B0] for VFR)
+ * @param emergencyStatus Emergency status
+ * @param flight_id Flight Identification: 8 ASCII characters, '0' through '9', 'A' through 'Z' or space. Spaces (0x20) used as a trailing pad character, or when call sign is unavailable.
+ * @param x_bit X-Bit enable (military transponders only)
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_uavionix_adsb_out_control_send(mavlink_channel_t chan, uint8_t state, int32_t baroAltMSL, uint16_t squawk, uint8_t emergencyStatus, const char *flight_id, uint8_t x_bit)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CONTROL_LEN];
+ _mav_put_int32_t(buf, 0, baroAltMSL);
+ _mav_put_uint16_t(buf, 4, squawk);
+ _mav_put_uint8_t(buf, 6, state);
+ _mav_put_uint8_t(buf, 7, emergencyStatus);
+ _mav_put_uint8_t(buf, 16, x_bit);
+ _mav_put_char_array(buf, 8, flight_id, 8);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CONTROL, buf, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CONTROL_MIN_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CONTROL_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CONTROL_CRC);
+#else
+ mavlink_uavionix_adsb_out_control_t packet;
+ packet.baroAltMSL = baroAltMSL;
+ packet.squawk = squawk;
+ packet.state = state;
+ packet.emergencyStatus = emergencyStatus;
+ packet.x_bit = x_bit;
+ mav_array_assign_char(packet.flight_id, flight_id, 8);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CONTROL, (const char *)&packet, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CONTROL_MIN_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CONTROL_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CONTROL_CRC);
+#endif
+}
+
+/**
+ * @brief Send a uavionix_adsb_out_control message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_uavionix_adsb_out_control_send_struct(mavlink_channel_t chan, const mavlink_uavionix_adsb_out_control_t* uavionix_adsb_out_control)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_uavionix_adsb_out_control_send(chan, uavionix_adsb_out_control->state, uavionix_adsb_out_control->baroAltMSL, uavionix_adsb_out_control->squawk, uavionix_adsb_out_control->emergencyStatus, uavionix_adsb_out_control->flight_id, uavionix_adsb_out_control->x_bit);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CONTROL, (const char *)uavionix_adsb_out_control, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CONTROL_MIN_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CONTROL_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CONTROL_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CONTROL_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_uavionix_adsb_out_control_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t state, int32_t baroAltMSL, uint16_t squawk, uint8_t emergencyStatus, const char *flight_id, uint8_t x_bit)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_int32_t(buf, 0, baroAltMSL);
+ _mav_put_uint16_t(buf, 4, squawk);
+ _mav_put_uint8_t(buf, 6, state);
+ _mav_put_uint8_t(buf, 7, emergencyStatus);
+ _mav_put_uint8_t(buf, 16, x_bit);
+ _mav_put_char_array(buf, 8, flight_id, 8);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CONTROL, buf, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CONTROL_MIN_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CONTROL_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CONTROL_CRC);
+#else
+ mavlink_uavionix_adsb_out_control_t *packet = (mavlink_uavionix_adsb_out_control_t *)msgbuf;
+ packet->baroAltMSL = baroAltMSL;
+ packet->squawk = squawk;
+ packet->state = state;
+ packet->emergencyStatus = emergencyStatus;
+ packet->x_bit = x_bit;
+ mav_array_assign_char(packet->flight_id, flight_id, 8);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CONTROL, (const char *)packet, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CONTROL_MIN_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CONTROL_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CONTROL_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE UAVIONIX_ADSB_OUT_CONTROL UNPACKING
+
+
+/**
+ * @brief Get field state from uavionix_adsb_out_control message
+ *
+ * @return ADS-B transponder control state flags
+ */
+static inline uint8_t mavlink_msg_uavionix_adsb_out_control_get_state(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 6);
+}
+
+/**
+ * @brief Get field baroAltMSL from uavionix_adsb_out_control message
+ *
+ * @return [mbar] Barometric pressure altitude (MSL) relative to a standard atmosphere of 1013.2 mBar and NOT bar corrected altitude (m * 1E-3). (up +ve). If unknown set to INT32_MAX
+ */
+static inline int32_t mavlink_msg_uavionix_adsb_out_control_get_baroAltMSL(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_int32_t(msg, 0);
+}
+
+/**
+ * @brief Get field squawk from uavionix_adsb_out_control message
+ *
+ * @return Mode A code (typically 1200 [0x04B0] for VFR)
+ */
+static inline uint16_t mavlink_msg_uavionix_adsb_out_control_get_squawk(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 4);
+}
+
+/**
+ * @brief Get field emergencyStatus from uavionix_adsb_out_control message
+ *
+ * @return Emergency status
+ */
+static inline uint8_t mavlink_msg_uavionix_adsb_out_control_get_emergencyStatus(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 7);
+}
+
+/**
+ * @brief Get field flight_id from uavionix_adsb_out_control message
+ *
+ * @return Flight Identification: 8 ASCII characters, '0' through '9', 'A' through 'Z' or space. Spaces (0x20) used as a trailing pad character, or when call sign is unavailable.
+ */
+static inline uint16_t mavlink_msg_uavionix_adsb_out_control_get_flight_id(const mavlink_message_t* msg, char *flight_id)
+{
+ return _MAV_RETURN_char_array(msg, flight_id, 8, 8);
+}
+
+/**
+ * @brief Get field x_bit from uavionix_adsb_out_control message
+ *
+ * @return X-Bit enable (military transponders only)
+ */
+static inline uint8_t mavlink_msg_uavionix_adsb_out_control_get_x_bit(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 16);
+}
+
+/**
+ * @brief Decode a uavionix_adsb_out_control message into a struct
+ *
+ * @param msg The message to decode
+ * @param uavionix_adsb_out_control C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_uavionix_adsb_out_control_decode(const mavlink_message_t* msg, mavlink_uavionix_adsb_out_control_t* uavionix_adsb_out_control)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ uavionix_adsb_out_control->baroAltMSL = mavlink_msg_uavionix_adsb_out_control_get_baroAltMSL(msg);
+ uavionix_adsb_out_control->squawk = mavlink_msg_uavionix_adsb_out_control_get_squawk(msg);
+ uavionix_adsb_out_control->state = mavlink_msg_uavionix_adsb_out_control_get_state(msg);
+ uavionix_adsb_out_control->emergencyStatus = mavlink_msg_uavionix_adsb_out_control_get_emergencyStatus(msg);
+ mavlink_msg_uavionix_adsb_out_control_get_flight_id(msg, uavionix_adsb_out_control->flight_id);
+ uavionix_adsb_out_control->x_bit = mavlink_msg_uavionix_adsb_out_control_get_x_bit(msg);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CONTROL_LEN? msg->len : MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CONTROL_LEN;
+ memset(uavionix_adsb_out_control, 0, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CONTROL_LEN);
+ memcpy(uavionix_adsb_out_control, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/uAvionix/mavlink_msg_uavionix_adsb_out_dynamic.h b/lib/main/MAVLink/uAvionix/mavlink_msg_uavionix_adsb_out_dynamic.h
new file mode 100644
index 00000000000..7323b526deb
--- /dev/null
+++ b/lib/main/MAVLink/uAvionix/mavlink_msg_uavionix_adsb_out_dynamic.h
@@ -0,0 +1,680 @@
+#pragma once
+// MESSAGE UAVIONIX_ADSB_OUT_DYNAMIC PACKING
+
+#define MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_DYNAMIC 10002
+
+
+typedef struct __mavlink_uavionix_adsb_out_dynamic_t {
+ uint32_t utcTime; /*< [s] UTC time in seconds since GPS epoch (Jan 6, 1980). If unknown set to UINT32_MAX*/
+ int32_t gpsLat; /*< [degE7] Latitude WGS84 (deg * 1E7). If unknown set to INT32_MAX*/
+ int32_t gpsLon; /*< [degE7] Longitude WGS84 (deg * 1E7). If unknown set to INT32_MAX*/
+ int32_t gpsAlt; /*< [mm] Altitude (WGS84). UP +ve. If unknown set to INT32_MAX*/
+ int32_t baroAltMSL; /*< [mbar] Barometric pressure altitude (MSL) relative to a standard atmosphere of 1013.2 mBar and NOT bar corrected altitude (m * 1E-3). (up +ve). If unknown set to INT32_MAX*/
+ uint32_t accuracyHor; /*< [mm] Horizontal accuracy in mm (m * 1E-3). If unknown set to UINT32_MAX*/
+ uint16_t accuracyVert; /*< [cm] Vertical accuracy in cm. If unknown set to UINT16_MAX*/
+ uint16_t accuracyVel; /*< [mm/s] Velocity accuracy in mm/s (m * 1E-3). If unknown set to UINT16_MAX*/
+ int16_t velVert; /*< [cm/s] GPS vertical speed in cm/s. If unknown set to INT16_MAX*/
+ int16_t velNS; /*< [cm/s] North-South velocity over ground in cm/s North +ve. If unknown set to INT16_MAX*/
+ int16_t VelEW; /*< [cm/s] East-West velocity over ground in cm/s East +ve. If unknown set to INT16_MAX*/
+ uint16_t state; /*< ADS-B transponder dynamic input state flags*/
+ uint16_t squawk; /*< Mode A code (typically 1200 [0x04B0] for VFR)*/
+ uint8_t gpsFix; /*< 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS, 5: RTK*/
+ uint8_t numSats; /*< Number of satellites visible. If unknown set to UINT8_MAX*/
+ uint8_t emergencyStatus; /*< Emergency status*/
+} mavlink_uavionix_adsb_out_dynamic_t;
+
+#define MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_DYNAMIC_LEN 41
+#define MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_DYNAMIC_MIN_LEN 41
+#define MAVLINK_MSG_ID_10002_LEN 41
+#define MAVLINK_MSG_ID_10002_MIN_LEN 41
+
+#define MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_DYNAMIC_CRC 186
+#define MAVLINK_MSG_ID_10002_CRC 186
+
+
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_UAVIONIX_ADSB_OUT_DYNAMIC { \
+ 10002, \
+ "UAVIONIX_ADSB_OUT_DYNAMIC", \
+ 16, \
+ { { "utcTime", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_uavionix_adsb_out_dynamic_t, utcTime) }, \
+ { "gpsLat", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_uavionix_adsb_out_dynamic_t, gpsLat) }, \
+ { "gpsLon", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_uavionix_adsb_out_dynamic_t, gpsLon) }, \
+ { "gpsAlt", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_uavionix_adsb_out_dynamic_t, gpsAlt) }, \
+ { "gpsFix", NULL, MAVLINK_TYPE_UINT8_T, 0, 38, offsetof(mavlink_uavionix_adsb_out_dynamic_t, gpsFix) }, \
+ { "numSats", NULL, MAVLINK_TYPE_UINT8_T, 0, 39, offsetof(mavlink_uavionix_adsb_out_dynamic_t, numSats) }, \
+ { "baroAltMSL", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_uavionix_adsb_out_dynamic_t, baroAltMSL) }, \
+ { "accuracyHor", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_uavionix_adsb_out_dynamic_t, accuracyHor) }, \
+ { "accuracyVert", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_uavionix_adsb_out_dynamic_t, accuracyVert) }, \
+ { "accuracyVel", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_uavionix_adsb_out_dynamic_t, accuracyVel) }, \
+ { "velVert", NULL, MAVLINK_TYPE_INT16_T, 0, 28, offsetof(mavlink_uavionix_adsb_out_dynamic_t, velVert) }, \
+ { "velNS", NULL, MAVLINK_TYPE_INT16_T, 0, 30, offsetof(mavlink_uavionix_adsb_out_dynamic_t, velNS) }, \
+ { "VelEW", NULL, MAVLINK_TYPE_INT16_T, 0, 32, offsetof(mavlink_uavionix_adsb_out_dynamic_t, VelEW) }, \
+ { "emergencyStatus", NULL, MAVLINK_TYPE_UINT8_T, 0, 40, offsetof(mavlink_uavionix_adsb_out_dynamic_t, emergencyStatus) }, \
+ { "state", NULL, MAVLINK_TYPE_UINT16_T, 0, 34, offsetof(mavlink_uavionix_adsb_out_dynamic_t, state) }, \
+ { "squawk", NULL, MAVLINK_TYPE_UINT16_T, 0, 36, offsetof(mavlink_uavionix_adsb_out_dynamic_t, squawk) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_UAVIONIX_ADSB_OUT_DYNAMIC { \
+ "UAVIONIX_ADSB_OUT_DYNAMIC", \
+ 16, \
+ { { "utcTime", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_uavionix_adsb_out_dynamic_t, utcTime) }, \
+ { "gpsLat", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_uavionix_adsb_out_dynamic_t, gpsLat) }, \
+ { "gpsLon", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_uavionix_adsb_out_dynamic_t, gpsLon) }, \
+ { "gpsAlt", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_uavionix_adsb_out_dynamic_t, gpsAlt) }, \
+ { "gpsFix", NULL, MAVLINK_TYPE_UINT8_T, 0, 38, offsetof(mavlink_uavionix_adsb_out_dynamic_t, gpsFix) }, \
+ { "numSats", NULL, MAVLINK_TYPE_UINT8_T, 0, 39, offsetof(mavlink_uavionix_adsb_out_dynamic_t, numSats) }, \
+ { "baroAltMSL", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_uavionix_adsb_out_dynamic_t, baroAltMSL) }, \
+ { "accuracyHor", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_uavionix_adsb_out_dynamic_t, accuracyHor) }, \
+ { "accuracyVert", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_uavionix_adsb_out_dynamic_t, accuracyVert) }, \
+ { "accuracyVel", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_uavionix_adsb_out_dynamic_t, accuracyVel) }, \
+ { "velVert", NULL, MAVLINK_TYPE_INT16_T, 0, 28, offsetof(mavlink_uavionix_adsb_out_dynamic_t, velVert) }, \
+ { "velNS", NULL, MAVLINK_TYPE_INT16_T, 0, 30, offsetof(mavlink_uavionix_adsb_out_dynamic_t, velNS) }, \
+ { "VelEW", NULL, MAVLINK_TYPE_INT16_T, 0, 32, offsetof(mavlink_uavionix_adsb_out_dynamic_t, VelEW) }, \
+ { "emergencyStatus", NULL, MAVLINK_TYPE_UINT8_T, 0, 40, offsetof(mavlink_uavionix_adsb_out_dynamic_t, emergencyStatus) }, \
+ { "state", NULL, MAVLINK_TYPE_UINT16_T, 0, 34, offsetof(mavlink_uavionix_adsb_out_dynamic_t, state) }, \
+ { "squawk", NULL, MAVLINK_TYPE_UINT16_T, 0, 36, offsetof(mavlink_uavionix_adsb_out_dynamic_t, squawk) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a uavionix_adsb_out_dynamic 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 utcTime [s] UTC time in seconds since GPS epoch (Jan 6, 1980). If unknown set to UINT32_MAX
+ * @param gpsLat [degE7] Latitude WGS84 (deg * 1E7). If unknown set to INT32_MAX
+ * @param gpsLon [degE7] Longitude WGS84 (deg * 1E7). If unknown set to INT32_MAX
+ * @param gpsAlt [mm] Altitude (WGS84). UP +ve. If unknown set to INT32_MAX
+ * @param gpsFix 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS, 5: RTK
+ * @param numSats Number of satellites visible. If unknown set to UINT8_MAX
+ * @param baroAltMSL [mbar] Barometric pressure altitude (MSL) relative to a standard atmosphere of 1013.2 mBar and NOT bar corrected altitude (m * 1E-3). (up +ve). If unknown set to INT32_MAX
+ * @param accuracyHor [mm] Horizontal accuracy in mm (m * 1E-3). If unknown set to UINT32_MAX
+ * @param accuracyVert [cm] Vertical accuracy in cm. If unknown set to UINT16_MAX
+ * @param accuracyVel [mm/s] Velocity accuracy in mm/s (m * 1E-3). If unknown set to UINT16_MAX
+ * @param velVert [cm/s] GPS vertical speed in cm/s. If unknown set to INT16_MAX
+ * @param velNS [cm/s] North-South velocity over ground in cm/s North +ve. If unknown set to INT16_MAX
+ * @param VelEW [cm/s] East-West velocity over ground in cm/s East +ve. If unknown set to INT16_MAX
+ * @param emergencyStatus Emergency status
+ * @param state ADS-B transponder dynamic input state flags
+ * @param squawk Mode A code (typically 1200 [0x04B0] for VFR)
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_uavionix_adsb_out_dynamic_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint32_t utcTime, int32_t gpsLat, int32_t gpsLon, int32_t gpsAlt, uint8_t gpsFix, uint8_t numSats, int32_t baroAltMSL, uint32_t accuracyHor, uint16_t accuracyVert, uint16_t accuracyVel, int16_t velVert, int16_t velNS, int16_t VelEW, uint8_t emergencyStatus, uint16_t state, uint16_t squawk)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_DYNAMIC_LEN];
+ _mav_put_uint32_t(buf, 0, utcTime);
+ _mav_put_int32_t(buf, 4, gpsLat);
+ _mav_put_int32_t(buf, 8, gpsLon);
+ _mav_put_int32_t(buf, 12, gpsAlt);
+ _mav_put_int32_t(buf, 16, baroAltMSL);
+ _mav_put_uint32_t(buf, 20, accuracyHor);
+ _mav_put_uint16_t(buf, 24, accuracyVert);
+ _mav_put_uint16_t(buf, 26, accuracyVel);
+ _mav_put_int16_t(buf, 28, velVert);
+ _mav_put_int16_t(buf, 30, velNS);
+ _mav_put_int16_t(buf, 32, VelEW);
+ _mav_put_uint16_t(buf, 34, state);
+ _mav_put_uint16_t(buf, 36, squawk);
+ _mav_put_uint8_t(buf, 38, gpsFix);
+ _mav_put_uint8_t(buf, 39, numSats);
+ _mav_put_uint8_t(buf, 40, emergencyStatus);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_DYNAMIC_LEN);
+#else
+ mavlink_uavionix_adsb_out_dynamic_t packet;
+ packet.utcTime = utcTime;
+ packet.gpsLat = gpsLat;
+ packet.gpsLon = gpsLon;
+ packet.gpsAlt = gpsAlt;
+ packet.baroAltMSL = baroAltMSL;
+ packet.accuracyHor = accuracyHor;
+ packet.accuracyVert = accuracyVert;
+ packet.accuracyVel = accuracyVel;
+ packet.velVert = velVert;
+ packet.velNS = velNS;
+ packet.VelEW = VelEW;
+ packet.state = state;
+ packet.squawk = squawk;
+ packet.gpsFix = gpsFix;
+ packet.numSats = numSats;
+ packet.emergencyStatus = emergencyStatus;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_DYNAMIC_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_DYNAMIC;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_DYNAMIC_MIN_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_DYNAMIC_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_DYNAMIC_CRC);
+}
+
+/**
+ * @brief Pack a uavionix_adsb_out_dynamic 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 utcTime [s] UTC time in seconds since GPS epoch (Jan 6, 1980). If unknown set to UINT32_MAX
+ * @param gpsLat [degE7] Latitude WGS84 (deg * 1E7). If unknown set to INT32_MAX
+ * @param gpsLon [degE7] Longitude WGS84 (deg * 1E7). If unknown set to INT32_MAX
+ * @param gpsAlt [mm] Altitude (WGS84). UP +ve. If unknown set to INT32_MAX
+ * @param gpsFix 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS, 5: RTK
+ * @param numSats Number of satellites visible. If unknown set to UINT8_MAX
+ * @param baroAltMSL [mbar] Barometric pressure altitude (MSL) relative to a standard atmosphere of 1013.2 mBar and NOT bar corrected altitude (m * 1E-3). (up +ve). If unknown set to INT32_MAX
+ * @param accuracyHor [mm] Horizontal accuracy in mm (m * 1E-3). If unknown set to UINT32_MAX
+ * @param accuracyVert [cm] Vertical accuracy in cm. If unknown set to UINT16_MAX
+ * @param accuracyVel [mm/s] Velocity accuracy in mm/s (m * 1E-3). If unknown set to UINT16_MAX
+ * @param velVert [cm/s] GPS vertical speed in cm/s. If unknown set to INT16_MAX
+ * @param velNS [cm/s] North-South velocity over ground in cm/s North +ve. If unknown set to INT16_MAX
+ * @param VelEW [cm/s] East-West velocity over ground in cm/s East +ve. If unknown set to INT16_MAX
+ * @param emergencyStatus Emergency status
+ * @param state ADS-B transponder dynamic input state flags
+ * @param squawk Mode A code (typically 1200 [0x04B0] for VFR)
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_uavionix_adsb_out_dynamic_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ uint32_t utcTime, int32_t gpsLat, int32_t gpsLon, int32_t gpsAlt, uint8_t gpsFix, uint8_t numSats, int32_t baroAltMSL, uint32_t accuracyHor, uint16_t accuracyVert, uint16_t accuracyVel, int16_t velVert, int16_t velNS, int16_t VelEW, uint8_t emergencyStatus, uint16_t state, uint16_t squawk)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_DYNAMIC_LEN];
+ _mav_put_uint32_t(buf, 0, utcTime);
+ _mav_put_int32_t(buf, 4, gpsLat);
+ _mav_put_int32_t(buf, 8, gpsLon);
+ _mav_put_int32_t(buf, 12, gpsAlt);
+ _mav_put_int32_t(buf, 16, baroAltMSL);
+ _mav_put_uint32_t(buf, 20, accuracyHor);
+ _mav_put_uint16_t(buf, 24, accuracyVert);
+ _mav_put_uint16_t(buf, 26, accuracyVel);
+ _mav_put_int16_t(buf, 28, velVert);
+ _mav_put_int16_t(buf, 30, velNS);
+ _mav_put_int16_t(buf, 32, VelEW);
+ _mav_put_uint16_t(buf, 34, state);
+ _mav_put_uint16_t(buf, 36, squawk);
+ _mav_put_uint8_t(buf, 38, gpsFix);
+ _mav_put_uint8_t(buf, 39, numSats);
+ _mav_put_uint8_t(buf, 40, emergencyStatus);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_DYNAMIC_LEN);
+#else
+ mavlink_uavionix_adsb_out_dynamic_t packet;
+ packet.utcTime = utcTime;
+ packet.gpsLat = gpsLat;
+ packet.gpsLon = gpsLon;
+ packet.gpsAlt = gpsAlt;
+ packet.baroAltMSL = baroAltMSL;
+ packet.accuracyHor = accuracyHor;
+ packet.accuracyVert = accuracyVert;
+ packet.accuracyVel = accuracyVel;
+ packet.velVert = velVert;
+ packet.velNS = velNS;
+ packet.VelEW = VelEW;
+ packet.state = state;
+ packet.squawk = squawk;
+ packet.gpsFix = gpsFix;
+ packet.numSats = numSats;
+ packet.emergencyStatus = emergencyStatus;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_DYNAMIC_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_DYNAMIC;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_DYNAMIC_MIN_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_DYNAMIC_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_DYNAMIC_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_DYNAMIC_MIN_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_DYNAMIC_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a uavionix_adsb_out_dynamic 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 utcTime [s] UTC time in seconds since GPS epoch (Jan 6, 1980). If unknown set to UINT32_MAX
+ * @param gpsLat [degE7] Latitude WGS84 (deg * 1E7). If unknown set to INT32_MAX
+ * @param gpsLon [degE7] Longitude WGS84 (deg * 1E7). If unknown set to INT32_MAX
+ * @param gpsAlt [mm] Altitude (WGS84). UP +ve. If unknown set to INT32_MAX
+ * @param gpsFix 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS, 5: RTK
+ * @param numSats Number of satellites visible. If unknown set to UINT8_MAX
+ * @param baroAltMSL [mbar] Barometric pressure altitude (MSL) relative to a standard atmosphere of 1013.2 mBar and NOT bar corrected altitude (m * 1E-3). (up +ve). If unknown set to INT32_MAX
+ * @param accuracyHor [mm] Horizontal accuracy in mm (m * 1E-3). If unknown set to UINT32_MAX
+ * @param accuracyVert [cm] Vertical accuracy in cm. If unknown set to UINT16_MAX
+ * @param accuracyVel [mm/s] Velocity accuracy in mm/s (m * 1E-3). If unknown set to UINT16_MAX
+ * @param velVert [cm/s] GPS vertical speed in cm/s. If unknown set to INT16_MAX
+ * @param velNS [cm/s] North-South velocity over ground in cm/s North +ve. If unknown set to INT16_MAX
+ * @param VelEW [cm/s] East-West velocity over ground in cm/s East +ve. If unknown set to INT16_MAX
+ * @param emergencyStatus Emergency status
+ * @param state ADS-B transponder dynamic input state flags
+ * @param squawk Mode A code (typically 1200 [0x04B0] for VFR)
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_uavionix_adsb_out_dynamic_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint32_t utcTime,int32_t gpsLat,int32_t gpsLon,int32_t gpsAlt,uint8_t gpsFix,uint8_t numSats,int32_t baroAltMSL,uint32_t accuracyHor,uint16_t accuracyVert,uint16_t accuracyVel,int16_t velVert,int16_t velNS,int16_t VelEW,uint8_t emergencyStatus,uint16_t state,uint16_t squawk)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_DYNAMIC_LEN];
+ _mav_put_uint32_t(buf, 0, utcTime);
+ _mav_put_int32_t(buf, 4, gpsLat);
+ _mav_put_int32_t(buf, 8, gpsLon);
+ _mav_put_int32_t(buf, 12, gpsAlt);
+ _mav_put_int32_t(buf, 16, baroAltMSL);
+ _mav_put_uint32_t(buf, 20, accuracyHor);
+ _mav_put_uint16_t(buf, 24, accuracyVert);
+ _mav_put_uint16_t(buf, 26, accuracyVel);
+ _mav_put_int16_t(buf, 28, velVert);
+ _mav_put_int16_t(buf, 30, velNS);
+ _mav_put_int16_t(buf, 32, VelEW);
+ _mav_put_uint16_t(buf, 34, state);
+ _mav_put_uint16_t(buf, 36, squawk);
+ _mav_put_uint8_t(buf, 38, gpsFix);
+ _mav_put_uint8_t(buf, 39, numSats);
+ _mav_put_uint8_t(buf, 40, emergencyStatus);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_DYNAMIC_LEN);
+#else
+ mavlink_uavionix_adsb_out_dynamic_t packet;
+ packet.utcTime = utcTime;
+ packet.gpsLat = gpsLat;
+ packet.gpsLon = gpsLon;
+ packet.gpsAlt = gpsAlt;
+ packet.baroAltMSL = baroAltMSL;
+ packet.accuracyHor = accuracyHor;
+ packet.accuracyVert = accuracyVert;
+ packet.accuracyVel = accuracyVel;
+ packet.velVert = velVert;
+ packet.velNS = velNS;
+ packet.VelEW = VelEW;
+ packet.state = state;
+ packet.squawk = squawk;
+ packet.gpsFix = gpsFix;
+ packet.numSats = numSats;
+ packet.emergencyStatus = emergencyStatus;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_DYNAMIC_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_DYNAMIC;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_DYNAMIC_MIN_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_DYNAMIC_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_DYNAMIC_CRC);
+}
+
+/**
+ * @brief Encode a uavionix_adsb_out_dynamic 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 uavionix_adsb_out_dynamic C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_uavionix_adsb_out_dynamic_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_uavionix_adsb_out_dynamic_t* uavionix_adsb_out_dynamic)
+{
+ return mavlink_msg_uavionix_adsb_out_dynamic_pack(system_id, component_id, msg, uavionix_adsb_out_dynamic->utcTime, uavionix_adsb_out_dynamic->gpsLat, uavionix_adsb_out_dynamic->gpsLon, uavionix_adsb_out_dynamic->gpsAlt, uavionix_adsb_out_dynamic->gpsFix, uavionix_adsb_out_dynamic->numSats, uavionix_adsb_out_dynamic->baroAltMSL, uavionix_adsb_out_dynamic->accuracyHor, uavionix_adsb_out_dynamic->accuracyVert, uavionix_adsb_out_dynamic->accuracyVel, uavionix_adsb_out_dynamic->velVert, uavionix_adsb_out_dynamic->velNS, uavionix_adsb_out_dynamic->VelEW, uavionix_adsb_out_dynamic->emergencyStatus, uavionix_adsb_out_dynamic->state, uavionix_adsb_out_dynamic->squawk);
+}
+
+/**
+ * @brief Encode a uavionix_adsb_out_dynamic 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 uavionix_adsb_out_dynamic C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_uavionix_adsb_out_dynamic_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_uavionix_adsb_out_dynamic_t* uavionix_adsb_out_dynamic)
+{
+ return mavlink_msg_uavionix_adsb_out_dynamic_pack_chan(system_id, component_id, chan, msg, uavionix_adsb_out_dynamic->utcTime, uavionix_adsb_out_dynamic->gpsLat, uavionix_adsb_out_dynamic->gpsLon, uavionix_adsb_out_dynamic->gpsAlt, uavionix_adsb_out_dynamic->gpsFix, uavionix_adsb_out_dynamic->numSats, uavionix_adsb_out_dynamic->baroAltMSL, uavionix_adsb_out_dynamic->accuracyHor, uavionix_adsb_out_dynamic->accuracyVert, uavionix_adsb_out_dynamic->accuracyVel, uavionix_adsb_out_dynamic->velVert, uavionix_adsb_out_dynamic->velNS, uavionix_adsb_out_dynamic->VelEW, uavionix_adsb_out_dynamic->emergencyStatus, uavionix_adsb_out_dynamic->state, uavionix_adsb_out_dynamic->squawk);
+}
+
+/**
+ * @brief Encode a uavionix_adsb_out_dynamic 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 uavionix_adsb_out_dynamic C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_uavionix_adsb_out_dynamic_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_uavionix_adsb_out_dynamic_t* uavionix_adsb_out_dynamic)
+{
+ return mavlink_msg_uavionix_adsb_out_dynamic_pack_status(system_id, component_id, _status, msg, uavionix_adsb_out_dynamic->utcTime, uavionix_adsb_out_dynamic->gpsLat, uavionix_adsb_out_dynamic->gpsLon, uavionix_adsb_out_dynamic->gpsAlt, uavionix_adsb_out_dynamic->gpsFix, uavionix_adsb_out_dynamic->numSats, uavionix_adsb_out_dynamic->baroAltMSL, uavionix_adsb_out_dynamic->accuracyHor, uavionix_adsb_out_dynamic->accuracyVert, uavionix_adsb_out_dynamic->accuracyVel, uavionix_adsb_out_dynamic->velVert, uavionix_adsb_out_dynamic->velNS, uavionix_adsb_out_dynamic->VelEW, uavionix_adsb_out_dynamic->emergencyStatus, uavionix_adsb_out_dynamic->state, uavionix_adsb_out_dynamic->squawk);
+}
+
+/**
+ * @brief Send a uavionix_adsb_out_dynamic message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param utcTime [s] UTC time in seconds since GPS epoch (Jan 6, 1980). If unknown set to UINT32_MAX
+ * @param gpsLat [degE7] Latitude WGS84 (deg * 1E7). If unknown set to INT32_MAX
+ * @param gpsLon [degE7] Longitude WGS84 (deg * 1E7). If unknown set to INT32_MAX
+ * @param gpsAlt [mm] Altitude (WGS84). UP +ve. If unknown set to INT32_MAX
+ * @param gpsFix 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS, 5: RTK
+ * @param numSats Number of satellites visible. If unknown set to UINT8_MAX
+ * @param baroAltMSL [mbar] Barometric pressure altitude (MSL) relative to a standard atmosphere of 1013.2 mBar and NOT bar corrected altitude (m * 1E-3). (up +ve). If unknown set to INT32_MAX
+ * @param accuracyHor [mm] Horizontal accuracy in mm (m * 1E-3). If unknown set to UINT32_MAX
+ * @param accuracyVert [cm] Vertical accuracy in cm. If unknown set to UINT16_MAX
+ * @param accuracyVel [mm/s] Velocity accuracy in mm/s (m * 1E-3). If unknown set to UINT16_MAX
+ * @param velVert [cm/s] GPS vertical speed in cm/s. If unknown set to INT16_MAX
+ * @param velNS [cm/s] North-South velocity over ground in cm/s North +ve. If unknown set to INT16_MAX
+ * @param VelEW [cm/s] East-West velocity over ground in cm/s East +ve. If unknown set to INT16_MAX
+ * @param emergencyStatus Emergency status
+ * @param state ADS-B transponder dynamic input state flags
+ * @param squawk Mode A code (typically 1200 [0x04B0] for VFR)
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_uavionix_adsb_out_dynamic_send(mavlink_channel_t chan, uint32_t utcTime, int32_t gpsLat, int32_t gpsLon, int32_t gpsAlt, uint8_t gpsFix, uint8_t numSats, int32_t baroAltMSL, uint32_t accuracyHor, uint16_t accuracyVert, uint16_t accuracyVel, int16_t velVert, int16_t velNS, int16_t VelEW, uint8_t emergencyStatus, uint16_t state, uint16_t squawk)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_DYNAMIC_LEN];
+ _mav_put_uint32_t(buf, 0, utcTime);
+ _mav_put_int32_t(buf, 4, gpsLat);
+ _mav_put_int32_t(buf, 8, gpsLon);
+ _mav_put_int32_t(buf, 12, gpsAlt);
+ _mav_put_int32_t(buf, 16, baroAltMSL);
+ _mav_put_uint32_t(buf, 20, accuracyHor);
+ _mav_put_uint16_t(buf, 24, accuracyVert);
+ _mav_put_uint16_t(buf, 26, accuracyVel);
+ _mav_put_int16_t(buf, 28, velVert);
+ _mav_put_int16_t(buf, 30, velNS);
+ _mav_put_int16_t(buf, 32, VelEW);
+ _mav_put_uint16_t(buf, 34, state);
+ _mav_put_uint16_t(buf, 36, squawk);
+ _mav_put_uint8_t(buf, 38, gpsFix);
+ _mav_put_uint8_t(buf, 39, numSats);
+ _mav_put_uint8_t(buf, 40, emergencyStatus);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_DYNAMIC, buf, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_DYNAMIC_MIN_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_DYNAMIC_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_DYNAMIC_CRC);
+#else
+ mavlink_uavionix_adsb_out_dynamic_t packet;
+ packet.utcTime = utcTime;
+ packet.gpsLat = gpsLat;
+ packet.gpsLon = gpsLon;
+ packet.gpsAlt = gpsAlt;
+ packet.baroAltMSL = baroAltMSL;
+ packet.accuracyHor = accuracyHor;
+ packet.accuracyVert = accuracyVert;
+ packet.accuracyVel = accuracyVel;
+ packet.velVert = velVert;
+ packet.velNS = velNS;
+ packet.VelEW = VelEW;
+ packet.state = state;
+ packet.squawk = squawk;
+ packet.gpsFix = gpsFix;
+ packet.numSats = numSats;
+ packet.emergencyStatus = emergencyStatus;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_DYNAMIC, (const char *)&packet, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_DYNAMIC_MIN_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_DYNAMIC_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_DYNAMIC_CRC);
+#endif
+}
+
+/**
+ * @brief Send a uavionix_adsb_out_dynamic message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_uavionix_adsb_out_dynamic_send_struct(mavlink_channel_t chan, const mavlink_uavionix_adsb_out_dynamic_t* uavionix_adsb_out_dynamic)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_uavionix_adsb_out_dynamic_send(chan, uavionix_adsb_out_dynamic->utcTime, uavionix_adsb_out_dynamic->gpsLat, uavionix_adsb_out_dynamic->gpsLon, uavionix_adsb_out_dynamic->gpsAlt, uavionix_adsb_out_dynamic->gpsFix, uavionix_adsb_out_dynamic->numSats, uavionix_adsb_out_dynamic->baroAltMSL, uavionix_adsb_out_dynamic->accuracyHor, uavionix_adsb_out_dynamic->accuracyVert, uavionix_adsb_out_dynamic->accuracyVel, uavionix_adsb_out_dynamic->velVert, uavionix_adsb_out_dynamic->velNS, uavionix_adsb_out_dynamic->VelEW, uavionix_adsb_out_dynamic->emergencyStatus, uavionix_adsb_out_dynamic->state, uavionix_adsb_out_dynamic->squawk);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_DYNAMIC, (const char *)uavionix_adsb_out_dynamic, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_DYNAMIC_MIN_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_DYNAMIC_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_DYNAMIC_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_DYNAMIC_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_uavionix_adsb_out_dynamic_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t utcTime, int32_t gpsLat, int32_t gpsLon, int32_t gpsAlt, uint8_t gpsFix, uint8_t numSats, int32_t baroAltMSL, uint32_t accuracyHor, uint16_t accuracyVert, uint16_t accuracyVel, int16_t velVert, int16_t velNS, int16_t VelEW, uint8_t emergencyStatus, uint16_t state, uint16_t squawk)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint32_t(buf, 0, utcTime);
+ _mav_put_int32_t(buf, 4, gpsLat);
+ _mav_put_int32_t(buf, 8, gpsLon);
+ _mav_put_int32_t(buf, 12, gpsAlt);
+ _mav_put_int32_t(buf, 16, baroAltMSL);
+ _mav_put_uint32_t(buf, 20, accuracyHor);
+ _mav_put_uint16_t(buf, 24, accuracyVert);
+ _mav_put_uint16_t(buf, 26, accuracyVel);
+ _mav_put_int16_t(buf, 28, velVert);
+ _mav_put_int16_t(buf, 30, velNS);
+ _mav_put_int16_t(buf, 32, VelEW);
+ _mav_put_uint16_t(buf, 34, state);
+ _mav_put_uint16_t(buf, 36, squawk);
+ _mav_put_uint8_t(buf, 38, gpsFix);
+ _mav_put_uint8_t(buf, 39, numSats);
+ _mav_put_uint8_t(buf, 40, emergencyStatus);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_DYNAMIC, buf, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_DYNAMIC_MIN_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_DYNAMIC_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_DYNAMIC_CRC);
+#else
+ mavlink_uavionix_adsb_out_dynamic_t *packet = (mavlink_uavionix_adsb_out_dynamic_t *)msgbuf;
+ packet->utcTime = utcTime;
+ packet->gpsLat = gpsLat;
+ packet->gpsLon = gpsLon;
+ packet->gpsAlt = gpsAlt;
+ packet->baroAltMSL = baroAltMSL;
+ packet->accuracyHor = accuracyHor;
+ packet->accuracyVert = accuracyVert;
+ packet->accuracyVel = accuracyVel;
+ packet->velVert = velVert;
+ packet->velNS = velNS;
+ packet->VelEW = VelEW;
+ packet->state = state;
+ packet->squawk = squawk;
+ packet->gpsFix = gpsFix;
+ packet->numSats = numSats;
+ packet->emergencyStatus = emergencyStatus;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_DYNAMIC, (const char *)packet, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_DYNAMIC_MIN_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_DYNAMIC_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_DYNAMIC_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE UAVIONIX_ADSB_OUT_DYNAMIC UNPACKING
+
+
+/**
+ * @brief Get field utcTime from uavionix_adsb_out_dynamic message
+ *
+ * @return [s] UTC time in seconds since GPS epoch (Jan 6, 1980). If unknown set to UINT32_MAX
+ */
+static inline uint32_t mavlink_msg_uavionix_adsb_out_dynamic_get_utcTime(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint32_t(msg, 0);
+}
+
+/**
+ * @brief Get field gpsLat from uavionix_adsb_out_dynamic message
+ *
+ * @return [degE7] Latitude WGS84 (deg * 1E7). If unknown set to INT32_MAX
+ */
+static inline int32_t mavlink_msg_uavionix_adsb_out_dynamic_get_gpsLat(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_int32_t(msg, 4);
+}
+
+/**
+ * @brief Get field gpsLon from uavionix_adsb_out_dynamic message
+ *
+ * @return [degE7] Longitude WGS84 (deg * 1E7). If unknown set to INT32_MAX
+ */
+static inline int32_t mavlink_msg_uavionix_adsb_out_dynamic_get_gpsLon(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_int32_t(msg, 8);
+}
+
+/**
+ * @brief Get field gpsAlt from uavionix_adsb_out_dynamic message
+ *
+ * @return [mm] Altitude (WGS84). UP +ve. If unknown set to INT32_MAX
+ */
+static inline int32_t mavlink_msg_uavionix_adsb_out_dynamic_get_gpsAlt(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_int32_t(msg, 12);
+}
+
+/**
+ * @brief Get field gpsFix from uavionix_adsb_out_dynamic message
+ *
+ * @return 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS, 5: RTK
+ */
+static inline uint8_t mavlink_msg_uavionix_adsb_out_dynamic_get_gpsFix(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 38);
+}
+
+/**
+ * @brief Get field numSats from uavionix_adsb_out_dynamic message
+ *
+ * @return Number of satellites visible. If unknown set to UINT8_MAX
+ */
+static inline uint8_t mavlink_msg_uavionix_adsb_out_dynamic_get_numSats(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 39);
+}
+
+/**
+ * @brief Get field baroAltMSL from uavionix_adsb_out_dynamic message
+ *
+ * @return [mbar] Barometric pressure altitude (MSL) relative to a standard atmosphere of 1013.2 mBar and NOT bar corrected altitude (m * 1E-3). (up +ve). If unknown set to INT32_MAX
+ */
+static inline int32_t mavlink_msg_uavionix_adsb_out_dynamic_get_baroAltMSL(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_int32_t(msg, 16);
+}
+
+/**
+ * @brief Get field accuracyHor from uavionix_adsb_out_dynamic message
+ *
+ * @return [mm] Horizontal accuracy in mm (m * 1E-3). If unknown set to UINT32_MAX
+ */
+static inline uint32_t mavlink_msg_uavionix_adsb_out_dynamic_get_accuracyHor(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint32_t(msg, 20);
+}
+
+/**
+ * @brief Get field accuracyVert from uavionix_adsb_out_dynamic message
+ *
+ * @return [cm] Vertical accuracy in cm. If unknown set to UINT16_MAX
+ */
+static inline uint16_t mavlink_msg_uavionix_adsb_out_dynamic_get_accuracyVert(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 24);
+}
+
+/**
+ * @brief Get field accuracyVel from uavionix_adsb_out_dynamic message
+ *
+ * @return [mm/s] Velocity accuracy in mm/s (m * 1E-3). If unknown set to UINT16_MAX
+ */
+static inline uint16_t mavlink_msg_uavionix_adsb_out_dynamic_get_accuracyVel(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 26);
+}
+
+/**
+ * @brief Get field velVert from uavionix_adsb_out_dynamic message
+ *
+ * @return [cm/s] GPS vertical speed in cm/s. If unknown set to INT16_MAX
+ */
+static inline int16_t mavlink_msg_uavionix_adsb_out_dynamic_get_velVert(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_int16_t(msg, 28);
+}
+
+/**
+ * @brief Get field velNS from uavionix_adsb_out_dynamic message
+ *
+ * @return [cm/s] North-South velocity over ground in cm/s North +ve. If unknown set to INT16_MAX
+ */
+static inline int16_t mavlink_msg_uavionix_adsb_out_dynamic_get_velNS(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_int16_t(msg, 30);
+}
+
+/**
+ * @brief Get field VelEW from uavionix_adsb_out_dynamic message
+ *
+ * @return [cm/s] East-West velocity over ground in cm/s East +ve. If unknown set to INT16_MAX
+ */
+static inline int16_t mavlink_msg_uavionix_adsb_out_dynamic_get_VelEW(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_int16_t(msg, 32);
+}
+
+/**
+ * @brief Get field emergencyStatus from uavionix_adsb_out_dynamic message
+ *
+ * @return Emergency status
+ */
+static inline uint8_t mavlink_msg_uavionix_adsb_out_dynamic_get_emergencyStatus(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 40);
+}
+
+/**
+ * @brief Get field state from uavionix_adsb_out_dynamic message
+ *
+ * @return ADS-B transponder dynamic input state flags
+ */
+static inline uint16_t mavlink_msg_uavionix_adsb_out_dynamic_get_state(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 34);
+}
+
+/**
+ * @brief Get field squawk from uavionix_adsb_out_dynamic message
+ *
+ * @return Mode A code (typically 1200 [0x04B0] for VFR)
+ */
+static inline uint16_t mavlink_msg_uavionix_adsb_out_dynamic_get_squawk(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 36);
+}
+
+/**
+ * @brief Decode a uavionix_adsb_out_dynamic message into a struct
+ *
+ * @param msg The message to decode
+ * @param uavionix_adsb_out_dynamic C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_uavionix_adsb_out_dynamic_decode(const mavlink_message_t* msg, mavlink_uavionix_adsb_out_dynamic_t* uavionix_adsb_out_dynamic)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ uavionix_adsb_out_dynamic->utcTime = mavlink_msg_uavionix_adsb_out_dynamic_get_utcTime(msg);
+ uavionix_adsb_out_dynamic->gpsLat = mavlink_msg_uavionix_adsb_out_dynamic_get_gpsLat(msg);
+ uavionix_adsb_out_dynamic->gpsLon = mavlink_msg_uavionix_adsb_out_dynamic_get_gpsLon(msg);
+ uavionix_adsb_out_dynamic->gpsAlt = mavlink_msg_uavionix_adsb_out_dynamic_get_gpsAlt(msg);
+ uavionix_adsb_out_dynamic->baroAltMSL = mavlink_msg_uavionix_adsb_out_dynamic_get_baroAltMSL(msg);
+ uavionix_adsb_out_dynamic->accuracyHor = mavlink_msg_uavionix_adsb_out_dynamic_get_accuracyHor(msg);
+ uavionix_adsb_out_dynamic->accuracyVert = mavlink_msg_uavionix_adsb_out_dynamic_get_accuracyVert(msg);
+ uavionix_adsb_out_dynamic->accuracyVel = mavlink_msg_uavionix_adsb_out_dynamic_get_accuracyVel(msg);
+ uavionix_adsb_out_dynamic->velVert = mavlink_msg_uavionix_adsb_out_dynamic_get_velVert(msg);
+ uavionix_adsb_out_dynamic->velNS = mavlink_msg_uavionix_adsb_out_dynamic_get_velNS(msg);
+ uavionix_adsb_out_dynamic->VelEW = mavlink_msg_uavionix_adsb_out_dynamic_get_VelEW(msg);
+ uavionix_adsb_out_dynamic->state = mavlink_msg_uavionix_adsb_out_dynamic_get_state(msg);
+ uavionix_adsb_out_dynamic->squawk = mavlink_msg_uavionix_adsb_out_dynamic_get_squawk(msg);
+ uavionix_adsb_out_dynamic->gpsFix = mavlink_msg_uavionix_adsb_out_dynamic_get_gpsFix(msg);
+ uavionix_adsb_out_dynamic->numSats = mavlink_msg_uavionix_adsb_out_dynamic_get_numSats(msg);
+ uavionix_adsb_out_dynamic->emergencyStatus = mavlink_msg_uavionix_adsb_out_dynamic_get_emergencyStatus(msg);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_DYNAMIC_LEN? msg->len : MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_DYNAMIC_LEN;
+ memset(uavionix_adsb_out_dynamic, 0, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_DYNAMIC_LEN);
+ memcpy(uavionix_adsb_out_dynamic, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/uAvionix/mavlink_msg_uavionix_adsb_out_status.h b/lib/main/MAVLink/uAvionix/mavlink_msg_uavionix_adsb_out_status.h
new file mode 100644
index 00000000000..5dc6267023a
--- /dev/null
+++ b/lib/main/MAVLink/uAvionix/mavlink_msg_uavionix_adsb_out_status.h
@@ -0,0 +1,390 @@
+#pragma once
+// MESSAGE UAVIONIX_ADSB_OUT_STATUS PACKING
+
+#define MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_STATUS 10008
+
+
+typedef struct __mavlink_uavionix_adsb_out_status_t {
+ uint16_t squawk; /*< Mode A code (typically 1200 [0x04B0] for VFR)*/
+ uint8_t state; /*< ADS-B transponder status state flags*/
+ uint8_t NIC_NACp; /*< Integrity and Accuracy of traffic reported as a 4-bit value for each field (NACp 7:4, NIC 3:0) and encoded by Containment Radius (HPL) and Estimated Position Uncertainty (HFOM), respectively*/
+ uint8_t boardTemp; /*< Board temperature in C*/
+ uint8_t fault; /*< ADS-B transponder fault flags*/
+ char flight_id[8]; /*< Flight Identification: 8 ASCII characters, '0' through '9', 'A' through 'Z' or space. Spaces (0x20) used as a trailing pad character, or when call sign is unavailable.*/
+} mavlink_uavionix_adsb_out_status_t;
+
+#define MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_STATUS_LEN 14
+#define MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_STATUS_MIN_LEN 14
+#define MAVLINK_MSG_ID_10008_LEN 14
+#define MAVLINK_MSG_ID_10008_MIN_LEN 14
+
+#define MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_STATUS_CRC 240
+#define MAVLINK_MSG_ID_10008_CRC 240
+
+#define MAVLINK_MSG_UAVIONIX_ADSB_OUT_STATUS_FIELD_FLIGHT_ID_LEN 8
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_UAVIONIX_ADSB_OUT_STATUS { \
+ 10008, \
+ "UAVIONIX_ADSB_OUT_STATUS", \
+ 6, \
+ { { "state", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_uavionix_adsb_out_status_t, state) }, \
+ { "squawk", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_uavionix_adsb_out_status_t, squawk) }, \
+ { "NIC_NACp", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_uavionix_adsb_out_status_t, NIC_NACp) }, \
+ { "boardTemp", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_uavionix_adsb_out_status_t, boardTemp) }, \
+ { "fault", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_uavionix_adsb_out_status_t, fault) }, \
+ { "flight_id", NULL, MAVLINK_TYPE_CHAR, 8, 6, offsetof(mavlink_uavionix_adsb_out_status_t, flight_id) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_UAVIONIX_ADSB_OUT_STATUS { \
+ "UAVIONIX_ADSB_OUT_STATUS", \
+ 6, \
+ { { "state", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_uavionix_adsb_out_status_t, state) }, \
+ { "squawk", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_uavionix_adsb_out_status_t, squawk) }, \
+ { "NIC_NACp", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_uavionix_adsb_out_status_t, NIC_NACp) }, \
+ { "boardTemp", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_uavionix_adsb_out_status_t, boardTemp) }, \
+ { "fault", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_uavionix_adsb_out_status_t, fault) }, \
+ { "flight_id", NULL, MAVLINK_TYPE_CHAR, 8, 6, offsetof(mavlink_uavionix_adsb_out_status_t, flight_id) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a uavionix_adsb_out_status 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 state ADS-B transponder status state flags
+ * @param squawk Mode A code (typically 1200 [0x04B0] for VFR)
+ * @param NIC_NACp Integrity and Accuracy of traffic reported as a 4-bit value for each field (NACp 7:4, NIC 3:0) and encoded by Containment Radius (HPL) and Estimated Position Uncertainty (HFOM), respectively
+ * @param boardTemp Board temperature in C
+ * @param fault ADS-B transponder fault flags
+ * @param flight_id Flight Identification: 8 ASCII characters, '0' through '9', 'A' through 'Z' or space. Spaces (0x20) used as a trailing pad character, or when call sign is unavailable.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_uavionix_adsb_out_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint8_t state, uint16_t squawk, uint8_t NIC_NACp, uint8_t boardTemp, uint8_t fault, const char *flight_id)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_STATUS_LEN];
+ _mav_put_uint16_t(buf, 0, squawk);
+ _mav_put_uint8_t(buf, 2, state);
+ _mav_put_uint8_t(buf, 3, NIC_NACp);
+ _mav_put_uint8_t(buf, 4, boardTemp);
+ _mav_put_uint8_t(buf, 5, fault);
+ _mav_put_char_array(buf, 6, flight_id, 8);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_STATUS_LEN);
+#else
+ mavlink_uavionix_adsb_out_status_t packet;
+ packet.squawk = squawk;
+ packet.state = state;
+ packet.NIC_NACp = NIC_NACp;
+ packet.boardTemp = boardTemp;
+ packet.fault = fault;
+ mav_array_assign_char(packet.flight_id, flight_id, 8);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_STATUS_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_STATUS;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_STATUS_MIN_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_STATUS_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_STATUS_CRC);
+}
+
+/**
+ * @brief Pack a uavionix_adsb_out_status 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 state ADS-B transponder status state flags
+ * @param squawk Mode A code (typically 1200 [0x04B0] for VFR)
+ * @param NIC_NACp Integrity and Accuracy of traffic reported as a 4-bit value for each field (NACp 7:4, NIC 3:0) and encoded by Containment Radius (HPL) and Estimated Position Uncertainty (HFOM), respectively
+ * @param boardTemp Board temperature in C
+ * @param fault ADS-B transponder fault flags
+ * @param flight_id Flight Identification: 8 ASCII characters, '0' through '9', 'A' through 'Z' or space. Spaces (0x20) used as a trailing pad character, or when call sign is unavailable.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_uavionix_adsb_out_status_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ uint8_t state, uint16_t squawk, uint8_t NIC_NACp, uint8_t boardTemp, uint8_t fault, const char *flight_id)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_STATUS_LEN];
+ _mav_put_uint16_t(buf, 0, squawk);
+ _mav_put_uint8_t(buf, 2, state);
+ _mav_put_uint8_t(buf, 3, NIC_NACp);
+ _mav_put_uint8_t(buf, 4, boardTemp);
+ _mav_put_uint8_t(buf, 5, fault);
+ _mav_put_char_array(buf, 6, flight_id, 8);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_STATUS_LEN);
+#else
+ mavlink_uavionix_adsb_out_status_t packet;
+ packet.squawk = squawk;
+ packet.state = state;
+ packet.NIC_NACp = NIC_NACp;
+ packet.boardTemp = boardTemp;
+ packet.fault = fault;
+ mav_array_memcpy(packet.flight_id, flight_id, sizeof(char)*8);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_STATUS_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_STATUS;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_STATUS_MIN_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_STATUS_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_STATUS_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_STATUS_MIN_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_STATUS_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a uavionix_adsb_out_status 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 state ADS-B transponder status state flags
+ * @param squawk Mode A code (typically 1200 [0x04B0] for VFR)
+ * @param NIC_NACp Integrity and Accuracy of traffic reported as a 4-bit value for each field (NACp 7:4, NIC 3:0) and encoded by Containment Radius (HPL) and Estimated Position Uncertainty (HFOM), respectively
+ * @param boardTemp Board temperature in C
+ * @param fault ADS-B transponder fault flags
+ * @param flight_id Flight Identification: 8 ASCII characters, '0' through '9', 'A' through 'Z' or space. Spaces (0x20) used as a trailing pad character, or when call sign is unavailable.
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_uavionix_adsb_out_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint8_t state,uint16_t squawk,uint8_t NIC_NACp,uint8_t boardTemp,uint8_t fault,const char *flight_id)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_STATUS_LEN];
+ _mav_put_uint16_t(buf, 0, squawk);
+ _mav_put_uint8_t(buf, 2, state);
+ _mav_put_uint8_t(buf, 3, NIC_NACp);
+ _mav_put_uint8_t(buf, 4, boardTemp);
+ _mav_put_uint8_t(buf, 5, fault);
+ _mav_put_char_array(buf, 6, flight_id, 8);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_STATUS_LEN);
+#else
+ mavlink_uavionix_adsb_out_status_t packet;
+ packet.squawk = squawk;
+ packet.state = state;
+ packet.NIC_NACp = NIC_NACp;
+ packet.boardTemp = boardTemp;
+ packet.fault = fault;
+ mav_array_assign_char(packet.flight_id, flight_id, 8);
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_STATUS_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_STATUS;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_STATUS_MIN_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_STATUS_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_STATUS_CRC);
+}
+
+/**
+ * @brief Encode a uavionix_adsb_out_status 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 uavionix_adsb_out_status C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_uavionix_adsb_out_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_uavionix_adsb_out_status_t* uavionix_adsb_out_status)
+{
+ return mavlink_msg_uavionix_adsb_out_status_pack(system_id, component_id, msg, uavionix_adsb_out_status->state, uavionix_adsb_out_status->squawk, uavionix_adsb_out_status->NIC_NACp, uavionix_adsb_out_status->boardTemp, uavionix_adsb_out_status->fault, uavionix_adsb_out_status->flight_id);
+}
+
+/**
+ * @brief Encode a uavionix_adsb_out_status 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 uavionix_adsb_out_status C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_uavionix_adsb_out_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_uavionix_adsb_out_status_t* uavionix_adsb_out_status)
+{
+ return mavlink_msg_uavionix_adsb_out_status_pack_chan(system_id, component_id, chan, msg, uavionix_adsb_out_status->state, uavionix_adsb_out_status->squawk, uavionix_adsb_out_status->NIC_NACp, uavionix_adsb_out_status->boardTemp, uavionix_adsb_out_status->fault, uavionix_adsb_out_status->flight_id);
+}
+
+/**
+ * @brief Encode a uavionix_adsb_out_status 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 uavionix_adsb_out_status C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_uavionix_adsb_out_status_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_uavionix_adsb_out_status_t* uavionix_adsb_out_status)
+{
+ return mavlink_msg_uavionix_adsb_out_status_pack_status(system_id, component_id, _status, msg, uavionix_adsb_out_status->state, uavionix_adsb_out_status->squawk, uavionix_adsb_out_status->NIC_NACp, uavionix_adsb_out_status->boardTemp, uavionix_adsb_out_status->fault, uavionix_adsb_out_status->flight_id);
+}
+
+/**
+ * @brief Send a uavionix_adsb_out_status message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param state ADS-B transponder status state flags
+ * @param squawk Mode A code (typically 1200 [0x04B0] for VFR)
+ * @param NIC_NACp Integrity and Accuracy of traffic reported as a 4-bit value for each field (NACp 7:4, NIC 3:0) and encoded by Containment Radius (HPL) and Estimated Position Uncertainty (HFOM), respectively
+ * @param boardTemp Board temperature in C
+ * @param fault ADS-B transponder fault flags
+ * @param flight_id Flight Identification: 8 ASCII characters, '0' through '9', 'A' through 'Z' or space. Spaces (0x20) used as a trailing pad character, or when call sign is unavailable.
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_uavionix_adsb_out_status_send(mavlink_channel_t chan, uint8_t state, uint16_t squawk, uint8_t NIC_NACp, uint8_t boardTemp, uint8_t fault, const char *flight_id)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_STATUS_LEN];
+ _mav_put_uint16_t(buf, 0, squawk);
+ _mav_put_uint8_t(buf, 2, state);
+ _mav_put_uint8_t(buf, 3, NIC_NACp);
+ _mav_put_uint8_t(buf, 4, boardTemp);
+ _mav_put_uint8_t(buf, 5, fault);
+ _mav_put_char_array(buf, 6, flight_id, 8);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_STATUS, buf, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_STATUS_MIN_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_STATUS_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_STATUS_CRC);
+#else
+ mavlink_uavionix_adsb_out_status_t packet;
+ packet.squawk = squawk;
+ packet.state = state;
+ packet.NIC_NACp = NIC_NACp;
+ packet.boardTemp = boardTemp;
+ packet.fault = fault;
+ mav_array_assign_char(packet.flight_id, flight_id, 8);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_STATUS, (const char *)&packet, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_STATUS_MIN_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_STATUS_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_STATUS_CRC);
+#endif
+}
+
+/**
+ * @brief Send a uavionix_adsb_out_status message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_uavionix_adsb_out_status_send_struct(mavlink_channel_t chan, const mavlink_uavionix_adsb_out_status_t* uavionix_adsb_out_status)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_uavionix_adsb_out_status_send(chan, uavionix_adsb_out_status->state, uavionix_adsb_out_status->squawk, uavionix_adsb_out_status->NIC_NACp, uavionix_adsb_out_status->boardTemp, uavionix_adsb_out_status->fault, uavionix_adsb_out_status->flight_id);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_STATUS, (const char *)uavionix_adsb_out_status, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_STATUS_MIN_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_STATUS_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_STATUS_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_uavionix_adsb_out_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t state, uint16_t squawk, uint8_t NIC_NACp, uint8_t boardTemp, uint8_t fault, const char *flight_id)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint16_t(buf, 0, squawk);
+ _mav_put_uint8_t(buf, 2, state);
+ _mav_put_uint8_t(buf, 3, NIC_NACp);
+ _mav_put_uint8_t(buf, 4, boardTemp);
+ _mav_put_uint8_t(buf, 5, fault);
+ _mav_put_char_array(buf, 6, flight_id, 8);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_STATUS, buf, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_STATUS_MIN_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_STATUS_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_STATUS_CRC);
+#else
+ mavlink_uavionix_adsb_out_status_t *packet = (mavlink_uavionix_adsb_out_status_t *)msgbuf;
+ packet->squawk = squawk;
+ packet->state = state;
+ packet->NIC_NACp = NIC_NACp;
+ packet->boardTemp = boardTemp;
+ packet->fault = fault;
+ mav_array_assign_char(packet->flight_id, flight_id, 8);
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_STATUS, (const char *)packet, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_STATUS_MIN_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_STATUS_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_STATUS_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE UAVIONIX_ADSB_OUT_STATUS UNPACKING
+
+
+/**
+ * @brief Get field state from uavionix_adsb_out_status message
+ *
+ * @return ADS-B transponder status state flags
+ */
+static inline uint8_t mavlink_msg_uavionix_adsb_out_status_get_state(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 2);
+}
+
+/**
+ * @brief Get field squawk from uavionix_adsb_out_status message
+ *
+ * @return Mode A code (typically 1200 [0x04B0] for VFR)
+ */
+static inline uint16_t mavlink_msg_uavionix_adsb_out_status_get_squawk(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint16_t(msg, 0);
+}
+
+/**
+ * @brief Get field NIC_NACp from uavionix_adsb_out_status message
+ *
+ * @return Integrity and Accuracy of traffic reported as a 4-bit value for each field (NACp 7:4, NIC 3:0) and encoded by Containment Radius (HPL) and Estimated Position Uncertainty (HFOM), respectively
+ */
+static inline uint8_t mavlink_msg_uavionix_adsb_out_status_get_NIC_NACp(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 3);
+}
+
+/**
+ * @brief Get field boardTemp from uavionix_adsb_out_status message
+ *
+ * @return Board temperature in C
+ */
+static inline uint8_t mavlink_msg_uavionix_adsb_out_status_get_boardTemp(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 4);
+}
+
+/**
+ * @brief Get field fault from uavionix_adsb_out_status message
+ *
+ * @return ADS-B transponder fault flags
+ */
+static inline uint8_t mavlink_msg_uavionix_adsb_out_status_get_fault(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 5);
+}
+
+/**
+ * @brief Get field flight_id from uavionix_adsb_out_status message
+ *
+ * @return Flight Identification: 8 ASCII characters, '0' through '9', 'A' through 'Z' or space. Spaces (0x20) used as a trailing pad character, or when call sign is unavailable.
+ */
+static inline uint16_t mavlink_msg_uavionix_adsb_out_status_get_flight_id(const mavlink_message_t* msg, char *flight_id)
+{
+ return _MAV_RETURN_char_array(msg, flight_id, 8, 6);
+}
+
+/**
+ * @brief Decode a uavionix_adsb_out_status message into a struct
+ *
+ * @param msg The message to decode
+ * @param uavionix_adsb_out_status C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_uavionix_adsb_out_status_decode(const mavlink_message_t* msg, mavlink_uavionix_adsb_out_status_t* uavionix_adsb_out_status)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ uavionix_adsb_out_status->squawk = mavlink_msg_uavionix_adsb_out_status_get_squawk(msg);
+ uavionix_adsb_out_status->state = mavlink_msg_uavionix_adsb_out_status_get_state(msg);
+ uavionix_adsb_out_status->NIC_NACp = mavlink_msg_uavionix_adsb_out_status_get_NIC_NACp(msg);
+ uavionix_adsb_out_status->boardTemp = mavlink_msg_uavionix_adsb_out_status_get_boardTemp(msg);
+ uavionix_adsb_out_status->fault = mavlink_msg_uavionix_adsb_out_status_get_fault(msg);
+ mavlink_msg_uavionix_adsb_out_status_get_flight_id(msg, uavionix_adsb_out_status->flight_id);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_STATUS_LEN? msg->len : MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_STATUS_LEN;
+ memset(uavionix_adsb_out_status, 0, MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_STATUS_LEN);
+ memcpy(uavionix_adsb_out_status, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/uAvionix/mavlink_msg_uavionix_adsb_transceiver_health_report.h b/lib/main/MAVLink/uAvionix/mavlink_msg_uavionix_adsb_transceiver_health_report.h
new file mode 100644
index 00000000000..7f1cbdfbfc0
--- /dev/null
+++ b/lib/main/MAVLink/uAvionix/mavlink_msg_uavionix_adsb_transceiver_health_report.h
@@ -0,0 +1,260 @@
+#pragma once
+// MESSAGE UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT PACKING
+
+#define MAVLINK_MSG_ID_UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT 10003
+
+
+typedef struct __mavlink_uavionix_adsb_transceiver_health_report_t {
+ uint8_t rfHealth; /*< ADS-B transponder messages*/
+} mavlink_uavionix_adsb_transceiver_health_report_t;
+
+#define MAVLINK_MSG_ID_UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_LEN 1
+#define MAVLINK_MSG_ID_UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_MIN_LEN 1
+#define MAVLINK_MSG_ID_10003_LEN 1
+#define MAVLINK_MSG_ID_10003_MIN_LEN 1
+
+#define MAVLINK_MSG_ID_UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_CRC 4
+#define MAVLINK_MSG_ID_10003_CRC 4
+
+
+
+#if MAVLINK_COMMAND_24BIT
+#define MAVLINK_MESSAGE_INFO_UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT { \
+ 10003, \
+ "UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT", \
+ 1, \
+ { { "rfHealth", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_uavionix_adsb_transceiver_health_report_t, rfHealth) }, \
+ } \
+}
+#else
+#define MAVLINK_MESSAGE_INFO_UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT { \
+ "UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT", \
+ 1, \
+ { { "rfHealth", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_uavionix_adsb_transceiver_health_report_t, rfHealth) }, \
+ } \
+}
+#endif
+
+/**
+ * @brief Pack a uavionix_adsb_transceiver_health_report 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 rfHealth ADS-B transponder messages
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_uavionix_adsb_transceiver_health_report_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
+ uint8_t rfHealth)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_LEN];
+ _mav_put_uint8_t(buf, 0, rfHealth);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_LEN);
+#else
+ mavlink_uavionix_adsb_transceiver_health_report_t packet;
+ packet.rfHealth = rfHealth;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT;
+ return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_MIN_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_CRC);
+}
+
+/**
+ * @brief Pack a uavionix_adsb_transceiver_health_report 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 rfHealth ADS-B transponder messages
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_uavionix_adsb_transceiver_health_report_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
+ uint8_t rfHealth)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_LEN];
+ _mav_put_uint8_t(buf, 0, rfHealth);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_LEN);
+#else
+ mavlink_uavionix_adsb_transceiver_health_report_t packet;
+ packet.rfHealth = rfHealth;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT;
+#if MAVLINK_CRC_EXTRA
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_MIN_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_CRC);
+#else
+ return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_MIN_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_LEN);
+#endif
+}
+
+/**
+ * @brief Pack a uavionix_adsb_transceiver_health_report 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 rfHealth ADS-B transponder messages
+ * @return length of the message in bytes (excluding serial stream start sign)
+ */
+static inline uint16_t mavlink_msg_uavionix_adsb_transceiver_health_report_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
+ mavlink_message_t* msg,
+ uint8_t rfHealth)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_LEN];
+ _mav_put_uint8_t(buf, 0, rfHealth);
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_LEN);
+#else
+ mavlink_uavionix_adsb_transceiver_health_report_t packet;
+ packet.rfHealth = rfHealth;
+
+ memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_LEN);
+#endif
+
+ msg->msgid = MAVLINK_MSG_ID_UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT;
+ return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_MIN_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_CRC);
+}
+
+/**
+ * @brief Encode a uavionix_adsb_transceiver_health_report 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 uavionix_adsb_transceiver_health_report C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_uavionix_adsb_transceiver_health_report_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_uavionix_adsb_transceiver_health_report_t* uavionix_adsb_transceiver_health_report)
+{
+ return mavlink_msg_uavionix_adsb_transceiver_health_report_pack(system_id, component_id, msg, uavionix_adsb_transceiver_health_report->rfHealth);
+}
+
+/**
+ * @brief Encode a uavionix_adsb_transceiver_health_report 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 uavionix_adsb_transceiver_health_report C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_uavionix_adsb_transceiver_health_report_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_uavionix_adsb_transceiver_health_report_t* uavionix_adsb_transceiver_health_report)
+{
+ return mavlink_msg_uavionix_adsb_transceiver_health_report_pack_chan(system_id, component_id, chan, msg, uavionix_adsb_transceiver_health_report->rfHealth);
+}
+
+/**
+ * @brief Encode a uavionix_adsb_transceiver_health_report 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 uavionix_adsb_transceiver_health_report C-struct to read the message contents from
+ */
+static inline uint16_t mavlink_msg_uavionix_adsb_transceiver_health_report_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_uavionix_adsb_transceiver_health_report_t* uavionix_adsb_transceiver_health_report)
+{
+ return mavlink_msg_uavionix_adsb_transceiver_health_report_pack_status(system_id, component_id, _status, msg, uavionix_adsb_transceiver_health_report->rfHealth);
+}
+
+/**
+ * @brief Send a uavionix_adsb_transceiver_health_report message
+ * @param chan MAVLink channel to send the message
+ *
+ * @param rfHealth ADS-B transponder messages
+ */
+#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
+
+static inline void mavlink_msg_uavionix_adsb_transceiver_health_report_send(mavlink_channel_t chan, uint8_t rfHealth)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char buf[MAVLINK_MSG_ID_UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_LEN];
+ _mav_put_uint8_t(buf, 0, rfHealth);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT, buf, MAVLINK_MSG_ID_UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_MIN_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_CRC);
+#else
+ mavlink_uavionix_adsb_transceiver_health_report_t packet;
+ packet.rfHealth = rfHealth;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT, (const char *)&packet, MAVLINK_MSG_ID_UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_MIN_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_CRC);
+#endif
+}
+
+/**
+ * @brief Send a uavionix_adsb_transceiver_health_report message
+ * @param chan MAVLink channel to send the message
+ * @param struct The MAVLink struct to serialize
+ */
+static inline void mavlink_msg_uavionix_adsb_transceiver_health_report_send_struct(mavlink_channel_t chan, const mavlink_uavionix_adsb_transceiver_health_report_t* uavionix_adsb_transceiver_health_report)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ mavlink_msg_uavionix_adsb_transceiver_health_report_send(chan, uavionix_adsb_transceiver_health_report->rfHealth);
+#else
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT, (const char *)uavionix_adsb_transceiver_health_report, MAVLINK_MSG_ID_UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_MIN_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_CRC);
+#endif
+}
+
+#if MAVLINK_MSG_ID_UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
+/*
+ This variant of _send() can be used to save stack space by reusing
+ 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_uavionix_adsb_transceiver_health_report_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t rfHealth)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ char *buf = (char *)msgbuf;
+ _mav_put_uint8_t(buf, 0, rfHealth);
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT, buf, MAVLINK_MSG_ID_UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_MIN_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_CRC);
+#else
+ mavlink_uavionix_adsb_transceiver_health_report_t *packet = (mavlink_uavionix_adsb_transceiver_health_report_t *)msgbuf;
+ packet->rfHealth = rfHealth;
+
+ _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT, (const char *)packet, MAVLINK_MSG_ID_UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_MIN_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_LEN, MAVLINK_MSG_ID_UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_CRC);
+#endif
+}
+#endif
+
+#endif
+
+// MESSAGE UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT UNPACKING
+
+
+/**
+ * @brief Get field rfHealth from uavionix_adsb_transceiver_health_report message
+ *
+ * @return ADS-B transponder messages
+ */
+static inline uint8_t mavlink_msg_uavionix_adsb_transceiver_health_report_get_rfHealth(const mavlink_message_t* msg)
+{
+ return _MAV_RETURN_uint8_t(msg, 0);
+}
+
+/**
+ * @brief Decode a uavionix_adsb_transceiver_health_report message into a struct
+ *
+ * @param msg The message to decode
+ * @param uavionix_adsb_transceiver_health_report C-struct to decode the message contents into
+ */
+static inline void mavlink_msg_uavionix_adsb_transceiver_health_report_decode(const mavlink_message_t* msg, mavlink_uavionix_adsb_transceiver_health_report_t* uavionix_adsb_transceiver_health_report)
+{
+#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
+ uavionix_adsb_transceiver_health_report->rfHealth = mavlink_msg_uavionix_adsb_transceiver_health_report_get_rfHealth(msg);
+#else
+ uint8_t len = msg->len < MAVLINK_MSG_ID_UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_LEN? msg->len : MAVLINK_MSG_ID_UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_LEN;
+ memset(uavionix_adsb_transceiver_health_report, 0, MAVLINK_MSG_ID_UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_LEN);
+ memcpy(uavionix_adsb_transceiver_health_report, _MAV_PAYLOAD(msg), len);
+#endif
+}
diff --git a/lib/main/MAVLink/uAvionix/testsuite.h b/lib/main/MAVLink/uAvionix/testsuite.h
new file mode 100644
index 00000000000..7d728122b49
--- /dev/null
+++ b/lib/main/MAVLink/uAvionix/testsuite.h
@@ -0,0 +1,547 @@
+/** @file
+ * @brief MAVLink comm protocol testsuite generated from uAvionix.xml
+ * @see https://mavlink.io/en/
+ */
+#pragma once
+#ifndef UAVIONIX_TESTSUITE_H
+#define UAVIONIX_TESTSUITE_H
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+#ifndef MAVLINK_TEST_ALL
+#define MAVLINK_TEST_ALL
+static void mavlink_test_common(uint8_t, uint8_t, mavlink_message_t *last_msg);
+static void mavlink_test_uAvionix(uint8_t, uint8_t, mavlink_message_t *last_msg);
+
+static void mavlink_test_all(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
+{
+ mavlink_test_common(system_id, component_id, last_msg);
+ mavlink_test_uAvionix(system_id, component_id, last_msg);
+}
+#endif
+
+#include "../common/testsuite.h"
+
+
+static void mavlink_test_uavionix_adsb_out_cfg(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_UAVIONIX_ADSB_OUT_CFG >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_uavionix_adsb_out_cfg_t packet_in = {
+ 963497464,17443,"GHIJKLMN",242,53,120,187,254
+ };
+ mavlink_uavionix_adsb_out_cfg_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.ICAO = packet_in.ICAO;
+ packet1.stallSpeed = packet_in.stallSpeed;
+ packet1.emitterType = packet_in.emitterType;
+ packet1.aircraftSize = packet_in.aircraftSize;
+ packet1.gpsOffsetLat = packet_in.gpsOffsetLat;
+ packet1.gpsOffsetLon = packet_in.gpsOffsetLon;
+ packet1.rfSelect = packet_in.rfSelect;
+
+ mav_array_memcpy(packet1.callsign, packet_in.callsign, sizeof(char)*9);
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_uavionix_adsb_out_cfg_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_uavionix_adsb_out_cfg_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_uavionix_adsb_out_cfg_pack(system_id, component_id, &msg , packet1.ICAO , packet1.callsign , packet1.emitterType , packet1.aircraftSize , packet1.gpsOffsetLat , packet1.gpsOffsetLon , packet1.stallSpeed , packet1.rfSelect );
+ mavlink_msg_uavionix_adsb_out_cfg_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_uavionix_adsb_out_cfg_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.ICAO , packet1.callsign , packet1.emitterType , packet1.aircraftSize , packet1.gpsOffsetLat , packet1.gpsOffsetLon , packet1.stallSpeed , packet1.rfSelect );
+ mavlink_msg_uavionix_adsb_out_cfg_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_DYNAMIC >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_uavionix_adsb_out_dynamic_t packet_in = {
+ 963497464,963497672,963497880,963498088,963498296,963498504,18483,18587,18691,18795,18899,19003,19107,247,58,125
+ };
+ mavlink_uavionix_adsb_out_dynamic_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.utcTime = packet_in.utcTime;
+ packet1.gpsLat = packet_in.gpsLat;
+ packet1.gpsLon = packet_in.gpsLon;
+ packet1.gpsAlt = packet_in.gpsAlt;
+ packet1.baroAltMSL = packet_in.baroAltMSL;
+ packet1.accuracyHor = packet_in.accuracyHor;
+ packet1.accuracyVert = packet_in.accuracyVert;
+ packet1.accuracyVel = packet_in.accuracyVel;
+ packet1.velVert = packet_in.velVert;
+ packet1.velNS = packet_in.velNS;
+ packet1.VelEW = packet_in.VelEW;
+ packet1.state = packet_in.state;
+ packet1.squawk = packet_in.squawk;
+ packet1.gpsFix = packet_in.gpsFix;
+ packet1.numSats = packet_in.numSats;
+ packet1.emergencyStatus = packet_in.emergencyStatus;
+
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_DYNAMIC_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_DYNAMIC_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_uavionix_adsb_out_dynamic_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_uavionix_adsb_out_dynamic_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_uavionix_adsb_out_dynamic_pack(system_id, component_id, &msg , packet1.utcTime , packet1.gpsLat , packet1.gpsLon , packet1.gpsAlt , packet1.gpsFix , packet1.numSats , packet1.baroAltMSL , packet1.accuracyHor , packet1.accuracyVert , packet1.accuracyVel , packet1.velVert , packet1.velNS , packet1.VelEW , packet1.emergencyStatus , packet1.state , packet1.squawk );
+ mavlink_msg_uavionix_adsb_out_dynamic_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_uavionix_adsb_out_dynamic_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.utcTime , packet1.gpsLat , packet1.gpsLon , packet1.gpsAlt , packet1.gpsFix , packet1.numSats , packet1.baroAltMSL , packet1.accuracyHor , packet1.accuracyVert , packet1.accuracyVel , packet1.velVert , packet1.velNS , packet1.VelEW , packet1.emergencyStatus , packet1.state , packet1.squawk );
+ mavlink_msg_uavionix_adsb_out_dynamic_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_uavionix_adsb_transceiver_health_report_t packet_in = {
+ 5
+ };
+ mavlink_uavionix_adsb_transceiver_health_report_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.rfHealth = packet_in.rfHealth;
+
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_uavionix_adsb_transceiver_health_report_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_uavionix_adsb_transceiver_health_report_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_uavionix_adsb_transceiver_health_report_pack(system_id, component_id, &msg , packet1.rfHealth );
+ mavlink_msg_uavionix_adsb_transceiver_health_report_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_uavionix_adsb_transceiver_health_report_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.rfHealth );
+ mavlink_msg_uavionix_adsb_transceiver_health_report_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_REGISTRATION >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_uavionix_adsb_out_cfg_registration_t packet_in = {
+ "ABCDEFGH"
+ };
+ mavlink_uavionix_adsb_out_cfg_registration_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+
+ mav_array_memcpy(packet1.registration, packet_in.registration, sizeof(char)*9);
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_REGISTRATION_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_REGISTRATION_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_uavionix_adsb_out_cfg_registration_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_uavionix_adsb_out_cfg_registration_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_uavionix_adsb_out_cfg_registration_pack(system_id, component_id, &msg , packet1.registration );
+ mavlink_msg_uavionix_adsb_out_cfg_registration_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_uavionix_adsb_out_cfg_registration_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.registration );
+ mavlink_msg_uavionix_adsb_out_cfg_registration_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_FLIGHTID >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_uavionix_adsb_out_cfg_flightid_t packet_in = {
+ "ABCDEFGH"
+ };
+ mavlink_uavionix_adsb_out_cfg_flightid_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+
+ mav_array_memcpy(packet1.flight_id, packet_in.flight_id, sizeof(char)*9);
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_FLIGHTID_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_FLIGHTID_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_uavionix_adsb_out_cfg_flightid_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_uavionix_adsb_out_cfg_flightid_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_uavionix_adsb_out_cfg_flightid_pack(system_id, component_id, &msg , packet1.flight_id );
+ mavlink_msg_uavionix_adsb_out_cfg_flightid_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_uavionix_adsb_out_cfg_flightid_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.flight_id );
+ mavlink_msg_uavionix_adsb_out_cfg_flightid_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_UAVIONIX_ADSB_GET >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_uavionix_adsb_get_t packet_in = {
+ 963497464
+ };
+ mavlink_uavionix_adsb_get_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.ReqMessageId = packet_in.ReqMessageId;
+
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_UAVIONIX_ADSB_GET_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_UAVIONIX_ADSB_GET_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_uavionix_adsb_get_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_uavionix_adsb_get_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_uavionix_adsb_get_pack(system_id, component_id, &msg , packet1.ReqMessageId );
+ mavlink_msg_uavionix_adsb_get_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_uavionix_adsb_get_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.ReqMessageId );
+ mavlink_msg_uavionix_adsb_get_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CONTROL >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_uavionix_adsb_out_control_t packet_in = {
+ 963497464,17443,151,218,"IJKLMNO",53
+ };
+ mavlink_uavionix_adsb_out_control_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.baroAltMSL = packet_in.baroAltMSL;
+ packet1.squawk = packet_in.squawk;
+ packet1.state = packet_in.state;
+ packet1.emergencyStatus = packet_in.emergencyStatus;
+ packet1.x_bit = packet_in.x_bit;
+
+ mav_array_memcpy(packet1.flight_id, packet_in.flight_id, sizeof(char)*8);
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CONTROL_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CONTROL_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_uavionix_adsb_out_control_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_uavionix_adsb_out_control_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_uavionix_adsb_out_control_pack(system_id, component_id, &msg , packet1.state , packet1.baroAltMSL , packet1.squawk , packet1.emergencyStatus , packet1.flight_id , packet1.x_bit );
+ mavlink_msg_uavionix_adsb_out_control_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_uavionix_adsb_out_control_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.state , packet1.baroAltMSL , packet1.squawk , packet1.emergencyStatus , packet1.flight_id , packet1.x_bit );
+ mavlink_msg_uavionix_adsb_out_control_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; iflags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) && MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_STATUS >= 256) {
+ return;
+ }
+#endif
+ mavlink_message_t msg;
+ uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
+ uint16_t i;
+ mavlink_uavionix_adsb_out_status_t packet_in = {
+ 17235,139,206,17,84,"GHIJKLM"
+ };
+ mavlink_uavionix_adsb_out_status_t packet1, packet2;
+ memset(&packet1, 0, sizeof(packet1));
+ packet1.squawk = packet_in.squawk;
+ packet1.state = packet_in.state;
+ packet1.NIC_NACp = packet_in.NIC_NACp;
+ packet1.boardTemp = packet_in.boardTemp;
+ packet1.fault = packet_in.fault;
+
+ mav_array_memcpy(packet1.flight_id, packet_in.flight_id, sizeof(char)*8);
+
+#ifdef MAVLINK_STATUS_FLAG_OUT_MAVLINK1
+ if (status->flags & MAVLINK_STATUS_FLAG_OUT_MAVLINK1) {
+ // cope with extensions
+ memset(MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_STATUS_MIN_LEN + (char *)&packet1, 0, sizeof(packet1)-MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_STATUS_MIN_LEN);
+ }
+#endif
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_uavionix_adsb_out_status_encode(system_id, component_id, &msg, &packet1);
+ mavlink_msg_uavionix_adsb_out_status_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_uavionix_adsb_out_status_pack(system_id, component_id, &msg , packet1.state , packet1.squawk , packet1.NIC_NACp , packet1.boardTemp , packet1.fault , packet1.flight_id );
+ mavlink_msg_uavionix_adsb_out_status_decode(&msg, &packet2);
+ MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
+
+ memset(&packet2, 0, sizeof(packet2));
+ mavlink_msg_uavionix_adsb_out_status_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.state , packet1.squawk , packet1.NIC_NACp , packet1.boardTemp , packet1.fault , packet1.flight_id );
+ mavlink_msg_uavionix_adsb_out_status_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
Date: Mon, 20 Apr 2026 18:38:54 -0400
Subject: [PATCH 45/46] .
---
src/main/fc/fc_mavlink.c | 12 +-----------
src/main/fc/settings.yaml | 2 +-
2 files changed, 2 insertions(+), 12 deletions(-)
diff --git a/src/main/fc/fc_mavlink.c b/src/main/fc/fc_mavlink.c
index 0fe195332c5..c481997881d 100644
--- a/src/main/fc/fc_mavlink.c
+++ b/src/main/fc/fc_mavlink.c
@@ -168,8 +168,6 @@ static bool handleIncoming_PARAM_REQUEST_LIST(void) {
static void mavlinkParseRxStats(const mavlink_radio_status_t *msg) {
switch(mavActiveConfig->radio_type) {
- case MAVLINK_RADIO_NONE:
- break;
case MAVLINK_RADIO_SIK:
rxLinkStatistics.uplinkRSSI = (msg->rssi / 1.9) - 127;
rxLinkStatistics.uplinkSNR = msg->noise / 1.9;
@@ -181,15 +179,7 @@ static void mavlinkParseRxStats(const mavlink_radio_status_t *msg) {
rxLinkStatistics.uplinkLQ = scaleRange(msg->rssi, 0, 255, 0, 100);
break;
case MAVLINK_RADIO_MLRS:
- // rssi/remrssi are 0-254 AP scale; back-convert to dBm: range is -120 to -50
- rxLinkStatistics.uplinkRSSI = msg->rssi != 255
- ? (int8_t)(((int32_t)msg->rssi * (-50 - -120) / 254) + (-120))
- : 0;
- // noise field is actually: clamp(-SNR + 10, 0, 127), so SNR = -(noise - 10) = 10 - noise
- rxLinkStatistics.uplinkSNR = 10 - (int8_t)msg->noise;
- rxLinkStatistics.uplinkLQ = msg->rssi != 255
- ? scaleRange(msg->rssi, 0, 254, 0, 100)
- : 0;
+ // implement here
break;
case MAVLINK_RADIO_GENERIC:
default:
diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml
index 3c00d9ceca5..68bbcb34ee6 100644
--- a/src/main/fc/settings.yaml
+++ b/src/main/fc/settings.yaml
@@ -199,7 +199,7 @@ tables:
values: ["NONE", "SERIAL", "MSP"]
enum: headTrackerDevType_e
- name: mavlink_radio_type
- values: ["GENERIC", "ELRS", "SIK", "MLRS", "NONE"]
+ values: ["GENERIC", "ELRS", "SIK", "MLRS"]
enum: mavlinkRadio_e
- name: mavlink_autopilot_type
values: ["GENERIC", "ARDUPILOT"]
From 98c35a8b3affb82ba6f32720bb23119e635c247e Mon Sep 17 00:00:00 2001
From: frogmane <7685285+xznhj8129@users.noreply.github.com>
Date: Wed, 22 Apr 2026 04:37:41 -0400
Subject: [PATCH 46/46] Add native MLRS MAVLink receive support
---
src/main/fc/fc_mavlink.c | 147 ++++++++++++++++++-
src/main/mavlink/mavlink_ports.c | 2 +
src/main/mavlink/mavlink_routing.c | 3 +-
src/main/mavlink/mavlink_runtime.c | 28 ++++
src/main/mavlink/mavlink_runtime.h | 5 +
src/main/mavlink/mavlink_types.h | 34 +++++
src/test/unit/CMakeLists.txt | 5 +-
src/test/unit/mavlink_unittest.cc | 223 +++++++++++++++++++++++++++++
8 files changed, 441 insertions(+), 6 deletions(-)
diff --git a/src/main/fc/fc_mavlink.c b/src/main/fc/fc_mavlink.c
index c481997881d..690891d8ec3 100644
--- a/src/main/fc/fc_mavlink.c
+++ b/src/main/fc/fc_mavlink.c
@@ -166,6 +166,24 @@ static bool handleIncoming_PARAM_REQUEST_LIST(void) {
return true;
}
+static bool mavlinkIngressPortIsMavlinkSerialRx(uint8_t ingressPortIndex)
+{
+ return ingressPortIndex < mavPortCount &&
+ mavPortStates[ingressPortIndex].portConfig &&
+ (mavPortStates[ingressPortIndex].portConfig->functionMask & FUNCTION_RX_SERIAL) &&
+ rxConfig()->receiverType == RX_TYPE_SERIAL &&
+ rxConfig()->serialrx_provider == SERIALRX_MAVLINK;
+}
+
+static uint16_t mavlinkDbmToMilliwatts(int8_t powerDbm)
+{
+ if (powerDbm == INT8_MAX) {
+ return 0;
+ }
+
+ return powerDbm <= 0 ? 0 : lrintf(powf(10.0f, powerDbm / 10.0f));
+}
+
static void mavlinkParseRxStats(const mavlink_radio_status_t *msg) {
switch(mavActiveConfig->radio_type) {
case MAVLINK_RADIO_SIK:
@@ -179,7 +197,6 @@ static void mavlinkParseRxStats(const mavlink_radio_status_t *msg) {
rxLinkStatistics.uplinkLQ = scaleRange(msg->rssi, 0, 255, 0, 100);
break;
case MAVLINK_RADIO_MLRS:
- // implement here
break;
case MAVLINK_RADIO_GENERIC:
default:
@@ -209,6 +226,126 @@ static bool handleIncoming_RADIO_STATUS(void) {
return true;
}
+static bool handleIncoming_MLRS_RADIO_LINK_STATS(uint8_t ingressPortIndex)
+{
+ if (mavlinkContext.recvMsg.compid != MAV_COMP_ID_TELEMETRY_RADIO) {
+ return false;
+ }
+
+ mavlink_mlrs_radio_link_stats_t msg;
+ mavlink_msg_mlrs_radio_link_stats_decode(&mavlinkContext.recvMsg, &msg);
+
+ if (msg.target_system != mavSystemId) {
+ return false;
+ }
+ if (msg.target_component != 0 && msg.target_component != mavComponentId) {
+ return false;
+ }
+
+ mavlinkMlrsLinkStatsRuntime_t *stats = &mavPortStates[ingressPortIndex].mlrs.stats;
+ stats->valid = true;
+ stats->packet = msg;
+ stats->rssiIsDbm = (msg.flags & MLRS_RADIO_LINK_STATS_FLAGS_RSSI_DBM) != 0;
+ stats->activeAntenna = (msg.flags & MLRS_RADIO_LINK_STATS_FLAGS_RX_RECEIVE_ANTENNA2) ? 1 : 0;
+ stats->rxLinkQualityRc = msg.rx_LQ_rc == UINT8_MAX ? 0 : MIN(msg.rx_LQ_rc, 100);
+ stats->rxLinkQualitySerial = msg.rx_LQ_ser == UINT8_MAX ? 0 : MIN(msg.rx_LQ_ser, 100);
+
+ uint8_t rxRssi = stats->activeAntenna ? msg.rx_rssi2 : msg.rx_rssi1;
+ if (stats->activeAntenna && rxRssi == UINT8_MAX) {
+ rxRssi = msg.rx_rssi1;
+ }
+ stats->rxRssi = 0;
+ if (rxRssi != 0 && rxRssi != UINT8_MAX) {
+ stats->rxRssi = stats->rssiIsDbm ? -rxRssi : rxRssi;
+ }
+
+ int8_t rxSnr = stats->activeAntenna ? msg.rx_snr2 : msg.rx_snr1;
+ if (stats->activeAntenna && rxSnr == INT8_MAX) {
+ rxSnr = msg.rx_snr1;
+ }
+ stats->rxSnr = rxSnr == INT8_MAX ? 0 : rxSnr;
+
+ if (!mavlinkIngressPortIsMavlinkSerialRx(ingressPortIndex)) {
+ return true;
+ }
+
+ rxLinkStatistics.uplinkLQ = stats->rxLinkQualityRc;
+ rxLinkStatistics.downlinkLQ = stats->rxLinkQualitySerial;
+ rxLinkStatistics.uplinkRSSI = stats->rxRssi;
+ rxLinkStatistics.uplinkSNR = stats->rxSnr;
+ rxLinkStatistics.activeAntenna = stats->activeAntenna;
+
+ return true;
+}
+
+static bool handleIncoming_MLRS_RADIO_LINK_INFORMATION(uint8_t ingressPortIndex)
+{
+ if (mavlinkContext.recvMsg.compid != MAV_COMP_ID_TELEMETRY_RADIO) {
+ return false;
+ }
+
+ mavlink_mlrs_radio_link_information_t msg;
+ mavlink_msg_mlrs_radio_link_information_decode(&mavlinkContext.recvMsg, &msg);
+
+ if (msg.target_system != mavSystemId) {
+ return false;
+ }
+ if (msg.target_component != 0 && msg.target_component != mavComponentId) {
+ return false;
+ }
+
+ mavlinkMlrsLinkInformationRuntime_t *info = &mavPortStates[ingressPortIndex].mlrs.info;
+ info->valid = true;
+ info->packet = msg;
+ memset(info->modeStr, 0, sizeof(info->modeStr));
+ memset(info->bandStr, 0, sizeof(info->bandStr));
+ memcpy(info->modeStr, msg.mode_str, MAVLINK_MSG_MLRS_RADIO_LINK_INFORMATION_FIELD_MODE_STR_LEN);
+ memcpy(info->bandStr, msg.band_str, MAVLINK_MSG_MLRS_RADIO_LINK_INFORMATION_FIELD_BAND_STR_LEN);
+ info->txPowerMw = mavlinkDbmToMilliwatts(msg.tx_power);
+ info->rxPowerMw = mavlinkDbmToMilliwatts(msg.rx_power);
+ info->txReceiveSensitivityDbm = msg.tx_receive_sensitivity ? -(int16_t)msg.tx_receive_sensitivity : 0;
+ info->rxReceiveSensitivityDbm = msg.rx_receive_sensitivity ? -(int16_t)msg.rx_receive_sensitivity : 0;
+
+ if (!mavlinkIngressPortIsMavlinkSerialRx(ingressPortIndex)) {
+ return true;
+ }
+
+ rxLinkStatistics.uplinkTXPower = info->txPowerMw;
+ rxLinkStatistics.downlinkTXPower = info->rxPowerMw;
+ memset(rxLinkStatistics.band, 0, sizeof(rxLinkStatistics.band));
+ memset(rxLinkStatistics.mode, 0, sizeof(rxLinkStatistics.mode));
+ memcpy(rxLinkStatistics.band, info->bandStr, sizeof(rxLinkStatistics.band) - 1);
+ memcpy(rxLinkStatistics.mode, info->modeStr, sizeof(rxLinkStatistics.mode) - 1);
+ sl_toupperptr(rxLinkStatistics.band);
+ sl_toupperptr(rxLinkStatistics.mode);
+
+ return true;
+}
+
+static bool handleIncoming_MLRS_RADIO_LINK_FLOW_CONTROL(uint8_t ingressPortIndex)
+{
+ if (mavlinkContext.recvMsg.compid != MAV_COMP_ID_TELEMETRY_RADIO) {
+ return false;
+ }
+
+ mavlink_mlrs_radio_link_flow_control_t msg;
+ mavlink_msg_mlrs_radio_link_flow_control_decode(&mavlinkContext.recvMsg, &msg);
+
+ mavlinkMlrsFlowControlRuntime_t *flowControl = &mavPortStates[ingressPortIndex].mlrs.flowControl;
+ flowControl->valid = true;
+ flowControl->packet = msg;
+
+ if (msg.txbuf <= 100) {
+ mavActivePort->txbuffValid = true;
+ mavActivePort->txbuffFree = msg.txbuf;
+ } else {
+ mavActivePort->txbuffValid = false;
+ mavActivePort->txbuffFree = 100;
+ }
+
+ return true;
+}
+
#ifdef USE_ADSB
static bool handleIncoming_ADSB_VEHICLE(void) {
mavlink_adsb_vehicle_t msg;
@@ -237,8 +374,6 @@ static bool handleIncoming_ADSB_VEHICLE(void) {
mavlinkFcDispatchResult_e mavlinkFcDispatchIncomingMessage(uint8_t ingressPortIndex)
{
- UNUSED(ingressPortIndex);
-
switch (mavlinkContext.recvMsg.msgid) {
case MAVLINK_MSG_ID_HEARTBEAT:
return mavlinkHandleIncomingHeartbeat() ? MAVLINK_FC_DISPATCH_HANDLED_ACTIVITY : MAVLINK_FC_DISPATCH_NOT_HANDLED;
@@ -275,6 +410,12 @@ mavlinkFcDispatchResult_e mavlinkFcDispatchIncomingMessage(uint8_t ingressPortIn
case MAVLINK_MSG_ID_ADSB_VEHICLE:
return handleIncoming_ADSB_VEHICLE() ? MAVLINK_FC_DISPATCH_HANDLED_ACTIVITY : MAVLINK_FC_DISPATCH_NOT_HANDLED;
#endif
+ case MAVLINK_MSG_ID_MLRS_RADIO_LINK_STATS:
+ return handleIncoming_MLRS_RADIO_LINK_STATS(ingressPortIndex) ? MAVLINK_FC_DISPATCH_HANDLED_NO_ACTIVITY : MAVLINK_FC_DISPATCH_NOT_HANDLED;
+ case MAVLINK_MSG_ID_MLRS_RADIO_LINK_INFORMATION:
+ return handleIncoming_MLRS_RADIO_LINK_INFORMATION(ingressPortIndex) ? MAVLINK_FC_DISPATCH_HANDLED_NO_ACTIVITY : MAVLINK_FC_DISPATCH_NOT_HANDLED;
+ case MAVLINK_MSG_ID_MLRS_RADIO_LINK_FLOW_CONTROL:
+ return handleIncoming_MLRS_RADIO_LINK_FLOW_CONTROL(ingressPortIndex) ? MAVLINK_FC_DISPATCH_HANDLED_NO_ACTIVITY : MAVLINK_FC_DISPATCH_NOT_HANDLED;
case MAVLINK_MSG_ID_RADIO_STATUS:
handleIncoming_RADIO_STATUS();
return MAVLINK_FC_DISPATCH_HANDLED_NO_ACTIVITY;
diff --git a/src/main/mavlink/mavlink_ports.c b/src/main/mavlink/mavlink_ports.c
index c3b9f81706e..3d17b688eab 100644
--- a/src/main/mavlink/mavlink_ports.c
+++ b/src/main/mavlink/mavlink_ports.c
@@ -29,6 +29,7 @@ void freeMAVLinkTelemetryPortByIndex(uint8_t portIndex)
memset(state->mavMessageNextDue, 0, sizeof(state->mavMessageNextDue));
memset(&state->mavRecvStatus, 0, sizeof(state->mavRecvStatus));
memset(&state->mavRecvMsg, 0, sizeof(state->mavRecvMsg));
+ memset(&state->mlrs, 0, sizeof(state->mlrs));
resetMspPort(&mavTunnelMspPorts[portIndex], NULL);
mavTunnelRemoteSystemIds[portIndex] = 0;
mavTunnelRemoteComponentIds[portIndex] = 0;
@@ -67,6 +68,7 @@ void configureMAVLinkTelemetryPort(uint8_t portIndex)
memset(state->mavMessageNextDue, 0, sizeof(state->mavMessageNextDue));
memset(&state->mavRecvStatus, 0, sizeof(state->mavRecvStatus));
memset(&state->mavRecvMsg, 0, sizeof(state->mavRecvMsg));
+ memset(&state->mlrs, 0, sizeof(state->mlrs));
resetMspPort(&mavTunnelMspPorts[portIndex], NULL);
mavTunnelRemoteSystemIds[portIndex] = 0;
mavTunnelRemoteComponentIds[portIndex] = 0;
diff --git a/src/main/mavlink/mavlink_routing.c b/src/main/mavlink/mavlink_routing.c
index f0b0b373d11..09144962fe4 100644
--- a/src/main/mavlink/mavlink_routing.c
+++ b/src/main/mavlink/mavlink_routing.c
@@ -99,7 +99,8 @@ static uint8_t mavlinkComputeForwardMask(uint8_t ingressPortIndex, int16_t targe
void mavlinkForwardMessage(uint8_t ingressPortIndex, int16_t targetSystem, int16_t targetComponent)
{
- if (mavlinkContext.recvMsg.msgid == MAVLINK_MSG_ID_RADIO_STATUS) {
+ if (mavlinkContext.recvMsg.msgid == MAVLINK_MSG_ID_RADIO_STATUS ||
+ mavlinkContext.recvMsg.msgid == MAVLINK_MSG_ID_MLRS_RADIO_LINK_FLOW_CONTROL) {
return;
}
diff --git a/src/main/mavlink/mavlink_runtime.c b/src/main/mavlink/mavlink_runtime.c
index 6905f0a0209..55573f9d597 100644
--- a/src/main/mavlink/mavlink_runtime.c
+++ b/src/main/mavlink/mavlink_runtime.c
@@ -27,6 +27,34 @@ uint8_t mavlinkGetProtocolVersion(void)
return mavlinkGetCommonConfig()->version;
}
+const mavlinkMlrsPortRuntime_t *mavlinkGetPortMlrsRuntime(uint8_t portIndex)
+{
+ if (portIndex >= mavPortCount) {
+ return NULL;
+ }
+
+ return &mavPortStates[portIndex].mlrs;
+}
+
+const mavlinkMlrsPortRuntime_t *mavlinkGetActiveMlrsRuntime(void)
+{
+ if (!mavActivePort) {
+ return NULL;
+ }
+
+ return &mavActivePort->mlrs;
+}
+
+bool mavlinkPortTxBufferIsValid(uint8_t portIndex)
+{
+ return portIndex < mavPortCount && mavPortStates[portIndex].txbuffValid;
+}
+
+uint8_t mavlinkPortTxBufferFree(uint8_t portIndex)
+{
+ return portIndex < mavPortCount ? mavPortStates[portIndex].txbuffFree : 100;
+}
+
static void mavlinkApplyActivePortOutputVersion(void)
{
mavlink_status_t *chanState = mavlink_get_channel_status(MAVLINK_COMM_0);
diff --git a/src/main/mavlink/mavlink_runtime.h b/src/main/mavlink/mavlink_runtime.h
index da5e1394eac..988b7b552b7 100644
--- a/src/main/mavlink/mavlink_runtime.h
+++ b/src/main/mavlink/mavlink_runtime.h
@@ -2,6 +2,7 @@
#include "common/time.h"
+#include "mavlink/mavlink_types.h"
#include "telemetry/telemetry.h"
void mavlinkRuntimeInit(void);
@@ -12,5 +13,9 @@ void mavlinkRuntimeFreePorts(void);
const mavlinkTelemetryPortConfig_t *mavlinkGetPortConfig(uint8_t portIndex);
const mavlinkTelemetryCommonConfig_t *mavlinkGetCommonConfig(void);
uint8_t mavlinkGetProtocolVersion(void);
+const mavlinkMlrsPortRuntime_t *mavlinkGetPortMlrsRuntime(uint8_t portIndex);
+const mavlinkMlrsPortRuntime_t *mavlinkGetActiveMlrsRuntime(void);
+bool mavlinkPortTxBufferIsValid(uint8_t portIndex);
+uint8_t mavlinkPortTxBufferFree(uint8_t portIndex);
void mavlinkSetActivePortContext(uint8_t portIndex);
void mavlinkSendMessage(void);
diff --git a/src/main/mavlink/mavlink_types.h b/src/main/mavlink/mavlink_types.h
index 27296242d80..42a5b66090d 100644
--- a/src/main/mavlink/mavlink_types.h
+++ b/src/main/mavlink/mavlink_types.h
@@ -73,6 +73,39 @@ typedef struct mavlinkRouteEntry_s {
uint8_t ingressPortIndex;
} mavlinkRouteEntry_t;
+typedef struct mavlinkMlrsLinkStatsRuntime_s {
+ bool valid;
+ bool rssiIsDbm;
+ uint8_t activeAntenna;
+ uint8_t rxLinkQualityRc;
+ uint8_t rxLinkQualitySerial;
+ int16_t rxRssi;
+ int8_t rxSnr;
+ mavlink_mlrs_radio_link_stats_t packet;
+} mavlinkMlrsLinkStatsRuntime_t;
+
+typedef struct mavlinkMlrsLinkInformationRuntime_s {
+ bool valid;
+ char modeStr[MAVLINK_MSG_MLRS_RADIO_LINK_INFORMATION_FIELD_MODE_STR_LEN + 1];
+ char bandStr[MAVLINK_MSG_MLRS_RADIO_LINK_INFORMATION_FIELD_BAND_STR_LEN + 1];
+ uint16_t txPowerMw;
+ uint16_t rxPowerMw;
+ int16_t txReceiveSensitivityDbm;
+ int16_t rxReceiveSensitivityDbm;
+ mavlink_mlrs_radio_link_information_t packet;
+} mavlinkMlrsLinkInformationRuntime_t;
+
+typedef struct mavlinkMlrsFlowControlRuntime_s {
+ bool valid;
+ mavlink_mlrs_radio_link_flow_control_t packet;
+} mavlinkMlrsFlowControlRuntime_t;
+
+typedef struct mavlinkMlrsPortRuntime_s {
+ mavlinkMlrsLinkStatsRuntime_t stats;
+ mavlinkMlrsLinkInformationRuntime_t info;
+ mavlinkMlrsFlowControlRuntime_t flowControl;
+} mavlinkMlrsPortRuntime_t;
+
typedef struct mavlinkPortRuntime_s {
serialPort_t *port;
const serialPortConfig_t *portConfig;
@@ -93,4 +126,5 @@ typedef struct mavlinkPortRuntime_s {
uint32_t txDroppedFrames;
mavlink_message_t mavRecvMsg;
mavlink_status_t mavRecvStatus;
+ mavlinkMlrsPortRuntime_t mlrs;
} mavlinkPortRuntime_t;
diff --git a/src/test/unit/CMakeLists.txt b/src/test/unit/CMakeLists.txt
index e8de17e9959..2fec0b4e62c 100644
--- a/src/test/unit/CMakeLists.txt
+++ b/src/test/unit/CMakeLists.txt
@@ -44,8 +44,9 @@ set_property(SOURCE gimbal_serial_unittest.cc PROPERTY depends "io/gimbal_serial
set_property(SOURCE gimbal_serial_unittest.cc PROPERTY definitions USE_SERIAL_GIMBAL GIMBAL_UNIT_TEST USE_HEADTRACKER)
set_property(SOURCE mavlink_unittest.cc PROPERTY depends
- "fc/fc_mavlink.c" "mavlink/mavlink_mission.c" "mavlink/mavlink_modes.c" "mavlink/mavlink_ports.c" "mavlink/mavlink_routing.c" "mavlink/mavlink_runtime.c"
- "mavlink/mavlink_streams.c" "telemetry/mavlink.c" "common/crc.c" "common/maths.c" "common/streambuf.c" "msp/msp_serial.c")
+ "fc/fc_mavlink.c" "mavlink/mavlink_command.c" "mavlink/mavlink_guided.c" "mavlink/mavlink_mission.c" "mavlink/mavlink_modes.c" "mavlink/mavlink_ports.c"
+ "mavlink/mavlink_routing.c" "mavlink/mavlink_runtime.c" "mavlink/mavlink_streams.c" "telemetry/mavlink.c"
+ "common/crc.c" "common/maths.c" "common/streambuf.c" "common/string_light.c" "msp/msp_serial.c")
set_property(SOURCE mavlink_unittest.cc PROPERTY definitions USE_TELEMETRY USE_TELEMETRY_MAVLINK)
set_property(SOURCE mavlink_unittest.cc PROPERTY includes
"${CMAKE_CURRENT_SOURCE_DIR}/../../../lib/main/MAVLink")
diff --git a/src/test/unit/mavlink_unittest.cc b/src/test/unit/mavlink_unittest.cc
index ba62200e3c7..07f26943b8b 100644
--- a/src/test/unit/mavlink_unittest.cc
+++ b/src/test/unit/mavlink_unittest.cc
@@ -57,6 +57,7 @@ extern "C" {
#include "msp/msp_protocol.h"
#include "msp/msp_serial.h"
+ #include "mavlink/mavlink_runtime.h"
#include "navigation/navigation.h"
#ifdef __cplusplus
#define _Static_assert static_assert
@@ -423,6 +424,228 @@ TEST(MavlinkTelemetryTest, TunnelLargeReplyFragmentsAcrossMultipleMessages)
EXPECT_EQ(collectTunnelPayload(messages), encodeMspV1Reply(testLargeReplyMspCommand, MSP_RESULT_ACK, expectedPayload));
}
+TEST(MavlinkTelemetryTest, MlrsRadioLinkStatsUpdateRxStatisticsOnMavlinkSerialRxPort)
+{
+ initMavlinkTestState();
+
+ telemetryConfigMutable()->mavlink[0].radio_type = MAVLINK_RADIO_MLRS;
+ rxConfigMutable()->receiverType = RX_TYPE_SERIAL;
+ rxConfigMutable()->serialrx_provider = SERIALRX_MAVLINK;
+ testPortConfig.functionMask |= FUNCTION_RX_SERIAL;
+
+ mavlink_message_t msg;
+ mavlink_msg_mlrs_radio_link_stats_pack(
+ testTunnelSourceSystem,
+ MAV_COMP_ID_TELEMETRY_RADIO,
+ &msg,
+ telemetryConfig()->mavlink_common.sysid,
+ testTargetComponent,
+ MLRS_RADIO_LINK_STATS_FLAGS_RSSI_DBM | MLRS_RADIO_LINK_STATS_FLAGS_RX_RECEIVE_ANTENNA2,
+ 91,
+ 77,
+ 100,
+ 7,
+ 55,
+ 120,
+ 9,
+ 111,
+ 11,
+ 130,
+ 13,
+ 0.0f,
+ 0.0f);
+
+ pushRxMessage(&msg);
+ handleMAVLinkTelemetry(1000);
+
+ const mavlinkMlrsPortRuntime_t *mlrs = mavlinkGetPortMlrsRuntime(0);
+ ASSERT_NE(mlrs, nullptr);
+ EXPECT_TRUE(mlrs->stats.valid);
+ EXPECT_TRUE(mlrs->stats.rssiIsDbm);
+ EXPECT_EQ(mlrs->stats.rxLinkQualityRc, 91);
+ EXPECT_EQ(mlrs->stats.rxLinkQualitySerial, 77);
+ EXPECT_EQ(mlrs->stats.activeAntenna, 1);
+ EXPECT_EQ(mlrs->stats.rxRssi, -111);
+ EXPECT_EQ(mlrs->stats.rxSnr, 11);
+ EXPECT_EQ(rxLinkStatistics.uplinkLQ, 91);
+ EXPECT_EQ(rxLinkStatistics.downlinkLQ, 77);
+ EXPECT_EQ(rxLinkStatistics.uplinkRSSI, -111);
+ EXPECT_EQ(rxLinkStatistics.uplinkSNR, 11);
+ EXPECT_EQ(rxLinkStatistics.activeAntenna, 1);
+}
+
+TEST(MavlinkTelemetryTest, MlrsRadioLinkStatsStayCachedOffReceiverPort)
+{
+ initMavlinkTestState();
+
+ telemetryConfigMutable()->mavlink[0].radio_type = MAVLINK_RADIO_MLRS;
+
+ mavlink_message_t msg;
+ mavlink_msg_mlrs_radio_link_stats_pack(
+ testTunnelSourceSystem,
+ MAV_COMP_ID_TELEMETRY_RADIO,
+ &msg,
+ telemetryConfig()->mavlink_common.sysid,
+ testTargetComponent,
+ MLRS_RADIO_LINK_STATS_FLAGS_RSSI_DBM,
+ 65,
+ 44,
+ 101,
+ 6,
+ 33,
+ 121,
+ 8,
+ 0,
+ INT8_MAX,
+ 0,
+ INT8_MAX,
+ 0.0f,
+ 0.0f);
+
+ pushRxMessage(&msg);
+ handleMAVLinkTelemetry(1000);
+
+ const mavlinkMlrsPortRuntime_t *mlrs = mavlinkGetPortMlrsRuntime(0);
+ ASSERT_NE(mlrs, nullptr);
+ EXPECT_TRUE(mlrs->stats.valid);
+ EXPECT_EQ(mlrs->stats.rxLinkQualityRc, 65);
+ EXPECT_EQ(mlrs->stats.rxLinkQualitySerial, 44);
+ EXPECT_EQ(mlrs->stats.rxRssi, -101);
+ EXPECT_EQ(mlrs->stats.rxSnr, 6);
+ EXPECT_EQ(rxLinkStatistics.uplinkLQ, 0);
+ EXPECT_EQ(rxLinkStatistics.downlinkLQ, 0);
+ EXPECT_EQ(rxLinkStatistics.uplinkRSSI, 0);
+ EXPECT_EQ(rxLinkStatistics.uplinkSNR, 0);
+}
+
+TEST(MavlinkTelemetryTest, MlrsRadioLinkInformationUpdatesReceiverFacingMetadata)
+{
+ initMavlinkTestState();
+
+ telemetryConfigMutable()->mavlink[0].radio_type = MAVLINK_RADIO_MLRS;
+ rxConfigMutable()->receiverType = RX_TYPE_SERIAL;
+ rxConfigMutable()->serialrx_provider = SERIALRX_MAVLINK;
+ testPortConfig.functionMask |= FUNCTION_RX_SERIAL;
+
+ mavlink_message_t msg;
+ mavlink_msg_mlrs_radio_link_information_pack(
+ testTunnelSourceSystem,
+ MAV_COMP_ID_TELEMETRY_RADIO,
+ &msg,
+ telemetryConfig()->mavlink_common.sysid,
+ testTargetComponent,
+ MLRS_RADIO_LINK_TYPE_MLRS,
+ 3,
+ 20,
+ 10,
+ 50,
+ 50,
+ "50HZ",
+ "915",
+ 9600,
+ 4800,
+ 115,
+ 117);
+
+ pushRxMessage(&msg);
+ handleMAVLinkTelemetry(1000);
+
+ const mavlinkMlrsPortRuntime_t *mlrs = mavlinkGetPortMlrsRuntime(0);
+ ASSERT_NE(mlrs, nullptr);
+ EXPECT_TRUE(mlrs->info.valid);
+ EXPECT_STREQ(mlrs->info.modeStr, "50HZ");
+ EXPECT_STREQ(mlrs->info.bandStr, "915");
+ EXPECT_EQ(mlrs->info.txPowerMw, 100);
+ EXPECT_EQ(mlrs->info.rxPowerMw, 10);
+ EXPECT_EQ(mlrs->info.txReceiveSensitivityDbm, -115);
+ EXPECT_EQ(mlrs->info.rxReceiveSensitivityDbm, -117);
+ EXPECT_EQ(rxLinkStatistics.uplinkTXPower, 100);
+ EXPECT_EQ(rxLinkStatistics.downlinkTXPower, 10);
+ EXPECT_STREQ(rxLinkStatistics.band, "915");
+ EXPECT_STREQ(rxLinkStatistics.mode, "50HZ");
+}
+
+TEST(MavlinkTelemetryTest, MlrsFlowControlUsesIngressPortAndAcceptsZeroTxbuf)
+{
+ initMavlinkTestState();
+
+ mavlink_message_t msg;
+ mavlink_msg_mlrs_radio_link_flow_control_pack(
+ testTunnelSourceSystem,
+ MAV_COMP_ID_TELEMETRY_RADIO,
+ &msg,
+ 9600,
+ 4800,
+ 90,
+ 40,
+ 0);
+
+ pushRxMessage(&msg);
+ handleMAVLinkTelemetry(1000);
+
+ const mavlinkMlrsPortRuntime_t *mlrs = mavlinkGetPortMlrsRuntime(0);
+ ASSERT_NE(mlrs, nullptr);
+ EXPECT_TRUE(mlrs->flowControl.valid);
+ EXPECT_EQ(mlrs->flowControl.packet.txbuf, 0);
+ EXPECT_TRUE(mavlinkPortTxBufferIsValid(0));
+ EXPECT_EQ(mavlinkPortTxBufferFree(0), 0);
+}
+
+TEST(MavlinkTelemetryTest, MlrsMessagesRequireTelemetryRadioComponent)
+{
+ initMavlinkTestState();
+
+ telemetryConfigMutable()->mavlink[0].radio_type = MAVLINK_RADIO_MLRS;
+ rxConfigMutable()->receiverType = RX_TYPE_SERIAL;
+ rxConfigMutable()->serialrx_provider = SERIALRX_MAVLINK;
+ testPortConfig.functionMask |= FUNCTION_RX_SERIAL;
+
+ mavlink_message_t statsMsg;
+ mavlink_msg_mlrs_radio_link_stats_pack(
+ testTunnelSourceSystem,
+ testTunnelSourceComponent,
+ &statsMsg,
+ telemetryConfig()->mavlink_common.sysid,
+ testTargetComponent,
+ MLRS_RADIO_LINK_STATS_FLAGS_RSSI_DBM,
+ 91,
+ 77,
+ 100,
+ 7,
+ 55,
+ 120,
+ 9,
+ 0,
+ INT8_MAX,
+ 0,
+ INT8_MAX,
+ 0.0f,
+ 0.0f);
+ pushRxMessage(&statsMsg);
+
+ mavlink_message_t flowControlMsg;
+ mavlink_msg_mlrs_radio_link_flow_control_pack(
+ testTunnelSourceSystem,
+ testTunnelSourceComponent,
+ &flowControlMsg,
+ 9600,
+ 4800,
+ 90,
+ 40,
+ 10);
+ pushRxMessage(&flowControlMsg);
+
+ handleMAVLinkTelemetry(1000);
+
+ const mavlinkMlrsPortRuntime_t *mlrs = mavlinkGetPortMlrsRuntime(0);
+ ASSERT_NE(mlrs, nullptr);
+ EXPECT_FALSE(mlrs->stats.valid);
+ EXPECT_FALSE(mlrs->flowControl.valid);
+ EXPECT_EQ(rxLinkStatistics.uplinkLQ, 0);
+ EXPECT_FALSE(mavlinkPortTxBufferIsValid(0));
+ EXPECT_EQ(mavlinkPortTxBufferFree(0), 100);
+}
+
TEST(MavlinkTelemetryTest, AttitudeUsesRadiansPerSecond)
{
initMavlinkTestState();