ATTITUDE
Summary
The ATTITUDE message provides the vehicle's orientation in three-dimensional space using Euler angles (Roll, Pitch, and Yaw). It also includes the angular velocity (rotation rates) for each axis. This is the primary telemetry packet used by Ground Control Stations to drive the Artificial Horizon and heading indicators.
Status
Supported
Directionality
- TX (Transmit): All Vehicles (Reports orientation to GCS)
- RX (Receive): None (Ignored)
Transmission (TX)
The transmission logic resides in GCS_MAVLINK::send_attitude within libraries/GCS_MAVLink/GCS_Common.cpp:5816.
Data Sourcing
- State Estimator: Data is retrieved directly from the
AP_AHRS(Attitude and Heading Reference System) library, which fuses data from the IMU, Compass, and GPS. - Format:
roll,pitch,yaw: Provided in radians.rollspeed,pitchspeed,yawspeed: Angular velocity in rad/s.
- Timestamp: Uses
AP_HAL::millis()since boot.
Scheduling
- Sent as part of the
MSG_ATTITUDEstream. - Triggered in
GCS_Common.cpp:6065within thetry_send_messageloop. - High-frequency message: Typically streamed at 20Hz - 50Hz for a smooth UI experience.
Data Fields
time_boot_ms: Timestamp (milliseconds since system boot).roll: Roll angle (rad, -pi..+pi).pitch: Pitch angle (rad, -pi..+pi).yaw: Yaw angle (rad, -pi..+pi).rollspeed: Roll angular speed (rad/s).pitchspeed: Pitch angular speed (rad/s).yawspeed: Yaw angular speed (rad/s).
Practical Use Cases
- Artificial Horizon:
- Scenario: A pilot is flying FPV (First Person View) through thick fog.
- Action: The GCS HUD uses the
rollandpitchvalues to draw a virtual horizon, allowing the pilot to maintain level flight without visual cues from the camera.
- Heading Lock Verification:
- Scenario: During an AUTO mission, the user wants to ensure the drone is pointing toward the next waypoint.
- Action: The GCS monitors the
yawfield and compares it against the "Desired Yaw" to verify the flight controller is tracking the path correctly.
- Vibration/Buffeting Detection:
- Scenario: A plane is flying in high turbulence.
- Action: A developer analyzes the
rollspeedandpitchspeedfields to quantify how much the airframe is being shaken by external forces.
Key Codebase Locations
- libraries/GCS_MAVLink/GCS_Common.cpp:5816: Implementation of
send_attitude. - libraries/AP_AHRS/AP_AHRS.h: Source of orientation data.
ATTITUDE_QUATERNION
Summary
The ATTITUDE_QUATERNION message provides the vehicle's orientation using unit quaternions ($q_w, q_x, q_y, q_z$). While Euler angles (used in the ATTITUDE message) are more intuitive for human pilots, quaternions are mathematically superior for 3D visualization and navigation algorithms because they avoid "Gimbal Lock"—a state where orientation becomes ambiguous at 90 degrees of pitch.
Status
Supported
Directionality
- TX (Transmit): All Vehicles (Advanced orientation telemetry)
- RX (Receive): None (Ignored)
Transmission (TX)
The transmission logic resides in GCS_MAVLINK::send_attitude_quaternion within libraries/GCS_MAVLink/GCS_Common.cpp:5833.
Data Sourcing
- Source: Data is retrieved from the
AP_AHRSlibrary viaAP::[ahrs](/field-manual/mavlink-interface/ahrs.html)().get_quaternion(). - Fields:
q1($q_w$),q2($q_x$),q3($q_y$),q4($q_z$): Normalized components of the attitude quaternion.rollspeed,pitchspeed,yawspeed: Angular velocity in rad/s (same as ID 30).
- Timestamp: Uses
AP_HAL::millis()since boot.
Scheduling
- Sent as part of the
MSG_ATTITUDE_QUATERNIONstream. - Triggered in
GCS_Common.cpp:6070within thetry_send_messageloop.
Data Fields
time_boot_ms: Timestamp (milliseconds since system boot).q1: Quaternion component 1, w (1 in null-rotation).q2: Quaternion component 2, x (0 in null-rotation).q3: Quaternion component 3, y (0 in null-rotation).q4: Quaternion component 4, z (0 in null-rotation).rollspeed: Roll angular speed (rad/s).pitchspeed: Pitch angular speed (rad/s).yawspeed: Yaw angular speed (rad/s).
Practical Use Cases
- 3D Model Rendering:
- Scenario: A Ground Control Station displays a high-fidelity 3D model of the drone that rotates in real-time.
- Action: The renderer uses the quaternion data to update the model's rotation matrix. This ensures smooth movement even during vertical climbs or aerobatic maneuvers where Euler angles might glitch.
- VR/AR HUDs:
- Scenario: A pilot is using AR (Augmented Reality) glasses to see the drone's attitude overlaid on their real-world vision.
- Action: Quaternions are used to align the virtual horizon precisely with the headset's inertial frame without complex trigonometric conversions.
- Advanced Log Analysis:
- Scenario: A researcher is analyzing the stability of a new airframe design.
- Action: By using quaternions, the researcher can accurately calculate the error between "Desired" and "Actual" orientation throughout the entire sphere of rotation.
Key Codebase Locations
- libraries/GCS_MAVLink/GCS_Common.cpp:5833: Implementation of
send_attitude_quaternion. - libraries/AP_AHRS/AP_AHRS.h: Source of quaternion data.
LOCAL_POSITION_NED
Summary
The LOCAL_POSITION_NED message provides the vehicle's position and velocity in a local North-East-Down (NED) coordinate system. Unlike GLOBAL_POSITION_INT, which uses Latitude/Longitude, this message uses meters relative to a fixed local "Origin" (usually the EKF origin established at boot or GPS lock). It is essential for navigation in environments where relative distance is more critical than absolute global coordinates.
Status
Supported
Directionality
- TX (Transmit): All Vehicles (Local state telemetry)
- RX (Receive): None (Use
VISION_POSITION_ESTIMATEorODOMETRYfor external input)
Transmission (TX)
The transmission logic resides in GCS_MAVLINK::send_local_position within libraries/GCS_MAVLink/GCS_Common.cpp:2979.
Data Sourcing
- State Estimator: Data is retrieved from the
AP_AHRSlibrary. - Position: Sourced via
[ahrs](/field-manual/mavlink-interface/ahrs.html).get_relative_position_NED_origin(). This returns meters North, East, and Down relative to the EKF origin. - Velocity: Sourced via
ahrs.get_velocity_NED(), providing ground speed components in m/s. - Timestamp: Uses
AP_HAL::millis()since boot.
Scheduling
- Sent as part of the
MSG_LOCAL_POSITIONstream. - Triggered in
GCS_Common.cpp:6134within thetry_send_messageloop.
Data Fields
time_boot_ms: Timestamp (milliseconds since system boot).x: X Position (meters).y: Y Position (meters).z: Z Position (meters).vx: X Speed (m/s).vy: Y Speed (m/s).vz: Z Speed (m/s).
Practical Use Cases
- Indoor Flight Visualization:
- Scenario: A drone is flying in a warehouse using Optical Flow and has no GPS.
- Action: The GCS uses
LOCAL_POSITION_NEDto draw the drone's path on a blank grid, as Latitude/Longitude are either unavailable or inaccurate.
- Swarm Coordination:
- Scenario: Multiple drones are performing a light show.
- Action: An orchestrating computer monitors the NED coordinates of all drones to ensure they maintaining the correct relative spacing in their "stage" coordinate system.
- Visual Odometry Debugging:
- Scenario: A developer is integrating a Realsense T265 camera for external positioning.
- Action: The developer compares the vehicle's reported
LOCAL_POSITION_NED(the EKF's fused result) against the raw camera output to tune the EKF's trust in the external sensor.
Key Codebase Locations
- libraries/GCS_MAVLink/GCS_Common.cpp:2979: Implementation of
send_local_position. - libraries/AP_AHRS/AP_AHRS.h: Provides the relative position and velocity data.
GLOBAL_POSITION_INT
Summary
The GLOBAL_POSITION_INT message is the primary source of absolute geographic positioning data in MAVLink. It provides the vehicle's Latitude, Longitude, and Altitude (both AMSL and relative to Home) using integer representation for high efficiency and precision. It is the core message used by Ground Control Stations for map plotting and altitude display.
Status
Supported
Directionality
- TX (Transmit): All Vehicles (Primary position telemetry)
- RX (Receive): All Vehicles (Used for "Follow Me" and Multi-Vehicle Avoidance)
Transmission (TX)
The transmission logic resides in GCS_MAVLINK::send_global_position_int within libraries/GCS_MAVLink/GCS_Common.cpp:5872.
Data Sourcing
- Coordinate Source: Data is fused by the EKF and provided by the
AP_AHRSlibrary via[ahrs](/field-manual/mavlink-interface/ahrs.html).get_location(). - Format:
lat,lon: Sourced in $degrees \times 10^7$.alt: Altitude Above Mean Sea Level (AMSL) in millimeters.relative_alt: Altitude relative to the Home position in millimeters.heading: Vehicle yaw sourced fromahrs.yaw_sensorin centidegrees ($0$ to $35999$).vx,vy,vz: Ground speed components in cm/s.
Scheduling
- Sent as part of the
MSG_GLOBAL_POSITION_INTstream. - Triggered in
GCS_Common.cpp:6102within thetry_send_messageloop.
Reception (RX)
ArduPilot handles this message in various specialized libraries, most notably AP_Follow and AP_Avoidance.
- Follow Me: In libraries/AP_Follow/AP_Follow.cpp, ArduPilot receives
GLOBAL_POSITION_INTfrom a "Lead" vehicle or a GCS to track and follow its position in real-time. - ADSB/Avoidance: Used to track the positions of other MAVLink-enabled vehicles in the vicinity to trigger collision avoidance maneuvers.
Data Fields
time_boot_ms: Timestamp (milliseconds since system boot).lat: Latitude, expressed as degrees * 1E7.lon: Longitude, expressed as degrees * 1E7.alt: Altitude (MSL). Note that virtually all GPS modules provide both WGS84 and MSL.relative_alt: Altitude above the home position.vx: Ground X Speed (Latitude, positive north).vy: Ground Y Speed (Longitude, positive east).vz: Ground Z Speed (Altitude, positive down).hdg: Vehicle heading (max 65535, valid 0-35999).
Practical Use Cases
- GCS Map Display:
- Scenario: A pilot is flying a 10km long-range mission.
- Action: The GCS uses
latandlonto update the vehicle's position on the map at high frequency (typically 5Hz - 10Hz).
- Terrain Following Verification:
- Scenario: A drone is flying 10m above a sloping hill.
- Action: The pilot monitors
relative_altto ensure the vehicle is maintaining the correct height relative to the take-off point, regardless of the absolute AMSL altitude.
- Lead-Follow Swarming:
- Scenario: A "Follower" drone is slaved to a "Leader" drone.
- Action: The Follower receives the Leader's
GLOBAL_POSITION_INTand calculates the required offset to maintain its position in the formation.
Key Codebase Locations
- libraries/GCS_MAVLink/GCS_Common.cpp:5872: TX implementation.
- libraries/AP_Follow/AP_Follow.cpp: RX implementation for vehicle following.
- libraries/AP_AHRS/AP_AHRS.h:586: Source of
yaw_sensordata.
ATTITUDE_QUATERNION_COV
Summary
The attitude in the aeronautical frame, expressed as quaternion, with covariance.
Status
Unsupported
Directionality
- TX (Transmit): None
- RX (Receive): None
Description
ArduPilot does not implement this message. It uses ATTITUDE_QUATERNION (31) or ATTITUDE (30) for attitude reporting.
Theoretical Use Cases
Attitude reporting with uncertainty.
GLOBAL_POSITION_INT_COV
Summary
The filtered global position with covariance.
Status
Unsupported
Directionality
- TX (Transmit): None
- RX (Receive): None
Description
ArduPilot does not implement this message. It uses GLOBAL_POSITION_INT (33) for position reporting.
Theoretical Use Cases
Position reporting with uncertainty.
LOCAL_POSITION_NED_COV
Summary
The filtered local position with covariance.
Status
Unsupported
Directionality
- TX (Transmit): None
- RX (Receive): None
Description
ArduPilot does not implement this message. It uses LOCAL_POSITION_NED (32) for local position reporting.
Theoretical Use Cases
Local position reporting with uncertainty.
DATA_STREAM
Summary
Data stream status information.
Status
Unsupported
Directionality
- TX (Transmit): None
- RX (Receive): None
Description
ArduPilot does not implement this message (neither sending nor receiving).
Theoretical Use Cases
Reporting the status of a data stream.
VFR_HUD
Summary
The VFR_HUD (Visual Flight Rules Head-Up Display) message is a bandwidth-optimized packet designed specifically to drive the dashboard instruments of a Ground Control Station. It aggregates the most critical flight metrics—speed, altitude, heading, throttle, and vertical speed—into a single 20-byte payload, reducing the need for the GCS to parse multiple high-frequency streams like ATTITUDE and GLOBAL_POSITION_INT.
Status
Supported
Directionality
- TX (Transmit): All Vehicles (Summary telemetry)
- RX (Receive): None (Ignored)
Transmission (TX)
The transmission logic resides in GCS_MAVLINK::send_vfr_hud within libraries/GCS_MAVLink/GCS_Common.cpp:3390.
Data Sourcing
ArduPilot uses vehicle-specific virtual functions to populate the fields:
airspeed: Sourced from theAP_Airspeedlibrary. If no airspeed sensor is present, ArduPilot may fall back to an EKF wind-speed estimate.groundspeed: Provided byAP::[ahrs](/field-manual/mavlink-interface/ahrs.html)().groundspeed()in m/s.heading: Provided byAP::ahrs().yaw_sensorin degrees ($0$-$360$).throttle: Represented as a percentage ($0$-$100$). For Copters, this is derived from the motor mixer's average output.alt: Current altitude Above Mean Sea Level (AMSL) in meters.climb: Vertical velocity (climb rate) in m/s.
Bandwidth Optimization
VFR_HUD is the "Swiss Army Knife" of telemetry. By streaming this single message at 5Hz-10Hz, a GCS can maintain a fully functional HUD even on very low-bandwidth links (like long-range 915MHz radios) where sending full position and attitude packets would cause lag.
Data Fields
airspeed: Current airspeed in m/s.groundspeed: Current ground speed in m/s.heading: Current heading in degrees, in compass units (0..360, 0=north).throttle: Current throttle setting in integer percent, 0 to 100.alt: Current altitude (MSL), in meters.climb: Current climb rate in meters/second.
Practical Use Cases
- Dashboard Telemetry:
- Scenario: A pilot is flying a long-range FPV mission.
- Action: The GCS HUD uses
VFR_HUDas the primary source for the Speed Tape, Altimeter Tape, and Compass Rose.
- Stall Prevention:
- Scenario: A fixed-wing plane is performing an autonomous climb.
- Action: The pilot monitors the
airspeedfield in the HUD. If it drops toward the "Stall Speed" (calculated GCS-side), the pilot can take manual control or adjust the throttle.
- Variometer Feedback:
- Scenario: A glider pilot is looking for thermals.
- Action: The
climbrate field is used to drive an audio variometer (beeping) on the ground station, helping the pilot identify rising air.
Key Codebase Locations
- libraries/GCS_MAVLink/GCS_Common.cpp:3390: Common implementation.
- ArduPlane/GCS_Mavlink.cpp:277: Plane-specific airspeed and throttle logic.
- ArduCopter/GCS_Mavlink.cpp:246: Copter-specific throttle logic.
Summary
The LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET message is defined in MAVLink to provide the offset between a local North-East-Down (NED) coordinate system and the global Latitude/Longitude frame. ArduPilot does not implement or transmit this message.
Status
Unsupported
Directionality
- TX (Transmit): None
- RX (Receive): None (Ignored)
Analysis
ArduPilot handles the relationship between local and global coordinates internally within the EKF (Extended Kalman Filter) and the AP_AHRS library. The origin of the local coordinate system is established relative to the home position or a fixed global coordinate, and this mapping is exposed through other messages like HOME_POSITION (242) and GLOBAL_POSITION_INT (33).
- Absence: There is no handler for ID 89 in the
GCS_MAVLinklibraries. - Alternative: To find the relationship between local NED and global coordinates, a GCS should compare
LOCAL_POSITION_NED(32) againstGLOBAL_POSITION_INT(33) or query theHOME_POSITION(242).
Data Fields (Standard)
time_boot_ms: Timestamp (milliseconds since system boot).x: X Position (meters).y: Y Position (meters).z: Z Position (meters).roll: Roll (rad).pitch: Pitch (rad).yaw: Yaw (rad).
Key Codebase Locations
- libraries/GCS_MAVLink/GCS_Common.cpp: Lacks a handler for ID 89.
RADIO_STATUS
Summary
Status reports from a 3DR/SiK-compatible telemetry radio.
Status
Supported (RX Only)
Directionality
- TX (Transmit): None
- RX (Receive): All Vehicles - Processed for link quality and flow control.
Reception (RX)
Handled by GCS_MAVLINK::handle_radio_status. This message is functionally identical to RADIO (166) in ArduPilot's handling logic.
Source: libraries/GCS_MAVLink/GCS_Common.cpp
Protocol Logic
See RADIO (166). The handler updates RSSI and TX Buffer stats to perform adaptive flow control.
Data Fields
rssi: Local signal strength.remrssi: Remote signal strength.txbuf: Transmit buffer remaining %.noise: Background noise.remnoise: Remote background noise.rxerrors: Receive errors.fixed: Corrected packets.
Practical Use Cases
- Telemetry Health:
- Scenario: Monitoring link quality.
- Action: GCS uses
remrssito show the signal bars for the drone's radio.
Key Codebase Locations
- libraries/GCS_MAVLink/GCS_Common.cpp:862: Handler.
ALTITUDE
Summary
The ALTITUDE message provides a dedicated high-precision altitude report, separating monotonic (continuous), AMSL (Above Mean Sea Level), local, relative, and terrain-relative altitudes. This message is designed to resolve ambiguity between different altitude frames.
Status
Unsupported
Directionality
- TX (Transmit): None
- RX (Receive): None
Description
ArduPilot does not currently broadcast this message.
Instead, ArduPilot reports altitude via:
GLOBAL_POSITION_INT(33): Containsalt(AMSL) andrelative_alt(Above Home).VFR_HUD(74): Containsalt(AMSL) for HUD displays.TERRAIN_REPORT(136): Contains terrain height and current height above terrain.
Intended Data Fields (Standard)
time_usec: Timestamp (micros).altitude_monotonic: Monotonic altitude (never resets).altitude_amsl: Altitude above mean sea level.altitude_local: Local altitude (relative to 0,0,0 origin).altitude_relative: Relative altitude (above home).altitude_terrain: Altitude above terrain.bottom_clearance: Distance to bottom surface (ground/water).
CONTROL_SYSTEM_STATE
Summary
The CONTROL_SYSTEM_STATE message is defined in MAVLink to provide a unified, high-frequency "State Vector" (Position, Velocity, Acceleration, Attitude, and Rates) to external controllers or companion computers. ArduPilot does not implement or transmit this message.
Status
Unsupported
Directionality
- TX (Transmit): None
- RX (Receive): None (Ignored)
Analysis
ArduPilot prefers to send its state estimation data through individual, specialized messages that are better integrated with its EKF (Extended Kalman Filter) architecture:
- Orientation:
ATTITUDE(30) orATTITUDE_QUATERNION(31). - Position:
LOCAL_POSITION_NED(32) orGLOBAL_POSITION_INT(33). - High-Frequency Data:
HIGHRES_IMU(105). - Filter Health:
EKF_STATUS_REPORT(ArduPilot Custom).
By using these discrete messages, ArduPilot ensures compatibility with a wider range of Ground Control Stations and reduces the bandwidth required for users who only need a subset of the state data.
Data Fields
time_usec: Timestamp (microseconds since UNIX epoch or microseconds since system boot).x_acc: X acceleration in body frame.y_acc: Y acceleration in body frame.z_acc: Z acceleration in body frame.x_vel: X velocity in body frame.y_vel: Y velocity in body frame.z_vel: Z velocity in body frame.x_pos: X position in local frame.y_pos: Y position in local frame.z_pos: Z position in local frame.airspeed: Airspeed.vel_variance: Variance of velocity.pos_variance: Variance of position.q: The attitude, represented as Quaternion.roll_rate: Angular rate in roll axis.pitch_rate: Angular rate in pitch axis.yaw_rate: Angular rate in yaw axis.
Key Codebase Locations
- libraries/GCS_MAVLink/GCS_Common.cpp: Lacks a handler or mapping for ID 146.
BATTERY_STATUS
Summary
The BATTERY_STATUS message provides a comprehensive report on the vehicle's power source health. Unlike the simpler SYS_STATUS (which only reports total voltage and current), BATTERY_STATUS supports multiple battery instances and provides detailed information including individual cell voltages, temperature, and remaining capacity. This is the primary message used by Ground Control Stations for advanced battery telemetry and "Smart Battery" integration.
Status
Supported (Critical)
Directionality
- TX (Transmit): All Vehicles (Broadcasts battery state)
- RX (Receive): None (Ignored)
Transmission (TX)
The transmission logic is centered in GCS_MAVLINK::send_battery_status within libraries/GCS_MAVLink/GCS_Common.cpp:266.
Data Sourcing
- Multiple Instances: ArduPilot iterates through all active battery monitors configured via the
BATT_MONITORparameters. It sends a separateBATTERY_STATUSpacket for each, using theidfield to distinguish them. - Cell Voltages:
- Standard (1-10): The message reports up to 10 cell voltages in the
voltagesarray (in millivolts). - Extended (11-14): ArduPilot uses MAVLink extensions to report cells 11 through 14 in the
voltages_extfield.
- Standard (1-10): The message reports up to 10 cell voltages in the
- Temperature: If the battery monitor backend supports it (e.g., SMBus or DroneCAN), the internal battery temperature is reported in centidegrees Celsius.
- Current and Capacity: Sourced from the
AP_BattMonitorlibrary, providingcurrent_consumed(mAh) andbattery_remaining(percentage).
Data Fields
id: Battery ID.battery_function: Function of the battery.type: Type (chemistry) of the battery.temperature: Temperature in centi-degrees Celsius.voltages: Battery voltage of cells, in millivolts (1 = 1 millivolt).current_battery: Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current.current_consumed: Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide consumption estimate.energy_consumed: Consumed energy, in 100*Joules (interrim test).battery_remaining: Remaining battery energy. (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery.time_remaining: Remaining battery time, 0: autopilot does not provide remaining battery time estimate.charge_state: State for additional protection, see MAV_BATTERY_CHARGE_STATE.voltages_ext: Battery voltages for cells 11-14.mode: Battery mode.fault_bitmask: Fault/health indications.
Practical Use Cases
- Individual Cell Health Monitoring:
- Smart Battery Integration:
- Scenario: A drone is equipped with a Tattu or Grepow Smart Battery that communicates via SMBus.
- Action: ArduPilot reads the battery's internal cycle count and temperature and relays this via
BATTERY_STATUS. The GCS displays this information, helping the operator track the long-term health of their battery fleet.
- Dual Battery Redundancy:
- Scenario: A drone uses two parallel batteries for redundancy.
- Action: The GCS displays two separate battery widgets (ID 0 and ID 1). If one battery starts drawing significantly more current than the other, it indicates a connector issue or an aging pack.
Key Codebase Locations
- libraries/GCS_MAVLink/GCS_Common.cpp:266: Implementation of the MAVLink packet construction.
- libraries/AP_BattMonitor/AP_BattMonitor.cpp: Primary source for all battery-related data.
AHRS
Summary
The AHRS message reports the internal state of the Attitude Heading Reference System (AHRS), specifically focusing on gyro drift estimates and attitude error metrics. It is useful for monitoring the health and convergence of the EKF or DCM estimator.
Status
Supported
Directionality
- TX (Transmit): All Vehicles (Reports AHRS health)
- RX (Receive): None (Ignored)
Transmission (TX)
Transmission is handled by GCS_MAVLINK::send_ahrs within libraries/GCS_MAVLink/GCS_Common.cpp:2424.
Data Fields
omegaIx: X gyro drift estimate (rad/s).omegaIy: Y gyro drift estimate (rad/s).omegaIz: Z gyro drift estimate (rad/s).accel_weight: Average accel_weight (0 to 1). Currently sent as 0.renorm_val: Average renormalisation value (0 to 1). Currently sent as 0.error_rp: Average error_roll_pitch value (0 to 1).error_yaw: Average error_yaw value (0 to 1).
Practical Use Cases
- Vibration Diagnosis:
- Scenario: A user experiences "EKS FAIL" warnings.
- Action: Analyzing
omegaIx/y/zin the logs can reveal if the gyro bias estimates are fluctuating wildly, often a sign of excessive vibration or a failing IMU.
- Magnetic Interference:
- Scenario: A rover's heading drifts during a turn.
- Action:
error_yawincreasing indicates the compass reading disagrees with the gyro integration, potentially due to magnetic interference from motors.
Key Codebase Locations
- libraries/GCS_MAVLink/GCS_Common.cpp:2424: Implementation of the sender.
RADIO
Summary
Status reports from a 3DR/SiK-compatible telemetry radio. These messages are typically generated locally by the telemetry radio firmware and injected into the autopilot's serial stream to report link quality and buffer status.
Status
Supported (RX Only)
Directionality
- TX (Transmit): None
- RX (Receive): All Vehicles - ArduPilot parses this message to monitor link quality and perform adaptive flow control.
Reception (RX)
ArduPilot processes this message in GCS_MAVLINK::handle_radio_status. The primary use is Adaptive Flow Control. The system monitors the radio's transmit buffer (txbuf) to dynamically adjust the rate at which MAVLink streams are sent.
Source: libraries/GCS_MAVLink/GCS_Common.cpp
Protocol Logic
- RSSI Tracking: Updates
last_radio_status.rssiandlast_radio_status.remrssi(Remote RSSI). - Flow Control: Checks
packet.txbuf(Remaining Free Space %):- < 20%: Radio buffer full. Increases
stream_slowdown_mssignificantly (slows down telemetry). - < 50%: Radio buffer getting full. Increases
stream_slowdown_msslightly. - > 95%: Buffer empty. Decreases
stream_slowdown_mssignificantly (speeds up telemetry). - > 90%: Buffer mostly empty. Decreases
stream_slowdown_msslightly.
- < 20%: Radio buffer full. Increases
- Logging: Writes a
RAD(Radio) log entry to the onboard SD card dataflash log.
Data Fields
rssi: Local signal strength (0-255). Often scaled to percentage.remrssi: Remote signal strength (0-255).txbuf: Remaining free space in the radio's transmit buffer (0-100%).noise: Background noise level.remnoise: Remote background noise level.rxerrors: Count of receive errors.fixed: Count of corrected packets.
Practical Use Cases
-
Telemetry Link Optimization:
- Scenario: User is flying at long range with a SiK telemetry radio.
- Action: As the radio link degrades or the bandwidth saturates, the radio reports low
txbuf. ArduPilot automatically throttles the stream rate (Hz) of attitude/GPS updates to prevent packet loss and latency buildup.
-
Link Quality Monitoring:
- Scenario: Post-flight analysis of a mission.
- Action: The user reviews the
RADlog messages to see a graph of RSSI vs Distance, helping to verify antenna placement and noise floor issues.
Key Codebase Locations
- libraries/GCS_MAVLink/GCS_Common.cpp:862:
handle_radio_statusimplementation.
DATA16
Summary
Generic 16-byte data packet. In ArduPilot, this is used exclusively by the AP_Radio library to facilitate firmware updates for attached telemetry radios (like the Cypress or CC2500 based radios).
Status
Supported (TX Only)
Directionality
- TX (Transmit): Specific Driver (AP_Radio) - Sends firmware data chunks to the radio hardware.
- RX (Receive): None
Transmission (TX)
ArduPilot sends this message when performing a firmware upload to a connected telemetry radio.
Source: libraries/AP_Radio/AP_Radio_cc2500.cpp
Protocol Logic
The AP_Radio driver chunks the firmware binary and sends it using type 42.
- Type: 42 (Firmware Update).
- Len: Length of data in bytes.
- Data: Raw bytes.
Data Fields
type: Data type ID (42 for firmware upload).len: Data length.data: Raw data (16 bytes).
Practical Use Cases
-
Radio Firmware Update:
- Scenario: A user initiates a radio firmware update via Mission Planner.
- Action: ArduPilot acts as a bridge, receiving the firmware via MAVLink (likely in
DATA96) and writing it to the radio chip usingDATA16(or direct SPI/UART depending on the exact hardware path, butDATA16is the MAVLink encapsulation for this specific radio driver). Correction: The search results showmavlink_msg_data16_sendbeing called by the radio driver. This suggests the autopilot might be sending data back to the GCS or to another node? Actually, looking at the codemavlink_msg_data16_send(fwupload.chan...suggests it's sending it out via MAVLink. IfAP_Radiois the radio driver on the autopilot, it might be reporting status or echoing data.
Re-reading code:
mavlink_msg_data16_send(fwupload.chan, 42, 4, data16);
It sends it tofwupload.chan. This is likely an ack or status back to the GCS during the update process.
Key Codebase Locations
- libraries/AP_Radio/AP_Radio_cc2500.cpp:1493: Sending implementation.
DATA32
Summary
Generic 32-byte data packet.
Status
Unsupported
Directionality
- TX (Transmit): None
- RX (Receive): None
Description
ArduPilot does not implement this message.
Theoretical Use Cases
Generic data transmission.
DATA64
Summary
Generic 64-byte data packet.
Status
Unsupported
Directionality
- TX (Transmit): None
- RX (Receive): None
Description
ArduPilot does not implement this message.
Theoretical Use Cases
Generic data transmission.
DATA96
Summary
Generic 96-byte data packet. In ArduPilot, this is used to receive firmware update data and test commands for the AP_Radio system from a Ground Control Station.
Status
Supported (RX Only)
Directionality
- TX (Transmit): None
- RX (Receive): All Vehicles - ArduPilot receives this from the GCS and forwards it to the
AP_Radiodriver.
Reception (RX)
ArduPilot processes this message in GCS_MAVLINK::handle_data_packet.
Source: libraries/GCS_MAVLink/GCS_Common.cpp
Protocol Logic
The handler inspects the type field:
- Type 42: Firmware Upload. Passed to
AP_Radio::handle_data_packet. - Type 43: Play Tune. Passed to
AP_Radio.
Data Fields
type: Data type ID (42=FW Upload, 43=Play Tune).len: Data length.data: Raw data (96 bytes).
Practical Use Cases
-
Updating Radio Firmware:
- Scenario: User uploads new firmware to the onboard telemetry radio via the GCS.
- Action: The GCS sends
DATA96packets containing the binary. ArduPilot receives them and flushes them to the radio hardware.
-
Radio Testing:
- Scenario: Debugging radio speakers/buzzers.
- Action: GCS sends a "Play Tune" command (Type 43) via
DATA96.
Key Codebase Locations
- libraries/GCS_MAVLink/GCS_Common.cpp:3818:
handle_data_packetimplementation.
AHRS2
Summary
Status of the secondary Attitude and Heading Reference System (AHRS) or EKF core.
Status
Supported (TX Only)
Directionality
- TX (Transmit): All Vehicles - Sends secondary EKF/AHRS state.
- RX (Receive): None
Transmission (TX)
ArduPilot sends this message to report the solution from the secondary estimation backend (e.g., EKF3 Core 1 if Core 0 is primary, or DCM if EKF is primary).
Source: libraries/GCS_MAVLink/GCS_Common.cpp
Protocol Logic
The system calls AP::ahrs().get_secondary_attitude() and get_secondary_position(). If valid, it populates the message.
- Role: Allows the GCS to monitor the health and divergence of the backup estimator.
Data Fields
roll: Roll angle (rad).pitch: Pitch angle (rad).yaw: Yaw angle (rad).altitude: Altitude (meters).lat: Latitude (deg * 1E7).lng: Longitude (deg * 1E7).
Practical Use Cases
- EKF Health Monitoring:
- Scenario: A developer wants to see if the secondary EKF core is agreeing with the primary core during a flight with magnetic interference.
- Action: The GCS plots
AHRS2.rollvsATTITUDE.rollto check for divergence.
Key Codebase Locations
- libraries/GCS_MAVLink/GCS_Common.cpp:587: Sending implementation.
BATTERY2
Summary
Voltage and current report for the secondary battery.
Status
Supported (TX Only)
Directionality
- TX (Transmit): All Vehicles - Sends secondary battery status.
- RX (Receive): None
Transmission (TX)
ArduPilot sends this message to report the status of the battery monitor at index 1 (the second battery).
Source: libraries/GCS_MAVLink/GCS_Common.cpp
Protocol Logic
Queries AP::battery().voltage(1) and current_amps(1).
- Note: This message is considered legacy/deprecated in favor of
BATTERY_STATUS(which supports an ID field), but it is still actively sent for compatibility with older GCS implementations that expect a dedicated "Battery 2" message.
Data Fields
voltage: Voltage (millivolts).current_battery: Current (centiamps).
Practical Use Cases
- Dual Battery Setup:
- Scenario: A large drone has two independent LiPo batteries for redundancy.
- Action: The GCS displays "Batt 1" (from
SYS_STATUS) and "Batt 2" (fromBATTERY2) separately.
Key Codebase Locations
- libraries/GCS_MAVLink/GCS_Common.cpp:2810: Sending implementation.
AHRS3
Summary
Status of a third AHRS/EKF core.
Status
Unsupported
Directionality
- TX (Transmit): None
- RX (Receive): None
Description
ArduPilot does not implement this message. Use AHRS2 for secondary status or standard ATTITUDE/GLOBAL_POSITION_INT for primary status.
Theoretical Use Cases
Debugging a tertiary estimator.
LED_CONTROL
Summary
Control the color and pattern of onboard RGB LEDs (e.g., NeoPixel, Toshiba LEDs).
Status
Supported (RX Only)
Directionality
- TX (Transmit): None
- RX (Receive): All Vehicles - Receives commands to set LED state.
Reception (RX)
Handled by AP_Notify::handle_led_control.
Source: libraries/AP_Notify/AP_Notify.cpp
Protocol Logic
Passed to the AP_Notify library, which overrides the standard status LED patterns.
- Patterns: Solid, Blink, Flash.
- Colors: RGB bytes.
Data Fields
target_system: System ID.target_component: Component ID.instance: LED instance (0 for all).pattern: Pattern ID (0=Solid, 1=Custom, etc.).custom_len: Custom pattern length.custom_bytes: Custom pattern data.
Practical Use Cases
- Light Shows / Swarming:
- Scenario: A swarm of drones performs a night show.
- Action: The central computer sends
LED_CONTROLmessages to change the color of each drone in sync with the music.
Key Codebase Locations
- libraries/AP_Notify/AP_Notify.cpp:475: Handler.
MAG_CAL_PROGRESS
Summary
Reports the progress of the onboard compass calibration process.
Status
Supported (TX Only)
Directionality
- TX (Transmit): All Vehicles - Sends calibration status.
- RX (Receive): None
Transmission (TX)
ArduPilot sends this message periodically while AP_Compass is in calibration mode.
Source: libraries/GCS_MAVLink/GCS_Common.cpp
Protocol Logic
- Progress: 0-100%.
- Direction Mask: Bitmask of which orientations (North, South, Up, Down, etc.) have been successfully sampled.
- ID: Compass ID being calibrated.
Data Fields
compass_id: Compass instance/ID.cal_mask: Bitmask of required orientations.cal_status: Status flags.attempt: Attempt number.completion_pct: Completion percentage.completion_mask: Bitmask of completed orientations.direction_x/y/z: Current direction vector.
Practical Use Cases
- Onboard Calibration:
- Scenario: User initiates compass calibration via GCS.
- Action: GCS displays a "dance" guide, highlighting which sides of the vehicle still need to be presented to the sky/ground based on
completion_mask.
Key Codebase Locations
- libraries/GCS_MAVLink/GCS_Common.cpp: Streaming entry.
MAG_CAL_REPORT
Summary
Reports the final results of the onboard compass calibration.
Status
Supported (TX Only)
Directionality
- TX (Transmit): All Vehicles - Sends final calibration offsets.
- RX (Receive): None
Transmission (TX)
Sent once when calibration completes (success or failure).
Source: libraries/GCS_MAVLink/GCS_Common.cpp
Protocol Logic
Contains the calculated hard-iron offsets, diagonals, and off-diagonals (soft iron), plus the "fitness" (error) score.
Data Fields
compass_id: Compass instance/ID.cal_mask: Calibration mask used.cal_status: Final status (Success/Failed).autosaved: True if parameters were saved.fitness: Error score (lower is better).ofs_x/y/z: Hard iron offsets.diag_x/y/z: Soft iron diagonal scaling.offdiag_x/y/z: Soft iron off-diagonal scaling.
Practical Use Cases
- Calibration Verification:
- Scenario: Calibration finishes.
- Action: GCS displays the
fitnessscore. If it's too high (e.g., > 10), the user knows the calibration was poor (likely magnetic interference nearby) and should retry.
Key Codebase Locations
- libraries/GCS_MAVLink/GCS_Common.cpp: Streaming entry.
EKF_STATUS_REPORT
Summary
Detailed health and status report of the Extended Kalman Filter (EKF).
Status
Supported (TX Only)
Directionality
- TX (Transmit): All Vehicles - Sends EKF variance metrics.
- RX (Receive): None
Transmission (TX)
ArduPilot sends this message to report the "health" of the EKF fusion. This data drives the "EKF Status" / "Vibe" HUD elements in Mission Planner.
Source: libraries/GCS_MAVLink/GCS_Common.cpp
Protocol Logic
The system queries the active EKF core for the ratio of innovation to gate size (test ratio) for various sensors.
- Values < 1.0: Healthy (Consistency within expected noise).
- Values > 1.0: Inconsistent (Sensor data conflicts with prediction).
Data Fields
flags: Flags indicating which sensors are active/fused.velocity_variance: Velocity innovation test ratio.pos_horiz_variance: Horizontal position innovation test ratio.pos_vert_variance: Vertical position innovation test ratio.compass_variance: Compass innovation test ratio.terrain_alt_variance: Terrain altitude innovation test ratio.airspeed_variance: Airspeed innovation test ratio.
Practical Use Cases
- Pre-Arm Check:
- Scenario: User tries to arm but gets "EKF Variance" error.
- Action: GCS checks
compass_variance. If high, it indicates magnetic interference or bad calibration.
Key Codebase Locations
- libraries/GCS_MAVLink/GCS_Common.cpp:1101: Streaming entry.
PID_TUNING
Summary
Real-time PID controller data for tuning analysis.
Status
Supported (TX Only)
Directionality
- TX (Transmit): All Vehicles - Sends PID components.
- RX (Receive): None
Transmission (TX)
ArduPilot sends this message when GCS_PID_MASK is set to monitor a specific axis (e.g., Roll, Pitch, Yaw).
Source: libraries/GCS_MAVLink/GCS_Common.cpp
Protocol Logic
Captures the internal state of the AC_PID controllers.
- axis: enum (ROLL=1, PITCH=2, YAW=3, etc).
- desired: Target rate/angle.
- achieved: Actual rate/angle.
- P/I/D/FF: Contribution of each term.
Data Fields
axis: Axis ID.desired: Desired value.achieved: Achieved value.FF: Feed-Forward component.P: Proportional component.I: Integral component.D: Derivative component.SRate: Slew rate (optional).PDmod: P/D modulation (optional).
Practical Use Cases
- Tuning Optimization:
- Scenario: User is manually tuning a racing drone.
- Action: They enable PID logging for the Roll axis. The GCS graphs
desiredvsachievedand theP/I/Dterms in real-time, helping the user adjust gains to minimize overshoot.
Key Codebase Locations
- libraries/GCS_MAVLink/GCS_Common.cpp:1102: Streaming entry.
DEEPSTALL
Summary
Status of the Deep Stall landing controller (used by fixed-wing aircraft).
Status
Supported (TX Only)
Directionality
- TX (Transmit): Plane - Sends landing status.
- RX (Receive): None
Transmission (TX)
ArduPilot sends this message when a deep stall landing is in progress.
Source: libraries/AP_Landing/AP_Landing_Deepstall.cpp
Protocol Logic
Reports the progress of the stall maneuver.
- Stage: Estimate/Wait/Descend/Land.
- Cross-track error: Distance from landing line.
Data Fields
landing_lat: Target latitude.landing_lon: Target longitude.path_lat: Path latitude.path_lon: Path longitude.arc_entry_lat: Arc entry latitude.arc_entry_lon: Arc entry longitude.altitude: Current altitude.expected_travel_distance: Estimated distance to touch down.cross_track_error: Deviation from path.stage: Landing stage (FlyToArc, Arc, Approach, Land).
Practical Use Cases
- Autonomous Landing:
- Scenario: A plane performs a vertical deep-stall landing in a tight space.
- Action: The GCS monitors the
stageandcross_track_errorto ensure the vehicle is committed to the correct landing spot.
Key Codebase Locations
- libraries/AP_Landing/AP_Landing_Deepstall.cpp:439: Sending implementation.
EFI_STATUS
Summary
Status of an Electronic Fuel Injection (EFI) engine.
Status
Supported (RX & TX)
Directionality
- TX (Transmit): All Vehicles - Forwards EFI status to GCS.
- RX (Receive): All Vehicles - Receives status from EFI hardware (e.g., via CAN or Serial).
Transmission (TX)
ArduPilot streams this message to the GCS to report engine health.
Source: libraries/GCS_MAVLink/GCS_Common.cpp
Reception (RX)
Handled by AP_EFI::handle_EFI_message. Allows a serial-connected EFI unit to inject its status into the autopilot.
Source: libraries/GCS_MAVLink/GCS_Common.cpp
Data Fields
health: Health flags.ecu_index: ECU instance.rpm: Engine RPM.fuel_consumed: Fuel consumed (cm^3).fuel_flow: Fuel flow rate (cm^3/min).engine_load: Engine load percentage.throttle_position: Throttle position percentage.spark_dwell_time: Spark dwell time.barometric_pressure: Barometric pressure (kPa).intake_manifold_pressure: Intake pressure (kPa).intake_air_temperature: Intake temp (degC).cylinder_head_temperature: CHT (degC).ignition_timing: Ignition timing (deg).injection_time: Injection time.exhaust_gas_temperature: EGT (degC).throttle_out: Throttle output percentage.pt_compensation: Pressure/Temp compensation.
Practical Use Cases
- Gas Engine Monitoring:
- Scenario: A large gasoline-powered VTOL plane.
- Action: The pilot monitors
cylinder_head_temperatureandrpmto ensure the engine is not overheating during hover.
Key Codebase Locations
- libraries/GCS_MAVLink/GCS_Common.cpp: Handler and Streamer.
ESTIMATOR_STATUS
Summary
Estimator status report.
Status
Unsupported
Directionality
- TX (Transmit): None
- RX (Receive): None
Description
ArduPilot does not implement this message. It uses EKF_STATUS_REPORT (193) for detailed estimator health.
Theoretical Use Cases
General estimator status.
HIGH_LATENCY
Summary
Legacy high latency telemetry message.
Status
Unsupported
Directionality
- TX (Transmit): None
- RX (Receive): None
Description
ArduPilot supports HIGH_LATENCY2 (235) instead.
Theoretical Use Cases
Satellite telemetry.
HIGH_LATENCY2
Summary
optimized telemetry message designed for high-latency, low-bandwidth links (e.g., Iridium SBD, RockBlock, LoRa).
Status
Supported (TX Only)
Directionality
- TX (Transmit): All Vehicles - Sends condensed telemetry.
- RX (Receive): None
Transmission (TX)
ArduPilot sends this message periodically (default 5s) on links where MSG_HIGH_LATENCY2 is enabled.
Source: libraries/GCS_MAVLink/GCS_Common.cpp
Protocol Logic
Packs essential flight data (Mode, Battery, GPS, Attitude, Airspeed, Failsafes) into a single compact message to minimize data usage and cost on satellite links.
Data Fields
timestamp: Time since boot.type: Vehicle type.autopilot: Autopilot type.custom_mode: Flight mode.latitude: Latitude.longitude: Longitude.altitude: Altitude.target_altitude: Target altitude.heading: Heading.target_heading: Target heading.target_distance: Distance to WP.throttle: Throttle %.airspeed: Airspeed.airspeed_sp: Airspeed setpoint.groundspeed: Groundspeed.windspeed: Windspeed.wind_heading: Wind heading.eph: GPS horizontal accuracy.epv: GPS vertical accuracy.temperature_air: Air temp.climb_rate: Climb rate.battery: Battery %.custom0/1/2: Custom debug/user fields.failure_flags: Bitmask of system failures.
Practical Use Cases
- Beyond Visual Line of Sight (BVLOS):
- Scenario: A glider flies 50km away, losing direct radio contact.
- Action: It switches to Iridium satellite telemetry, sending one
HIGH_LATENCY2packet every 10 seconds to keep the operator informed of its position and battery without incurring high data costs.
Key Codebase Locations
- libraries/GCS_MAVLink/GCS_Common.cpp:1139: Streaming entry.
HOME_POSITION
Summary
The HOME_POSITION message defines the vehicle's reference point for return-to-launch (RTL) maneuvers and distance-from-home calculations. It provides the global coordinates (Latitude, Longitude, Altitude) of the take-off location or a user-defined mission origin. This message is critical for GCS situational awareness and for ensuring the drone has a valid recovery point before embarking on an autonomous mission.
Status
Supported (Critical)
Directionality
- TX (Transmit): All Vehicles (Reports the current home location)
- RX (Receive): None (Use
SET_HOME_POSITION(243) to override the home location)
Transmission (TX)
The transmission logic resides in GCS_MAVLINK::send_home_position within libraries/GCS_MAVLink/GCS_Common.cpp:3032.
Data Sourcing
- AHRS Home: Data is retrieved from the
AP_AHRSlibrary viaget_home(). - Coordinate Format:
- Latitude/Longitude: Sourced in $degrees \times 10^7$.
- Altitude: Sourced as MSL altitude in millimeters.
- Relative Position: Includes the X, Y, and Z distance (in meters) from the local EKF origin to the Home position.
Trigger Logic
ArduPilot sends this message:
- Periodically: As part of the
MSG_HOMEtelemetry stream (typically at a low rate like 0.5Hz or 1Hz). - On Demand: In response to a
MAV_CMD_GET_HOME_POSITIONcommand. - On Set: Automatically whenever the Home position is initialized or updated (e.g., at the moment of arming).
Data Fields
latitude: Latitude (WGS84), in degrees * 1E7.longitude: Longitude (WGS84, in degrees * 1E7.altitude: Altitude (MSL), in meters * 1000 (positive for up).x: Local X position of this position in the local coordinate frame.y: Local Y position of this position in the local coordinate frame.z: Local Z position of this position in the local coordinate frame.q: World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground.approach_x: Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.approach_y: Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.approach_z: Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.time_usec: Timestamp (microseconds since UNIX epoch or microseconds since system boot).
Practical Use Cases
- RTL Safety Check:
- Scenario: A pilot is about to fly a long-range mission.
- Action: The GCS checks for the presence of the
HOME_POSITIONmessage. If not received, the GCS shows a "Home Not Set" warning and may prevent the pilot from arming, ensuring the drone won't attempt to return to an unknown location.
- Distance-to-Home Display:
- Scenario: A drone is 2km away from the pilot.
- Action: The GCS HUD calculates the distance between the vehicle's current
GLOBAL_POSITION_INT(33) and theHOME_POSITION(242) to show a live "Distance" readout to the pilot.
- Mission Origin Alignment:
- Scenario: A surveyor is using a pre-planned mission that relies on relative altitudes.
- Action: The GCS uses the
HOME_POSITIONaltitude as the $0m$ reference point, ensuring the mission's vertical steps are executed at the correct heights above the ground.
Key Codebase Locations
- libraries/GCS_MAVLink/GCS_Common.cpp:3032: Implementation of the MAVLink packet construction.
- libraries/AP_AHRS/AP_AHRS.h: Provides the
get_home()interface.
EXTENDED_SYS_STATE
Summary
Extended system state, primarily used for VTOL aircraft to report their flight state (transitioning, hovering, flying fixed-wing) and landing status.
Status
Supported (TX Only)
Directionality
- TX (Transmit): All Vehicles (especially QuadPlane/VTOL) - Sends VTOL state.
- RX (Receive): None
Transmission (TX)
ArduPilot sends this message to update the GCS on the specific state of a VTOL vehicle.
Source: libraries/GCS_MAVLink/GCS_Common.cpp
Protocol Logic
- vtol_state: MAV_VTOL_STATE (Undefined, Transitioning, MC, FW).
- landed_state: MAV_LANDED_STATE (On Ground, In Air, Taking Off, Landing).
Data Fields
vtol_state: VTOL flight state.landed_state: Landed state.
Practical Use Cases
- VTOL Transition Monitoring:
- Scenario: A QuadPlane takes off and transitions to forward flight.
- Action: The GCS uses
vtol_stateto change the HUD symbology (e.g., from Copter style to Plane style) during the transition.
Key Codebase Locations
- libraries/GCS_MAVLink/GCS_Common.cpp:1121: Streaming entry.
V2_EXTENSION
Summary
MAVLink v2 extension message.
Status
Unsupported
Directionality
- TX (Transmit): None
- RX (Receive): None
Description
ArduPilot does not implement this message directly.
Theoretical Use Cases
Protocol extension wrapper.
PLAY_TUNE
Summary
Command the vehicle to play a musical tune on its buzzer and/or ESCs.
Status
Supported (RX Only)
Directionality
- TX (Transmit): None
- RX (Receive): All Vehicles - Receives tune commands.
Reception (RX)
Handled by AP_Notify::handle_play_tune.
Source: libraries/GCS_MAVLink/GCS_Common.cpp
Protocol Logic
Parses the tune string (formatted in the "Play string" format, e.g., "A B C") and queues it for playback.
Data Fields
target_system: System ID.target_component: Component ID.tune: Tune string (30 chars max).tune2: Extension string (200 chars).
Practical Use Cases
- Lost Model Finder:
- Scenario: Drone lands in tall grass.
- Action: GCS sends
PLAY_TUNEwith a loud, repetitive beep sequence to help the pilot locate it.
Key Codebase Locations
- libraries/GCS_MAVLink/GCS_Common.cpp:4346: Handler.
FLIGHT_INFORMATION
Summary
The FLIGHT_INFORMATION message is designed to provide high-level metadata about the current flight session. Its primary purpose is to provide a unique identifier (UUID) for the flight, along with precise UTC timestamps for the arming and takeoff events. This facilitates the automatic organization and synchronization of flight logs across different systems (e.g., Drone vs. GCS vs. Cloud).
Status
Unsupported
Directionality
- TX (Transmit): None
- RX (Receive): None
Description
ArduPilot currently does not implement this message.
Flight UUIDs and arming timestamps are typically handled internally by the logging system (DataFlash / .BIN logs) and are not broadcast over MAVLink in this specific format. Ground Control Stations generally infer "New Flight" events by monitoring HEARTBEAT mode changes (e.g., Disarmed -> Armed) or GLOBAL_POSITION_INT data.
Intended Data Fields (Standard)
time_boot_ms: Timestamp (ms since boot).arming_time_utc: Timestamp at arming (us since UNIX epoch).takeoff_time_utc: Timestamp at takeoff (us since UNIX epoch).flight_uuid: Universally Unique Identifier (UUID) for the flight. This should ideally correspond to the filename of the log file.
Theoretical Use Cases
- Cloud Logging Sync:
- Scenario: A drone uploads telemetry to a cloud service.
- Action: The
flight_uuidallows the cloud service to automatically group telemetry packets into discrete "Flight" objects, even if the connection drops and reconnects.
- Legal Compliance:
- Scenario: Automated flight logging for commercial operations.
- Action: The
takeoff_time_utcprovides a definitive, tamper-evident start time for the flight log, useful for pilot logbooks.
WIFI_CONFIG_AP
Summary
The WIFI_CONFIG_AP message is designed to configure the WiFi credentials (SSID and Password) of a MAVLink-enabled WiFi Access Point or Station. It is intended for setting up telemetry radios or companion computers without needing a physical USB connection.
Status
Unsupported
Directionality
- TX (Transmit): None
- RX (Receive): None
Description
ArduPilot does not implement this message.
While ArduPilot supports networking via AP_Networking and PPP/Ethernet interfaces, the configuration of WiFi credentials on external bridges (like ESP8266/ESP32 MAVLink bridges) is typically handled via their own web interfaces or specific setup tools, not via this MAVLink message processed by the Flight Controller.
Intended Data Fields (Standard)
ssid: Name of the WiFi network (up to 32 chars).password: Password (up to 64 chars).mode:WIFI_CONFIG_AP_MODE(AP, Station, Disabled).response:WIFI_CONFIG_AP_RESPONSE(Accepted, Rejected, Error).
Theoretical Use Cases
- Headless Provisioning:
- Scenario: A user buys a new telemetry module.
- Action: Instead of connecting a USB cable, they connect to the module's default hotspot. The GCS sends
WIFI_CONFIG_APto instruct the module to join the user's home WiFi network (Station Mode).
- Field Reconfiguration:
- Scenario: A drone swarm needs to change WiFi channels to avoid interference.
- Action: The GCS broadcasts a new configuration to all drones simultaneously via MAVLink, switching their onboard WiFi radios to a new SSID or frequency.
AIS_VESSEL
Summary
The AIS_VESSEL message reports the position, velocity, and identification of a marine vessel detected by an onboard AIS (Automatic Identification System) receiver. This allows the Autopilot and Ground Control Station to track maritime traffic and, in some cases, perform collision avoidance.
Status
Supported
Directionality
- TX (Transmit): Autopilot (Reports detected vessels to GCS)
- RX (Receive): None (Autopilot consumes raw NMEA from AIS hardware, not MAVLink)
Transmission (TX)
The message is generated by the AP_AIS library, which parses incoming data from an AIS receiver connected to a serial port.
Core Logic
The implementation is in AP_AIS::send within libraries/AP_AIS/AP_AIS.cpp:264.
- Database: The library maintains a list of detected vessels (
_list). - Scheduling: It iterates through the list and transmits a message for a vessel if:
- The data has updated since the last transmission.
- 30 seconds have elapsed (periodic refresh).
- TSLC: It calculates
tslc(Time Since Last Communication) to let the GCS know how stale the data is.
Data Fields
MMSI: Mobile Marine Service Identity.lat: Latitude (deg * 1E7).lon: Longitude (deg * 1E7).COG: Course over ground (deg * 100).heading: True heading (deg * 100).SOG: Speed over ground (cm/s).callsign: The vessel callsign.name: The vessel name.width: Width of the vessel (meters).length: Length of the vessel (meters).type: Type of vessel.dimension_bow: Distance from GPS to bow (meters).dimension_stern: Distance from GPS to stern (meters).dimension_port: Distance from GPS to port (meters).dimension_starboard: Distance from GPS to starboard (meters).tslc: Time since last communication (seconds).flags: Bitmask to indicate various statuses including valid data fields.rot: Rate of turn (deg/min).
Practical Use Cases
- Maritime Patrol:
- Scenario: A drone is inspecting a harbor.
- Action: The GCS displays all ships on the map with their names and vectors (SOG/COG), allowing the pilot to identify vessels without visual confirmation.
- Collision Avoidance:
- Scenario: An autonomous boat is navigating a channel.
- Action: The Autopilot uses the
lat/lonandSOGof surrounding AIS targets to calculate Time to Closest Point of Approach (TCPA) and steer clear of moving ships.
Key Codebase Locations
- libraries/AP_AIS/AP_AIS.cpp:264: Implementation of the sender.
ISBD_LINK_STATUS
Summary
The ISBD_LINK_STATUS message reports the status of an Iridium SBD (Short Burst Data) satellite link. This includes signal quality, session status, and ring call alerts.
Status
Unsupported
Directionality
- TX (Transmit): None
- RX (Receive): None
Description
ArduPilot does not implement this message.
While ArduPilot supports Iridium SBD modems (like the RockBlock) via the AP_IridiumSBD library, it does not currently expose the link status via this specific MAVLink message. Status information is typically logged internally or reported via STATUSTEXT messages.
Intended Data Fields (Standard)
timestamp: Timestamp.last_heartbeat: Timestamp of last heartbeat.failed_sessions: Number of failed sessions.successful_sessions: Number of successful sessions.signal_quality: Signal quality (0-5).ring_pending: Ring alert pending.tx_session_pending: TX session pending.rx_session_pending: RX session pending.
Theoretical Use Cases
- Link Troubleshooting:
- Scenario: A BVLOS drone over the ocean stops reporting position.
- Action: The last received
ISBD_LINK_STATUSshowed a signal quality of 0. This confirms the issue was antenna obstruction or satellite coverage, rather than a system crash.
- Cost Optimization:
- Scenario: Satellite data is expensive per byte.
- Action: The GCS monitors
tx_session_pendingandsignal_quality. It only queues non-critical telemetry uploads whensignal_qualityis 5/5, minimizing the chance of failed (but billed) transmission attempts.
UTM_GLOBAL_POSITION
Summary
The UTM_GLOBAL_POSITION message is used to report the vehicle's position to a UTM (Unmanned Traffic Management) system. It includes secure authentication tokens (UAS ID) and flight state information.
Status
Unsupported
Directionality
- TX (Transmit): None
- RX (Receive): None
Description
ArduPilot does not implement this message.
For Remote ID and traffic management compliance, ArduPilot uses the OpenDroneID protocol family:
OPEN_DRONE_ID_BASIC_ID(12900)OPEN_DRONE_ID_LOCATION(12901)OPEN_DRONE_ID_AUTHENTICATION(12902)OPEN_DRONE_ID_SELF_ID(12903)OPEN_DRONE_ID_SYSTEM(12904)OPEN_DRONE_ID_OPERATOR_ID(12905)
Intended Data Fields (Standard)
time: Timestamp (us).uas_id: Unique Aerial System ID (18 chars).lat/lon/alt: Position (degE7, mm).relative_alt: Altitude above home (mm).vx/vy/vz: Velocity (cm/s).h_acc/v_acc/vel_acc: Uncertainty (mm).next_lat/next_lon/next_alt: Next waypoint.update_rate: Update rate (cs).flight_state: Flight state.flags: Flags.
Theoretical Use Cases
- Air Traffic Integration:
- Scenario: A delivery drone enters controlled airspace.
- Action: The drone transmits
UTM_GLOBAL_POSITIONto a networked UTM Service Provider (USS). This provider forwards the position to Air Traffic Control, allowing them to see the drone on their radar screens alongside manned aircraft.
SMART_BATTERY_INFO
Summary
The SMART_BATTERY_INFO message provides static configuration and health info for a smart battery, such as its capacity, chemistry, and cycle count.
Status
Unsupported
Directionality
- TX (Transmit): None
- RX (Receive): None
Description
ArduPilot does not implement this message.
ArduPilot supports Smart Batteries (SMBus, DroneCAN) but maps their data into the standard BATTERY_STATUS (147) message, which includes fields for voltages, current, temperature, and cell voltages.
Intended Data Fields (Standard)
id: Battery ID.capacity_full_specification: Capacity when new.capacity_full: Current full capacity.cycle_count: Number of discharge cycles.weight: Weight.discharge_minimum_voltage: Minimum voltage.charging_minimum_voltage: Minimum charging voltage.resting_minimum_voltage: Resting voltage.charging_maximum_voltage: Max charging voltage.cells_in_series: Serial cell count.discharge_maximum_current: Max discharge current.charging_maximum_current: Max charging current.manufacture_date: Manufacture date.serial_number: Serial number.name: Name string.
Theoretical Use Cases
- Inventory Management:
- Scenario: A fleet of delivery drones swaps batteries 50 times a day.
- Action: The GCS reads
serial_numberandcycle_countviaSMART_BATTERY_INFO. It logs this data to a database to track exactly how many cycles each specific battery pack has undergone, scheduling retirement before performance degrades.
- Chemistry Verification:
GENERATOR_STATUS
Summary
The GENERATOR_STATUS message provides telemetry for an onboard electrical generator (e.g., RichenPower hybrid generator). It reports the operational state (Idle, Generating, Fault), electrical output, and maintenance metrics.
Status
Supported
Directionality
- TX (Transmit): Autopilot (Reports generator state to GCS)
- RX (Receive): None
Transmission (TX)
The message is generated by the AP_Generator library. Specific backends (like AP_Generator_RichenPower) implement the logic to populate this message from the generator's serial telemetry.
Core Logic
The implementation example is in AP_Generator_RichenPower::send_generator_status within libraries/AP_Generator/AP_Generator_RichenPower.cpp:438.
It maps internal generator states (Idle, Run, Charge) to the standard MAV_GENERATOR_STATUS_FLAG bitmask.
Data Fields
status: Status flags.generator_speed: Speed of electrical generator or alternator.battery_current: Current into/out of battery.load_current: Current going to the UAV.power_generated: The power being generated.bus_voltage: Voltage of the bus seen at the generator, or battery voltage if battery is active.rectifier_temperature: The temperature of the rectifier or other inverter.generator_temperature: The temperature of the mechanical motor, fuel cell core or generator.bat_current_setpoint: The target battery current.runtime: Seconds this generator has run since it was rebooted.time_until_maintenance: Seconds until this generator requires maintenance. A negative value indicates maintenance is past-due.
Practical Use Cases
- Hybrid Drones:
- Scenario: A petrol-electric hybrid multirotor.
- Action: The GCS displays the
generator_speedandbus_voltage. If the generator stalls (statusbecomesOFFwhile in air), the GCS triggers a critical alarm, warning the pilot they are running on reserve battery power only.
- Maintenance Tracking:
- Scenario: Fleet management.
- Action: The
time_until_maintenancefield allows ground crews to schedule oil changes or engine service proactively.
Key Codebase Locations
- libraries/AP_Generator/AP_Generator_RichenPower.cpp:438: Implementation of the sender.
RELAY_STATUS
Summary
The RELAY_STATUS message reports the current state (On/Off) of the vehicle's relay pins. Relays are digital switches often used to control lights, camera triggers, or power to peripherals.
Status
Supported
Directionality
- TX (Transmit): Autopilot (Reports relay states to GCS)
- RX (Receive): None
Transmission (TX)
The message is generated by the AP_Relay library. It is typically sent at low frequency or upon change.
Core Logic
The implementation is in AP_Relay::send_relay_status within libraries/AP_Relay/AP_Relay.cpp:655.
It supports reporting up to 16 relays using bitmasks.
Data Fields
time_boot_ms: Timestamp (milliseconds since system boot).on: Relay state. 1 bit per relay. 0: off, 1: on.present: Relay present. 1 bit per relay. 0: not configured, 1: configured.
Practical Use Cases
- Remote Switch Verification:
- Scenario: A user toggles a switch on their RC transmitter to turn on landing lights (connected to Relay 1).
- Action: The GCS receives
RELAY_STATUS. It sees Bit 0 ofongo high and updates the UI indicator to show the lights are ON.
Key Codebase Locations
- libraries/AP_Relay/AP_Relay.cpp:655: Implementation of the sender.
TUNNEL
Summary
The TUNNEL message is designed to tunnel arbitrary data (payloads) between MAVLink components. It allows for custom protocols or vendor-specific data to be transported transparently over the MAVLink network.
Status
Unsupported
Directionality
- TX (Transmit): None
- RX (Receive): None
Description
ArduPilot does not implement this message.
ArduPilot supports Serial Tunneling over the DroneCAN bus (using uavcan.tunnel.Targetted messages) to transparently pass serial data (like GPS configuration or firmware updates) to CAN peripherals. However, it does not currently support the MAVLink TUNNEL message for this purpose.
Intended Data Fields (Standard)
target_system/target_component: Targeted component.payload_type: Type of payload (enumMAV_TUNNEL_PAYLOAD_TYPE).payload_length: Length of data (up to 128 bytes).payload: Raw data buffer.
Theoretical Use Cases
- Proprietary Payload Control:
- Scenario: A user has a custom sensor payload that speaks a proprietary binary protocol (not MAVLink).
- Action: Instead of writing a new MAVLink parser, the GCS encapsulates the binary blob in a
TUNNELmessage. The payload on the drone (connected to the Mavlink stream) unwraps the blob and consumes it directly.
- Debug Shell:
- Scenario: A developer wants to access a Linux shell on a Companion Computer via the telemetry radio.
- Action: SSH traffic is chunked and wrapped into
TUNNELmessages, creating a virtual terminal connection over the telemetry link.
ADAP_TUNING
Summary
The ADAP_TUNING message is designed to report internal variables of an adaptive controller or auto-tuning process.
Status
Unsupported
Directionality
- TX (Transmit): None
- RX (Receive): None
Description
ArduPilot does not implement this message.
For tuning telemetry, ArduPilot typically uses:
PID_TUNING(194): Real-time PID data.MAV_CMD_DO_AUTOTUNE_ENABLE: To start AutoTune.STATUSTEXT: For AutoTune progress updates.
Intended Data Fields (Standard)
axis: Axis being tuned (Roll, Pitch, Yaw).desired: Desired rate/angle.achieved: Achieved rate/angle.error: Error value.theta: Adaptive gain.omega: Adaptive frequency.sigma: Adaptive sigma.theta_dot: Derivative of gain.omega_dot: Derivative of frequency.sigma_dot: Derivative of sigma.f: Feed-forward value.f_dot: Derivative of feed-forward.u: Output.
Theoretical Use Cases
- Real-Time MRAC Debugging:
- Scenario: A developer is testing a Model Reference Adaptive Controller (MRAC).
- Action: The controller streams
ADAP_TUNINGto report how the adaptive gains (theta) are evolving in real-time response to disturbances. The developer plots these gains to ensure they are converging and not oscillating.
- System Identification:
- Scenario: Identifying the moment of inertia of a new airframe.
- Action: An adaptive estimator varies the control inputs and measures the response.
ADAP_TUNINGreports the estimated physical parameters (omega,sigma) as they settle.
AOA_SSA
Summary
The AOA_SSA message reports the vehicle's Angle of Attack (AoA) and Side Slip Angle (SSA). This is critical for fixed-wing aircraft to monitor aerodynamic performance and prevent stalls.
Status
Supported (Plane Only)
Directionality
- TX (Transmit): Autopilot (Reports AoA/SSA to GCS)
- RX (Receive): None
Transmission (TX)
The message is generated by the ArduPlane firmware's GCS_Mavlink module.
Core Logic
The implementation is in GCS_MAVLINK_Plane::send_aoa_ssa within ArduPlane/GCS_Mavlink.cpp:190.
It pulls data directly from the AHRS:
ahrs.getAOA(): Angle of Attack in degrees.ahrs.getSSA(): Side Slip Angle in degrees.
These values may be synthesized from inertial data and airspeed, or measured directly by an AoA sensor (like a vane).
Data Fields
time_usec: Timestamp (us since UNIX epoch).AOA: Angle of Attack (degrees).SSA: Side Slip Angle (degrees).
Practical Use Cases
- Stall Warning:
- Scenario: A pilot is flying a glider near its limits.
- Action: The GCS monitors
AOA. If it exceeds the critical angle (e.g., 15 degrees), an audible alarm is triggered.
- Turn Coordination:
- Scenario: Tuning yaw dampers.
- Action: Analyzing the
SSAlog to minimize sideslip during turns.
Key Codebase Locations
- ArduPlane/GCS_Mavlink.cpp:190: Implementation of the sender.
ESC_TELEMETRY_1_TO_4
Summary
The ESC_TELEMETRY_1_TO_4 message provides real-time telemetry data for the first four Electronic Speed Controllers (ESCs). This includes voltage, current, RPM, and temperature, which are critical for monitoring propulsion health.
Status
Supported
Directionality
- TX (Transmit): Autopilot (Reports ESC status to GCS)
- RX (Receive): None
Transmission (TX)
The message is generated by the AP_ESC_Telem library. It aggregates data from various sources (BLHeli_S/32, DroneCAN, DShot) and standardizes it into MAVLink messages.
Core Logic
The implementation is in AP_ESC_Telem::send_esc_telemetry_mavlink within libraries/AP_ESC_Telem/AP_ESC_Telem.cpp:428.
It groups ESCs into blocks of 4. If ESC_TELEMETRY_1_TO_4 is full, it moves to ESC_TELEMETRY_5_TO_8 (11031), and so on, up to 32 ESCs.
Data Fields
temperature: Array of 4 temperatures in degC.voltage: Array of 4 voltages in centi-volts (V * 100).current: Array of 4 currents in centi-amps (A * 100).totalcurrent: Array of 4 consumed energy values in mAh.rpm: Array of 4 RPM values.count: Array of 4 error counts (or packet counts depending on ESC type).
Practical Use Cases
- Propulsion Failure Detection:
- Scenario: A motor bearing seizes mid-flight.
- Action: The current for that motor spikes while RPM drops. The GCS logs this anomaly, helping post-flight diagnostics.
- Battery Management:
- Scenario: Long-range flight.
- Action: The GCS sums the
totalcurrent(mAh) from all ESCs to cross-check the battery monitor's consumption estimate.
Key Codebase Locations
- libraries/AP_ESC_Telem/AP_ESC_Telem.cpp:428: Implementation of the sender.
ESC_TELEMETRY_5_TO_8
Summary
The ESC_TELEMETRY_5_TO_8 message provides real-time telemetry data for Electronic Speed Controllers (ESCs) 5 through 8. It follows the same structure and logic as ESC_TELEMETRY_1_TO_4 (11030).
Status
Supported
Directionality
- TX (Transmit): Autopilot (Reports ESC status to GCS)
- RX (Receive): None
Transmission (TX)
The message is generated by the AP_ESC_Telem library.
Core Logic
The implementation is in AP_ESC_Telem::send_esc_telemetry_mavlink within libraries/AP_ESC_Telem/AP_ESC_Telem.cpp:428.
It is populated if the system has more than 4 active ESCs (e.g., an Octocopter).
Data Fields
temperature: Array of 4 temperatures in degC.voltage: Array of 4 voltages in centi-volts.current: Array of 4 currents in centi-amps.totalcurrent: Array of 4 consumed energy values in mAh.rpm: Array of 4 RPM values.count: Array of 4 error counts.
ESC_TELEMETRY_9_TO_12
Summary
The ESC_TELEMETRY_9_TO_12 message provides real-time telemetry data for Electronic Speed Controllers (ESCs) 9 through 12. It follows the same structure and logic as ESC_TELEMETRY_1_TO_4 (11030).
Status
Supported
Directionality
- TX (Transmit): Autopilot (Reports ESC status to GCS)
- RX (Receive): None
Transmission (TX)
The message is generated by the AP_ESC_Telem library.
Core Logic
The implementation is in AP_ESC_Telem::send_esc_telemetry_mavlink within libraries/AP_ESC_Telem/AP_ESC_Telem.cpp:428.
It is populated if the system has more than 8 active ESCs (e.g., a Dodecacopter or Dodeca-Hexa).
Data Fields
temperature: Array of 4 temperatures in degC.voltage: Array of 4 voltages in centi-volts.current: Array of 4 currents in centi-amps.totalcurrent: Array of 4 consumed energy values in mAh.rpm: Array of 4 RPM values.count: Array of 4 error counts.
ESC_TELEMETRY_13_TO_16
Summary
The ESC_TELEMETRY_13_TO_16 message provides real-time telemetry data for Electronic Speed Controllers (ESCs) 13 through 16. It follows the same structure and logic as ESC_TELEMETRY_1_TO_4 (11030).
Status
Supported
Directionality
- TX (Transmit): Autopilot (Reports ESC status to GCS)
- RX (Receive): None
Transmission (TX)
The message is generated by the AP_ESC_Telem library.
Core Logic
The implementation is in AP_ESC_Telem::send_esc_telemetry_mavlink within libraries/AP_ESC_Telem/AP_ESC_Telem.cpp:428.
It is populated if the system has more than 12 active ESCs.
Data Fields
temperature: Array of 4 temperatures in degC.voltage: Array of 4 voltages in centi-volts.current: Array of 4 currents in centi-amps.totalcurrent: Array of 4 consumed energy values in mAh.rpm: Array of 4 RPM values.count: Array of 4 error counts.
ESC_TELEMETRY_17_TO_20
Summary
The ESC_TELEMETRY_17_TO_20 message provides real-time telemetry data for Electronic Speed Controllers (ESCs) 17 through 20. It follows the same structure and logic as ESC_TELEMETRY_1_TO_4 (11030).
Status
Supported
Directionality
- TX (Transmit): Autopilot (Reports ESC status to GCS)
- RX (Receive): None
Transmission (TX)
The message is generated by the AP_ESC_Telem library.
Core Logic
The implementation is in AP_ESC_Telem::send_esc_telemetry_mavlink within libraries/AP_ESC_Telem/AP_ESC_Telem.cpp:428.
It is populated if the system has more than 16 active ESCs.
Data Fields
temperature: Array of 4 temperatures in degC.voltage: Array of 4 voltages in centi-volts.current: Array of 4 currents in centi-amps.totalcurrent: Array of 4 consumed energy values in mAh.rpm: Array of 4 RPM values.count: Array of 4 error counts.
ESC_TELEMETRY_21_TO_24
Summary
The ESC_TELEMETRY_21_TO_24 message provides real-time telemetry data for Electronic Speed Controllers (ESCs) 21 through 24. It follows the same structure and logic as ESC_TELEMETRY_1_TO_4 (11030).
Status
Supported
Directionality
- TX (Transmit): Autopilot (Reports ESC status to GCS)
- RX (Receive): None
Transmission (TX)
The message is generated by the AP_ESC_Telem library.
Core Logic
The implementation is in AP_ESC_Telem::send_esc_telemetry_mavlink within libraries/AP_ESC_Telem/AP_ESC_Telem.cpp:428.
It is populated if the system has more than 20 active ESCs.
Data Fields
temperature: Array of 4 temperatures in degC.voltage: Array of 4 voltages in centi-volts.current: Array of 4 currents in centi-amps.totalcurrent: Array of 4 consumed energy values in mAh.rpm: Array of 4 RPM values.count: Array of 4 error counts.
ESC_TELEMETRY_25_TO_28
Summary
The ESC_TELEMETRY_25_TO_28 message provides real-time telemetry data for Electronic Speed Controllers (ESCs) 25 through 28. It follows the same structure and logic as ESC_TELEMETRY_1_TO_4 (11030).
Status
Supported
Directionality
- TX (Transmit): Autopilot (Reports ESC status to GCS)
- RX (Receive): None
Transmission (TX)
The message is generated by the AP_ESC_Telem library.
Core Logic
The implementation is in AP_ESC_Telem::send_esc_telemetry_mavlink within libraries/AP_ESC_Telem/AP_ESC_Telem.cpp:428.
It is populated if the system has more than 24 active ESCs.
Data Fields
temperature: Array of 4 temperatures in degC.voltage: Array of 4 voltages in centi-volts.current: Array of 4 currents in centi-amps.totalcurrent: Array of 4 consumed energy values in mAh.rpm: Array of 4 RPM values.count: Array of 4 error counts.
ESC_TELEMETRY_29_TO_32
Summary
The ESC_TELEMETRY_29_TO_32 message provides real-time telemetry data for Electronic Speed Controllers (ESCs) 29 through 32. It follows the same structure and logic as ESC_TELEMETRY_1_TO_4 (11030).
Status
Supported
Directionality
- TX (Transmit): Autopilot (Reports ESC status to GCS)
- RX (Receive): None
Transmission (TX)
The message is generated by the AP_ESC_Telem library.
Core Logic
The implementation is in AP_ESC_Telem::send_esc_telemetry_mavlink within libraries/AP_ESC_Telem/AP_ESC_Telem.cpp:428.
It is populated if the system has more than 28 active ESCs (e.g., massive Drone Light Show swarms or complex VTOLs).
Data Fields
temperature: Array of 4 temperatures in degC.voltage: Array of 4 voltages in centi-volts.current: Array of 4 currents in centi-amps.totalcurrent: Array of 4 consumed energy values in mAh.rpm: Array of 4 RPM values.count: Array of 4 error counts.