GPS_RAW_INT
Summary
The GPS_RAW_INT message provides raw satellite positioning data from the vehicle's primary GPS receiver. It includes latitude, longitude, altitude (MSL), and velocity components, along with quality indicators like the number of satellites visible and horizontal dilution of precision (HDOP).
Status
Supported
Directionality
- TX (Transmit): All Vehicles (Streams GPS 0 data)
- RX (Receive): None (Use
GPS_INPUTorHIL_GPSfor external input)
Transmission (TX)
The primary transmission logic is in AP_GPS::send_mavlink_gps_raw within libraries/AP_GPS/AP_GPS.cpp:1370.
Data Sourcing
- Primary Instance: This message specifically sends data from the first GPS instance (
instance 0). For second GPS units, ArduPilot uses the ArduPilot-specific messageGPS2_RAW(ID 124). - Coordinate Format: Latitude and Longitude are sent as
int32_twith a scale of 1E7. - Altitude: Sourced as Altitude above Mean Sea Level (MSL) in millimeters.
- Velocity: Sourced from the GPS driver's velocity vector, converted to cm/s for ground speed and centidegrees for course over ground.
Scheduling
- Sent as part of the
MSG_GPS_RAWstream. - Triggered in
GCS_Common.cpp:6204within thetry_send_messageloop.
Data Fields
time_usec: Timestamp (microseconds since UNIX epoch or microseconds since system boot).fix_type: GPS fix type (GPS_FIX_TYPE).lat: Latitude (WGS84, EGM96 ellipsoid), in degrees * 1E7.lon: Longitude (WGS84, EGM96 ellipsoid), in degrees * 1E7.alt: Altitude (MSL). Positive for up.eph: GPS HDOP horizontal dilution of precision in cm (m*100). If unknown, set to: UINT16_MAX.epv: GPS VDOP vertical dilution of precision in cm (m*100). If unknown, set to: UINT16_MAX.vel: GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX.cog: Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX.satellites_visible: Number of satellites visible. If unknown, set to 255.
Practical Use Cases
- Map Plotting:
- Scenario: A tablet running QGroundControl needs to show the drone's icon on a satellite map.
- Action: QGC reads
latandlonfromGPS_RAW_INTto position the icon.
- Signal Quality Monitoring:
- Scenario: A pilot is flying near tall buildings and wants to ensure the GPS link is stable.
- Action: The HUD monitors
satellites_visibleandeph(HDOP). If satellites drop below 6 or HDOP rises above 200 (2.0), the GCS warns the pilot of "Poor GPS Health".
- Antenna Tracking:
- Scenario: A long-range antenna tracker needs to point a directional antenna at the drone.
- Action: The tracker calculates the heading from its own position to the
lat/lonreported by the vehicle.
Key Codebase Locations
- libraries/AP_GPS/AP_GPS.cpp:1370: Implementation of the MAVLink packet construction.
- libraries/GCS_MAVLink/GCS_Common.cpp:6204: Scheduling and stream control.
GPS_STATUS
Summary
The GPS_STATUS message is defined in the MAVLink protocol to transmit detailed per-satellite information, including the PRN (satellite ID), Signal-to-Noise Ratio (SNR), Elevation, and Azimuth for up to 20 satellites. ArduPilot does not implement or transmit this message.
Status
Unsupported
Directionality
- TX (Transmit): None
- RX (Receive): None (Ignored)
Analysis
While many GPS modules (u-blox, MTK) provide the satellite constellation data required for this message, ArduPilot does not currently aggregate or stream this data via MAVLink. Basic satellite count and fix quality are instead provided by GPS_RAW_INT (24).
- Absence: There is no
send_gps_statusfunction in the GCS libraries. - Alternative: Advanced users often rely on u-blox "pass-through" (Serial over MAVLink) or DataFlash logs to view detailed satellite geometry during post-flight analysis.
Data Fields (Standard)
satellites_visible: Number of satellites visible.satellite_prn: Global satellite ID.satellite_used: 0: Satellite not used, 1: used for localization.satellite_elevation: Elevation (0: right on top of receiver, 90: on the horizon) of satellite.satellite_azimuth: Direction of satellite, 0: 0 deg, 255: 360 deg.satellite_snr: Signal to noise ratio of satellite.
Key Codebase Locations
- libraries/GCS_MAVLink/ap_message.h: Message ID 25 is missing from the supported message enum.
- libraries/GCS_MAVLink/GCS_Common.cpp: Lacks a handler for ID 25 in both TX and RX loops.
SCALED_IMU
Summary
The SCALED_IMU message provides high-frequency acceleration and rotation data from the vehicle's primary inertial sensors. Unlike legacy MAVLink implementations that distinguish between "Raw" (ADC values) and "Scaled" (physics units), ArduPilot's RAW_IMU and SCALED_IMU both provide physics-ready values (mG and rad/s). The primary distinction in ArduPilot is the timestamp format and instance mapping.
Status
Supported
Directionality
- TX (Transmit): All Vehicles (Outgoing telemetry)
- RX (Receive): None (Ignored)
Transmission (TX)
The transmission logic resides in GCS_MAVLINK::send_scaled_imu within libraries/GCS_MAVLink/GCS_Common.cpp:2259.
Data Sourcing
- Primary Instance:
SCALED_IMU(ID 26) transmits data specifically from IMU 0. - Time Source: Uses a millisecond timestamp (
AP_HAL::millis()). - Scaling:
- Accelerometer: Scaled to milli-G (mG).
- Gyroscope: Scaled to millirad/s (rad/s * 1000).
- Magnetometer: Scaled to milli-Gauss (mGauss).
Stream Configuration
In ArduPilot's default RAW_SENSORS stream (typically SRx_RAW_SENS), RAW_IMU (27) is used for IMU 0 to take advantage of microsecond precision. Consequently, SCALED_IMU (26) is often redundant for the primary sensor and may not be active in default configurations. However, SCALED_IMU2 (115) and SCALED_IMU3 (129) are the standard way secondary and tertiary IMUs are reported.
Data Fields
time_boot_ms: Timestamp (milliseconds since system boot).xacc: X acceleration (mg).yacc: Y acceleration (mg).zacc: Z acceleration (mg).xgyro: Angular speed around X axis (millirad /sec).ygyro: Angular speed around Y axis (millirad /sec).zgyro: Angular speed around Z axis (millirad /sec).xmag: X Magnetic field (milli tesla).ymag: Y Magnetic field (milli tesla).zmag: Z Magnetic field (milli tesla).
Practical Use Cases
- Vibration Analysis:
- Scenario: A builder is worried about motor balance and wants to check "Vibe" levels in real-time.
- Action: The GCS graphs the
xacc,yacc, andzaccfields at high frequency (e.g., 50Hz) to visualize mechanical noise.
- Orientation Verification:
- Scenario: A user has mounted the flight controller sideways.
- Action: By observing rotation rates (
xgyro,ygyro,zgyro) while physically rotating the drone, the user can verify if theBOARD_ORIENTATIONparameter is set correctly.
- Peripheral Monitoring:
- Scenario: Monitoring the health of a redundant IMU system.
- Action: Comparing the outputs of
SCALED_IMU(IMU 0) againstSCALED_IMU2(IMU 1) to check for sensor drift or hardware failure.
Key Codebase Locations
- libraries/GCS_MAVLink/GCS_Common.cpp:2259: Implementation of
send_scaled_imu. - libraries/GCS_MAVLink/GCS_Common.cpp:6305: The message scheduler case.
RAW_IMU
Summary
The RAW_IMU message is the high-precision companion to SCALED_IMU. In ArduPilot, both messages provide physics-scaled values (mG and rad/s), but RAW_IMU leverages a 64-bit microsecond timestamp (time_usec), making it the preferred message for high-frequency telemetry used in vibration analysis and IMU debugging.
Status
Supported
Directionality
- TX (Transmit): All Vehicles (Outgoing telemetry)
- RX (Receive): None (Ignored)
Transmission (TX)
The transmission logic resides in GCS_MAVLINK::send_raw_imu within libraries/GCS_MAVLink/GCS_Common.cpp:2150.
Data Sourcing
- Primary Instance: This message specifically transmits data from IMU 0.
- Timestamp: Uses
AP_HAL::micros64(), providing the best possible temporal resolution for the data. - Scaling:
- Accelerometer: Scaled to milli-G (mG).
- Gyroscope: Scaled to millirad/s (rad/s * 1000).
- Magnetometer: Scaled to milli-Gauss (mGauss).
- Temperature: Includes the IMU's internal temperature sensor data in centidegrees Celsius.
Scheduling
- Sent as part of the
MSG_RAW_IMUstream. - This message is usually prioritized in the "Raw Sensors" stream configuration to ensure ground control stations have high-fidelity sensor logs.
Data Fields
time_usec: Timestamp (microseconds since UNIX epoch or microseconds since system boot).xacc: X acceleration (raw).yacc: Y acceleration (raw).zacc: Z acceleration (raw).xgyro: Angular speed around X axis (raw).ygyro: Angular speed around Y axis (raw).zgyro: Angular speed around Z axis (raw).xmag: X Magnetic field (raw).ymag: Y Magnetic field (raw).zmag: Z Magnetic field (raw).id: Id. Optional, default: 0.temperature: Temperature (centidegrees). Optional, default: 0.
Practical Use Cases
- FFT Tuning:
- Scenario: A pilot is setting up a Notch Filter to eliminate motor noise.
- Action: The GCS captures a burst of
RAW_IMUdata and performs a Fast Fourier Transform (FFT) to identify the resonant frequencies of the frame. The microsecond timestamps are critical for accurate frequency mapping.
- IMU Health Check:
- Scenario: During pre-flight, the GCS detects "IMU Mismatch".
- Action: The operator compares
RAW_IMU(IMU 0) against other IMU messages to see if a particular sensor is producing erratic or noisy values while stationary.
- Blackbox Logging (Remote):
- Scenario: A developer is testing a vehicle too small for a high-speed SD card.
- Action: The telemetry link is saturated with
RAW_IMUpackets, allowing the developer to reconstruct the flight dynamics on a remote ground station with high precision.
Key Codebase Locations
- libraries/GCS_MAVLink/GCS_Common.cpp:2150: Implementation of
send_raw_imu. - libraries/GCS_MAVLink/GCS.h:360: Declaration of the send function.
RAW_PRESSURE
Summary
The RAW_PRESSURE message is defined in the MAVLink protocol to transmit uncalibrated pressure readings. ArduPilot does not implement or transmit this message. Instead, it uses SCALED_PRESSURE (29) to report physics-ready absolute and differential pressure data.
Status
Unsupported
Directionality
- TX (Transmit): None
- RX (Receive): None (Ignored)
Analysis
ArduPilot's philosophy is to perform sensor calibration and scaling onboard. Consequently, it bypasses "Raw" messages (which often imply raw ADC counts or uncompensated values) for subsystems like Barometers.
- Replacement: Users should look for
SCALED_PRESSURE(29) for the primary barometer. - Secondary Sensors:
SCALED_PRESSURE2(137) andSCALED_PRESSURE3(143) are used for redundant sensors.
Data Fields (Standard)
time_usec: Timestamp (microseconds since UNIX epoch or microseconds since system boot).press_abs: Absolute pressure (raw).press_diff1: Differential pressure 1 (raw, 0 if nonexistant).press_diff2: Differential pressure 2 (raw, 0 if nonexistant).temperature: Raw Temperature measurement (raw).
Key Codebase Locations
- libraries/GCS_MAVLink/GCS_Common.cpp:1030: Lacks a mapping for
MAVLINK_MSG_ID_RAW_PRESSURE(28), while mapping ID 29 toMSG_SCALED_PRESSURE.
SCALED_PRESSURE
Summary
The SCALED_PRESSURE message provides calibrated environmental data, specifically absolute pressure (for altitude) and differential pressure (for airspeed). This message is the primary source for the Altimeter and Airspeed indicators in a Ground Control Station.
Status
Supported
Directionality
- TX (Transmit): All Vehicles (Reports altitude/airspeed data)
- RX (Receive): Antenna Tracker (Syncs altitude for tracking)
Transmission (TX)
The transmission logic is implemented in GCS_MAVLINK::send_scaled_pressure within libraries/GCS_MAVLink/GCS_Common.cpp:2354.
Data Sourcing
- Absolute Pressure (
press_abs): Sourced from the primary barometer (Index 0) viaAP_Baro. Values are in Hectopascals (hPa). - Differential Pressure (
press_diff): Sourced from the primary airspeed sensor (Index 0) viaAP_Airspeed. Values are in hPa. - Temperature: Includes the barometer's ambient temperature reading in centidegrees Celsius.
Reception (RX)
While most vehicles only send this data, the Antenna Tracker firmware receives it.
- Handler:
Tracker::tracking_update_pressurein AntennaTracker/tracking.cpp. - Purpose: The tracker compares its local pressure against the vehicle's pressure to calculate a high-precision relative altitude, which is critical for aiming the directional antenna accurately at the drone.
Data Fields
time_boot_ms: Timestamp (milliseconds since system boot).press_abs: Absolute pressure (hectopascal).press_diff: Differential pressure 1 (hectopascal).temperature: Temperature (centidegrees Celsius).
Practical Use Cases
- HUD Altimeter:
- Scenario: A pilot is flying in a mountainous area.
- Action: The GCS uses
press_absto calculate the vehicle's barometric altitude, providing a stable height reference that doesn't suffer from GPS vertical jitter.
- Airspeed Verification:
- Scenario: A fixed-wing pilot is flying in high winds.
- Action: The GCS monitors
press_diff. If the reading stays near zero while flying fast, the GCS warns of a "Pitot Tube Blockage".
- Automatic Antenna Aiming:
- Scenario: A long-range mission requires a high-gain antenna.
- Action: The Antenna Tracker uses received
SCALED_PRESSUREpackets to maintain a vertical lock on the vehicle's position.
Key Codebase Locations
- libraries/GCS_MAVLink/GCS_Common.cpp:2308: Core logic for populating pressure data.
- libraries/AP_Baro/AP_Baro.h: Source of absolute pressure data.
- libraries/AP_Airspeed/AP_Airspeed.h: Source of differential pressure data.
GPS_GLOBAL_ORIGIN
Summary
Publishes the GPS coordinates of the vehicle's local origin (0,0,0).
Status
Supported (TX Only)
Directionality
- TX (Transmit): All Vehicles - Sends current EKF origin.
- RX (Receive): None
Transmission (TX)
ArduPilot sends this message to confirm the EKF origin has been set or changed.
Source: libraries/GCS_MAVLink/GCS_Common.cpp
Protocol Logic
Queries AP::[ahrs](/field-manual/mavlink-interface/ahrs.html)().get_origin() and broadcasts it.
- Trigger: Sent after
SET_GPS_GLOBAL_ORIGINis received or when the EKF initializes its origin (e.g., getting a 3D GPS lock).
Data Fields
latitude: Latitude (deg * 1E7).longitude: Longitude (deg * 1E7).altitude: Altitude (mm).time_usec: Timestamp.
Practical Use Cases
- Map Alignment:
- Scenario: Drone is flying in "Guided NoGPS" mode.
- Action: The GCS receives
GPS_GLOBAL_ORIGINand uses it to render the drone's position on the map, even though the drone itself is only navigating using local meters relative to startup.
Key Codebase Locations
- libraries/GCS_MAVLink/GCS_Common.cpp:3064: Sending implementation.
OPTICAL_FLOW
Summary
The OPTICAL_FLOW message provides 2D velocity data based on the optical movement of the ground beneath the vehicle. It is a critical sensor message for GPS-denied navigation, allowing the flight controller to maintain a stable horizontal position (loiter) indoors or in deep urban canyons. ArduPilot can both receive this data from external MAVLink sensors (like the PX4Flow) and transmit it to Ground Control Stations for real-time visualization of sensor health.
Status
Supported
Directionality
- TX (Transmit): All Vehicles (Reports sensor data to GCS)
- RX (Receive): All Vehicles (Accepts data from external MAVLink flow sensors)
Reception (RX)
Reception is handled by GCS_MAVLINK::handle_optical_flow in libraries/GCS_MAVLink/GCS_Common.cpp:4047.
Data Processing
- Backend Dispatch: The message is passed to the
AP_OpticalFlowlibrary, which identifies theMAVbackend. - Accumulation: In AP_OpticalFlow_MAV.cpp, the
flow_x,flow_y, andqualityvalues are integrated into a running sum. - EKF Fusion: During the next EKF (Extended Kalman Filter) update, these integrated values are converted into body-frame velocity estimates. The
qualityfield is used to determine how much the EKF should "trust" the data (e.g., quality < 50 may be ignored).
Transmission (TX)
ArduPilot relays optical flow data to the GCS via the MSG_OPTICAL_FLOW stream.
- Purpose: This allows pilots to verify that the flow sensor is working correctly (e.g., seeing the "Flow" graph move when they physically tilt the drone) without needing to connect directly to the sensor hardware.
Data Fields
time_usec: Timestamp (microseconds since UNIX epoch or microseconds since system boot).sensor_id: Sensor ID.flow_x: Flow in x-sensor direction (deci-pixels).flow_y: Flow in y-sensor direction (deci-pixels).flow_comp_m_x: Flow in x-sensor direction, angular-speed compensated (m).flow_comp_m_y: Flow in y-sensor direction, angular-speed compensated (m).quality: Optical flow quality / confidence. 0: bad, 255: maximum quality.ground_distance: Ground distance (m). Positive value: distance known. Negative value: Unknown distance.flow_rate_x: Flow rate about X axis (rad/s).flow_rate_y: Flow rate about Y axis (rad/s).
Practical Use Cases
- Stable Indoor Hover:
- Scenario: A pilot is flying a drone inside a high-ceiling warehouse where GPS is unavailable.
- Action: The drone uses the
OPTICAL_FLOWmessage from an onboard camera to counter drift, allowing the pilot to take their hands off the sticks while the drone holds position perfectly.
- Precision Landing:
- Scenario: A drone is landing on a small target with a specific visual pattern.
- Action: As the drone nears the ground, the optical flow sensor provides high-resolution horizontal velocity data that is more accurate than GPS, allowing for a smoother and more precise touchdown.
- Terrain Following (Low Alt):
- Scenario: A drone is flying 1m above the ground.
- Action: While primarily using a rangefinder for height, the optical flow data (combined with height) provides a robust velocity reference that is unaffected by atmospheric pressure changes.
Key Codebase Locations
- libraries/GCS_MAVLink/GCS_Common.cpp:4047: Entry point for flow data.
- libraries/AP_OpticalFlow/AP_OpticalFlow_MAV.cpp: MAVLink backend implementation.
- libraries/AP_OpticalFlow/AP_OpticalFlow.cpp: Frontend sensor management.
GLOBAL_VISION_POSITION_ESTIMATE
Summary
The GLOBAL_VISION_POSITION_ESTIMATE message is used by external positioning systems (like Vicon or SLAM) to provide the vehicle with a globally-referenced position and attitude estimate. While the MAVLink standard distinguishes this from local estimates, ArduPilot unifies both into its "External Navigation" pipeline to support high-precision flight in environments where GPS is unavailable or untrusted.
Status
Supported
Directionality
- TX (Transmit): None
- RX (Receive): All Vehicles (Enables external navigation input)
Reception (RX)
Reception is handled by GCS_MAVLINK::handle_global_vision_position_estimate in libraries/GCS_MAVLink/GCS_Common.cpp:3859.
Data Processing
- Decoding: The message is decoded and passed to a common handler for vision data (GCS_Common.cpp:3919).
- Library Integration: The data is forwarded to the
AP_VisualOdomlibrary. - EKF Fusion: The
AP_VisualOdom_MAVbackend converts the meters-based X, Y, and Z coordinates into a format suitable for the EKF (Extended Kalman Filter). The EKF then treats this as a primary position source (External Navigation) viaAP_AHRS::writeExtNavData.
Data Fields
usec: Timestamp (microseconds since UNIX epoch or microseconds since system boot).x: Global X position (meters).y: Global Y position (meters).z: Global Z position (meters).roll: Roll angle (rad).pitch: Pitch angle (rad).yaw: Yaw angle (rad).covariance: Pose covariance matrix upper right triangle (first six entries are the first ROW, next five entries are the second ROW, etc.).reset_counter: Estimate reset counter. This should be incremented when the estimate jumps in a discontinuous creation (e.g. at the start of a mission or when the system recovers from a tracking failure).
Practical Use Cases
- Vicon/Optitrack Integration:
- Scenario: A researcher is flying a drone in a motion capture laboratory.
- Action: The lab computer tracks the drone and streams
GLOBAL_VISION_POSITION_ESTIMATEat 50Hz-100Hz. The drone flies with millimeter precision, even with no GPS lock.
- Autonomous Greenhouse Monitoring:
- Scenario: A drone is navigating between rows of crops in a greenhouse using a pre-mapped SLAM environment.
- Action: The onboard SLAM computer sends global-referenced coordinates to the autopilot, allowing the drone to follow complex inspection routes autonomously.
- GPS-Denied Surveying:
- Scenario: A drone is surveying the inside of a large storage tank.
- Action: A laser-based positioning system provides absolute coordinates to the flight controller, ensuring the survey data is spatially accurate.
Key Codebase Locations
- libraries/GCS_MAVLink/GCS_Common.cpp:3859: Message entry point.
- libraries/AP_VisualOdom/AP_VisualOdom_MAV.cpp:26: MAVLink backend for visual odometry.
VISION_POSITION_ESTIMATE
Summary
The VISION_POSITION_ESTIMATE message is the standard MAVLink packet for providing local X, Y, and Z position data from an external vision system (e.g., SLAM or Visual Odometry). ArduPilot uses this message to enable stable flight and autonomous navigation in GPS-denied environments.
Status
Supported
Directionality
- TX (Transmit): None
- RX (Receive): All Vehicles (Enables external navigation input)
Reception (RX)
Reception is handled by GCS_MAVLINK::handle_vision_position_estimate in libraries/GCS_MAVLink/GCS_Common.cpp:3850.
Data Processing
- Unification: In ArduPilot's implementation,
VISION_POSITION_ESTIMATEandGLOBAL_VISION_POSITION_ESTIMATE(101) are handled by the same internal pipeline (GCS_Common.cpp:3919). - State Estimation: The data is forwarded to the
AP_VisualOdomlibrary. - EKF Injection: The message provides position (X, Y, Z in meters) and attitude (Roll, Pitch, Yaw in radians). These are injected into the EKF as "External Navigation" data. This allows the vehicle to hold its position based purely on camera-derived movement.
Data Fields
usec: Timestamp (microseconds since UNIX epoch or microseconds since system boot).x: Global X position (meters).y: Global Y position (meters).z: Global Z position (meters).roll: Roll angle (rad).pitch: Pitch angle (rad).yaw: Yaw angle (rad).covariance: Pose covariance matrix upper right triangle (first six entries are the first ROW, next five entries are the second ROW, etc.).reset_counter: Estimate reset counter. This should be incremented when the estimate jumps in a discontinuous creation (e.g. at the start of a mission or when the system recovers from a tracking failure).
Practical Use Cases
- Companion Computer SLAM:
- Scenario: An Intel Realsense T265 camera is connected to a Jetson Nano onboard the drone.
- Action: The Jetson Nano runs a SLAM algorithm and sends
VISION_POSITION_ESTIMATEto the flight controller at 30Hz. The pilot can then switch to "Position Hold" or "Auto" mode indoors.
- Swarm Robotics in Studios:
- Scenario: Multiple drones are performing synchronized dance routines in a studio equipped with infrared cameras.
- Action: The central studio controller tracks each drone and sends local coordinates, ensuring no collisions and perfect synchronization.
- Visual Docking:
- Scenario: A drone is attempting to land on a moving rover with a visual target.
- Action: A visual tracking system calculates the drone's position relative to the target and provides it via MAVLink, allowing for a precise automated landing.
Key Codebase Locations
- libraries/GCS_MAVLink/GCS_Common.cpp:3850: Message entry point.
- libraries/AP_VisualOdom/AP_VisualOdom.cpp:193: Common pose handling logic.
- libraries/AP_VisualOdom/AP_VisualOdom_MAV.cpp:26: MAVLink backend for visual odometry.
VISION_SPEED_ESTIMATE
Summary
The VISION_SPEED_ESTIMATE message is used by external sensors to provide 3D velocity data (X, Y, Z in meters per second) to the flight controller. This is often used as a supplement to position estimates or as a standalone source for velocity fusion in the EKF (Extended Kalman Filter), allowing the vehicle to maintain stability based on perceived movement even if absolute global or local position is unknown.
Status
Supported
Directionality
- TX (Transmit): None (Except SITL for simulation)
- RX (Receive): All Vehicles (Enables external velocity input)
Reception (RX)
Reception is handled by GCS_MAVLINK::handle_vision_speed_estimate in libraries/GCS_MAVLink/GCS_Common.cpp:3964.
Data Processing
- Decoding: The message is decoded into X, Y, and Z velocity components ($m/s$).
- Visual Odometry Integration: The data is passed to the
AP_VisualOdomfrontend (AP_VisualOdom.cpp:235). - EKF Fusion: The MAVLink backend for visual odometry calls
AP_AHRS::writeExtNavVelData. This pushes the external velocity directly into the EKF's state vector. This is particularly useful for damping and position-hold stability.
Data Fields
usec: Timestamp (microseconds since UNIX epoch or microseconds since system boot).x: Global X speed (m/s).y: Global Y speed (m/s).z: Global Z speed (m/s).covariance: Linear velocity covariance matrix (m/s)^2. Upper right triangle (first three entries are the first ROW, next two entries are the second ROW, etc.).reset_counter: Estimate reset counter. This should be incremented when the estimate jumps in a discontinuous creation (e.g. at the start of a mission or when the system recovers from a tracking failure).
Practical Use Cases
- Velocity-Only SLAM:
- Scenario: An external camera system provides high-frequency velocity data but the position drifts too much for absolute navigation.
- Action: The autopilot uses
VISION_SPEED_ESTIMATEto "brake" and hold position effectively, while ignoring the drifting position data.
- Optical Flow Enhancement:
- Scenario: A high-end optical flow system calculates 3D velocity using a downward-facing camera and IMU.
- Action: The system sends
VISION_SPEED_ESTIMATEto ArduPilot, providing a more robust velocity reference than the standardOPTICAL_FLOW(100) message.
- Wind Speed Correction (Experimental):
- Scenario: A ground-based anemometer array tracks the drone and estimates its true ground speed.
- Action: The ground system sends velocity updates to the drone via MAVLink to improve its flight controller's performance in turbulent conditions.
Key Codebase Locations
- libraries/GCS_MAVLink/GCS_Common.cpp:3964: Message entry point.
- libraries/AP_VisualOdom/AP_VisualOdom_MAV.cpp:62: EKF integration logic for velocity estimates.
VICON_POSITION_ESTIMATE
Summary
The VICON_POSITION_ESTIMATE message is used to provide high-precision position and orientation data from an external Motion Capture (MoCap) system, such as Vicon or OptiTrack. This is the "Gold Standard" for indoor flight, providing millimeter-level accuracy that allows for aggressive autonomous maneuvers in environments where GPS is blocked or multipathed.
Status
Supported
Directionality
- TX (Transmit): None (Except SITL for simulation)
- RX (Receive): All Vehicles (Enables MoCap-based navigation)
Reception (RX)
Reception is handled by GCS_MAVLINK::handle_vicon_position_estimate in libraries/GCS_MAVLink/GCS_Common.cpp:3868.
Data Processing
- Decoding: The message is decoded into local X, Y, and Z position ($m$) and Roll, Pitch, and Yaw attitude ($rad$).
- Unification: Like other vision messages, the data is forwarded to the
AP_VisualOdomlibrary. - EKF Fusion: The data is pushed to the EKF as "External Navigation" (ExtNav). Because MoCap data is extremely low-noise and has very low latency, the EKF can be tuned to "trust" this source almost exclusively, enabling extremely stable hover and precise path tracking.
Data Fields
usec: Timestamp (microseconds since UNIX epoch or microseconds since system boot).x: Global X position (meters).y: Global Y position (meters).z: Global Z position (meters).roll: Roll angle (rad).pitch: Pitch angle (rad).yaw: Yaw angle (rad).covariance: Pose covariance matrix upper right triangle (first six entries are the first ROW, next five entries are the second ROW, etc.).
Practical Use Cases
- Indoor Research Labs:
- Scenario: A university team is testing a new obstacle avoidance algorithm using multiple drones.
- Action: The lab's Vicon system tracks all drones and sends individual
VICON_POSITION_ESTIMATEpackets to each flight controller. This provides a "Ground Truth" for the drones to navigate safely within the lab.
- Cinematic Stage Flight:
- Scenario: A drone is required to fly a precise 3D path around actors on a film set inside a studio.
- Action: An OptiTrack system provides the drone with its coordinates, ensuring the flight path is repeatable and safe to within a few centimeters.
- HIL Simulation Testing:
- Scenario: A developer wants to test how the drone reacts to high-frequency position updates.
- Action: ArduPilot's SITL (Software In The Loop) simulator can be configured to generate "Fake Vicon" data, allowing the developer to test the ExtNav pipeline without a physical lab.
Key Codebase Locations
- libraries/GCS_MAVLink/GCS_Common.cpp:3868: Message entry point.
- libraries/SITL/SIM_Vicon.cpp: SITL simulator for MoCap systems.
HIGHRES_IMU
Summary
The HIGHRES_IMU message is a high-fidelity, integrated sensor packet designed for performance-critical applications like Visual-Inertial Odometry (VIO) and high-speed logging. Unlike standard IMU messages that use 16-bit integers, HIGHRES_IMU uses single-precision floats for all sensor data and provides a unified view of the Accelerometer, Gyroscope, Magnetometer, and Barometer.
Status
Supported (Requires > 1MB Flash)
Directionality
- TX (Transmit): All Vehicles (High-fidelity sensor stream)
- RX (Receive): None (Ignored)
Transmission (TX)
The transmission logic resides in GCS_MAVLINK::send_highres_imu within libraries/GCS_MAVLink/GCS_Common.cpp:2183.
Data Sourcing
This message aggregates data from across the sensor stack:
- IMU: Accelerometer ($m/s^2$) and Gyroscope ($rad/s$) data from the primary IMU.
- Compass: Magnetometer ($Gauss$) data.
- Barometer: Absolute pressure ($hPa$) and Pressure Altitude ($m$).
- Airspeed: Differential pressure ($hPa$) if an airspeed sensor is active.
- Timestamp: Uses a 64-bit microsecond timestamp (
time_usec) for precise data alignment.
Efficiency
The "Highres" designation refers to the use of IEEE 754 floats, which allow for much greater dynamic range and precision compared to the scaled integers used in RAW_IMU or SCALED_IMU.
Data Fields
time_usec: Timestamp (microseconds since UNIX epoch or microseconds since system boot).xacc: X acceleration (m/s^2).yacc: Y acceleration (m/s^2).zacc: Z acceleration (m/s^2).xgyro: Angular speed around X axis (rad/s).ygyro: Angular speed around Y axis (rad/s).zgyro: Angular speed around Z axis (rad/s).xmag: X Magnetic field (Gauss).ymag: Y Magnetic field (Gauss).zmag: Z Magnetic field (Gauss).abs_pressure: Absolute pressure (hectopascal).diff_pressure: Differential pressure (hectopascal).pressure_alt: Altitude calculated from pressure.temperature: Temperature (degrees celsius).fields_updated: Bitmap for fields that have updated since last message, bit 0 = xacc, bit 12: temperature.id: Id. Optional, default: 0.
Practical Use Cases
- VIO/SLAM Integration:
- Scenario: A drone is flying indoors using a companion computer (e.g., Raspberry Pi) running VIO (Visual Inertial Odometry).
- Action: The companion computer subscribes to
HIGHRES_IMUat 100Hz+. The high-precision float values and integrated microsecond timestamps are used to fuse camera data with IMU movement, providing stable position estimates in GPS-denied environments.
- External Kalman Filtering:
- Scenario: A researcher is developing a custom navigation filter on a ground computer.
- Action: The researcher logs
HIGHRES_IMUdata. Because it includes pressure and magnetometer data in the same packet as the IMU, the researcher doesn't have to worry about inter-message jitter or alignment issues.
- High-Speed Vibration Monitoring:
- Scenario: Testing a new propulsion system with very high RPM motors.
- Action: The developer uses
HIGHRES_IMUto capture the full spectrum of high-frequency vibrations that might be clipped or aliased by lower-resolution integer messages.
Key Codebase Locations
- libraries/GCS_MAVLink/GCS_Common.cpp:2183: Implementation of
send_highres_imu. - libraries/GCS_MAVLink/GCS_config.h:131: Conditional compilation logic based on board flash size.
OPTICAL_FLOW_RAD
Summary
The OPTICAL_FLOW_RAD message is an advanced alternative to the standard OPTICAL_FLOW (100) message. It transmits flow data as integrated angular speeds (radians) and includes integrated gyroscope data for better rotation compensation. ArduPilot does not currently implement a handler or sender for this message.
Status
Unsupported
Directionality
- TX (Transmit): None
- RX (Receive): None (Ignored)
Analysis
While many modern flow sensors (like the PX4Flow) output data in radians, ArduPilot's MAVLink backend for optical flow (AP_OpticalFlow_MAV) is currently hardcoded to expect the pixel-based OPTICAL_FLOW (100) message.
- Absence: There is no mapping for
MAVLINK_MSG_ID_OPTICAL_FLOW_RADinGCS_Common.cpporAP_OpticalFlow. - Recommendation: Developers using external MAVLink flow sensors should ensure they are configured to output the standard pixel-based
OPTICAL_FLOW(100) packet.
Data Fields
time_usec: Timestamp (microseconds since UNIX epoch or microseconds since system boot).sensor_id: Sensor ID.integration_time_us: Integration time.integrated_x: Integrated optical flow around X-axis (rad).integrated_y: Integrated optical flow around Y-axis (rad).integrated_xgyro: Integrated gyro around X-axis (rad).integrated_ygyro: Integrated gyro around Y-axis (rad).integrated_zgyro: Integrated gyro around Z-axis (rad).temperature: Temperature (centidegrees).quality: Optical flow quality / confidence. 0: bad, 255: maximum quality.time_delta_distance_us: Time since the distance was sampled.distance: Distance to the center of the flow field. Positive value: distance known. Negative value: Unknown distance.
Key Codebase Locations
- libraries/GCS_MAVLink/GCS_Common.cpp:4047: Shows that only
OPTICAL_FLOW(100) is handled. - libraries/AP_OpticalFlow/AP_OpticalFlow_MAV.cpp:92: Decodes only the pixel-based message.
SCALED_IMU2
Summary
The SCALED_IMU2 message provides high-frequency acceleration and rotation data from the vehicle's secondary inertial sensor (IMU 1). ArduPilot uses this message to stream data from redundant IMUs, allowing Ground Control Stations to monitor the health and alignment of secondary sensors in multi-IMU systems.
Status
Supported
Directionality
- TX (Transmit): All Vehicles (Secondary IMU telemetry)
- RX (Receive): None (Ignored)
Transmission (TX)
The transmission logic is implemented in a unified helper GCS_MAVLINK::send_scaled_imu within libraries/GCS_MAVLink/GCS_Common.cpp:2259.
Data Sourcing
- Secondary Instance: This message specifically transmits data from IMU 1.
- Time Source: Uses a millisecond timestamp (
AP_HAL::millis()). - Scaling: (Identical to
SCALED_IMUID 26)- Accelerometer: Scaled to milli-G (mG).
- Gyroscope: Scaled to millirad/s (rad/s * 1000).
- Magnetometer: Scaled to milli-Gauss (mGauss).
Scheduling
- Sent as part of the
MSG_SCALED_IMU2stream. - Triggered in
GCS_Common.cpp:6312within thetry_send_messageloop.
Data Fields
time_boot_ms: Timestamp (milliseconds since system boot).xacc: X acceleration (mg).yacc: Y acceleration (mg).zacc: Z acceleration (mg).xgyro: Angular speed around X axis (millirad /sec).ygyro: Angular speed around Y axis (millirad /sec).zgyro: Angular speed around Z axis (millirad /sec).xmag: X Magnetic field (milli tesla).ymag: Y Magnetic field (milli tesla).zmag: Z Magnetic field (milli tesla).
Practical Use Cases
- Redundancy Monitoring:
- Scenario: A high-end hexacopter has triple-redundant IMUs.
- Action: The GCS graphs
SCALED_IMU(IMU 0) andSCALED_IMU2(IMU 1) together. If one sensor shows significantly more vibration than the other, the pilot can identify a mechanical issue near that specific sensor mounting point.
- Vibration Isolation Testing:
- Scenario: A builder is testing a new silicone damping mount for the flight controller.
- Action: By comparing the data from a hard-mounted IMU (reported via one message) against a dampened IMU (reported via another), the builder can quantify the effectiveness of the vibration isolation.
Key Codebase Locations
- libraries/GCS_MAVLink/GCS_Common.cpp:2259: Core logic for scaling and sending IMU data.
- libraries/GCS_MAVLink/GCS_Common.cpp:6310: Dispatcher for the secondary IMU stream.
GPS_INJECT_DATA
Summary
The GPS_INJECT_DATA message carries RTCM correction data sent from a ground-based RTK Base Station (via the GCS) to the vehicle. This data is injected into the onboard GPS receiver to enable Real-Time Kinematic (RTK) precision (centimeter-level accuracy).
Status
RX Only
Directionality
- TX (Transmit): None
- RX (Receive): All Vehicles (Receives RTCM corrections)
Reception (RX)
Reception is handled by AP_GPS::handle_gps_inject within libraries/AP_GPS/AP_GPS.cpp:1236.
Protocol Logic
- Extraction: The message payload (
data) and length (len) are extracted. - Routing: The data is passed to
handle_gps_rtcm_fragment, which routes the raw RTCM bytes to the configured GPS instances. - Forwarding: Drivers like
AP_GPS_UBLOXwrite these bytes directly to the GPS module's UART port.
Data Fields
target_system: System ID.target_component: Component ID.len: Data length (bytes).data: Raw data (up to 110 bytes).
Practical Use Cases
- RTK Positioning:
- Scenario: A survey drone uses a Here3+ GPS.
- Action: Mission Planner connects to a local Base Station (via USB or NTRIP). It packages the RTCM stream into
GPS_INJECT_DATAmessages and sends them to the drone over the telemetry link. The drone achieves "RTK Fixed" status.
Key Codebase Locations
- libraries/AP_GPS/AP_GPS.cpp:1236: Implementation of the handler.
GPS2_RAW
Summary
The GPS2_RAW message provides raw satellite positioning data from the vehicle's secondary GPS receiver (GPS 1). In multi-GPS or "Blended" setups, this message allows the Ground Control Station (GCS) to monitor the health and fix quality of the backup receiver independently of the primary or fused position estimate.
Status
Supported
Directionality
- TX (Transmit): All Vehicles (Reports secondary GPS data)
- RX (Receive): None (Ignored)
Transmission (TX)
The transmission logic resides in AP_GPS::send_mavlink_gps2_raw within libraries/AP_GPS/AP_GPS.cpp:1405.
Data Sourcing
- Secondary Instance: Unlike
GPS_RAW_INT(24) which uses GPS instance 0, this message specifically pulls data from GPS instance 1. - Fields: Includes the standard set of GPS metrics:
lat,lon: Sourced in $degrees \times 10^7$.alt: MSL Altitude in millimeters.vel,cog: Ground speed (cm/s) and Course Over Ground (centidegrees).satellites_visible: Number of satellites used by the secondary receiver.dgps_numch,dgps_age: Metadata for Differential GPS (DGPS) or RTK correction.
Scheduling
- Sent as part of the
MSG_GPS2_RAWstream. - Triggered in
GCS_Common.cpp:6213within thetry_send_messageloop.
Data Fields
time_usec: Timestamp (microseconds since UNIX epoch or microseconds since system boot).fix_type: GPS fix type (GPS_FIX_TYPE).lat: Latitude (WGS84, EGM96 ellipsoid), in degrees * 1E7.lon: Longitude (WGS84, EGM96 ellipsoid), in degrees * 1E7.alt: Altitude (MSL). Positive for up.eph: GPS HDOP horizontal dilution of precision in cm (m*100). If unknown, set to: UINT16_MAX.epv: GPS VDOP vertical dilution of precision in cm (m*100). If unknown, set to: UINT16_MAX.vel: GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX.cog: Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX.satellites_visible: Number of satellites visible. If unknown, set to 255.dgps_numch: Number of DGPS satellites.dgps_age: Age of DGPS info.
Practical Use Cases
- Redundancy Verification:
- Scenario: A high-value cinematic drone is flying a mission.
- Action: The pilot monitors
GPS_RAW_INTandGPS2_RAWside-by-side. If the primary GPS loses lock (drops to 0 satellites), the pilot can see if the secondary GPS still has a healthy 3D fix before deciding to continue the flight.
- Blended GPS Analysis:
- Scenario: A developer is using
GPS_TYPE=1(Blending) to merge data from two different brands of GPS receivers. - Action: The developer logs both messages to analyze which receiver provides better performance in high-multipath environments (e.g., near buildings).
- Scenario: A developer is using
- RTK Baseline Monitoring:
- Scenario: Using a "Moving Baseline" setup for GPS Yaw.
- Action: The GCS uses
GPS2_RAWto verify that the "Rover" GPS (the secondary unit) is receiving RTK corrections from the "Base" GPS.
Key Codebase Locations
- libraries/AP_GPS/AP_GPS.cpp:1405: Implementation of the MAVLink packet construction for GPS 1.
- libraries/GCS_MAVLink/GCS_Common.cpp:6213: Scheduling logic.
GPS2_STATUS
Summary
The GPS2_STATUS message is defined in the MAVLink protocol to provide detailed satellite-level information for a secondary GPS receiver, including PRN, SNR, Elevation, and Azimuth for each visible satellite. ArduPilot does not implement or transmit this message.
Status
Unsupported
Directionality
- TX (Transmit): None
- RX (Receive): None (Ignored)
Analysis
Consistent with the lack of support for the primary GPS_STATUS (25) message, ArduPilot does not stream satellite constellations for secondary receivers via MAVLink. General health, fix type, and satellite counts for the second GPS are instead provided by GPS2_RAW (124).
- Absence: There is no handler for
MAVLINK_MSG_ID_GPS2_STATUSin theGCS_MAVLinklibraries. - Alternative: Users needing detailed satellite info typically use "Pass-Through" logging or vendor-specific tools.
Intended Data Fields (Standard)
satellites_visible: Number of satellites visible.satellite_prn: Global satellite ID.satellite_used: 0: Satellite not used, 1: used for localization.satellite_elevation: Elevation (0: right on top of receiver, 90: on the horizon) of satellite.satellite_azimuth: Direction of satellite, 0: 0 deg, 255: 360 deg.satellite_snr: Signal to noise ratio of satellite.
Theoretical Use Cases
- Deep Multipath Analysis:
- Scenario: A rover operating in an urban canyon with two GPS receivers.
- Action: By analyzing the SNR and Elevation of individual satellites from both receivers, a researcher could determine which unit is seeing more obstructed sky and tune the blending weights accordingly.
- Constellation Verification:
- Scenario: Verifying a "Dual Frequency" (L1/L5) receiver.
- Action: Checking the PRN codes to confirm the secondary receiver is actually tracking the specific satellites (e.g., Galileo E5a) claimed by the manufacturer.
Key Codebase Locations
- libraries/GCS_MAVLink/GCS_Common.cpp: Lacks a handler or sender for ID 125.
GPS_RTK
Summary
The GPS_RTK message provides detailed status information about the Real-Time Kinematic (RTK) baseline solution from the primary GPS receiver. It includes the baseline vector (X, Y, Z in millimeters) and accuracy metrics. This message is primarily supported by specific high-precision GPS drivers (Septentrio SBF, Swift Navigation SBP, and Emlid ERB).
Status
Supported
Directionality
- TX (Transmit): All Vehicles (Reports RTK baseline)
- RX (Receive): None (Ignored)
Transmission (TX)
Transmission is handled by AP_GPS_Backend::send_mavlink_gps_rtk within libraries/AP_GPS/GPS_Backend.cpp:176.
Drivers
Only specific GPS drivers implement the supports_mavlink_gps_rtk_message() flag to enable this message:
- SBF: Septentrio
- SBP: Swift Navigation (Piksi)
- ERB: Emlid Reach
Data Fields
time_last_baseline_ms: Time since last baseline (ms) - Currently sent as 0.rtk_receiver_id: RTK receiver ID - Currently sent as 0.wn: GPS Week Number of last baseline.tow: GPS Time of Week of last baseline (ms).rtk_health: RTK health - Currently sent as 0.rtk_rate: RTK rate - Currently sent as 0.nsats: Number of satellites used for RTK.baseline_a_mm: RTK Baseline Coordinate A (mm) - (North or ECEF X depending onbaseline_coords_type).baseline_b_mm: RTK Baseline Coordinate B (mm) - (East or ECEF Y depending onbaseline_coords_type).baseline_c_mm: RTK Baseline Coordinate C (mm) - (Down or ECEF Z depending onbaseline_coords_type).accuracy: RTK accuracy (mm).iar_num_hypotheses: Integer Ambiguity Resolution hypotheses.
Practical Use Cases
- Baseline Monitoring:
- Scenario: A user is setting up a dual-GPS yaw system using SBF receivers.
- Action: The GCS monitors
baseline_a/b/c_mmto visualize the vector between the two antennas, ensuring it matches the physical mounting distance.
Key Codebase Locations
- libraries/AP_GPS/GPS_Backend.cpp:176: Implementation of the sender.
GPS2_RTK
Summary
The GPS2_RTK message provides detailed status information about the Real-Time Kinematic (RTK) baseline solution from the secondary GPS receiver. It functions identically to GPS_RTK (127).
Status
Supported
Directionality
- TX (Transmit): All Vehicles (Reports secondary RTK baseline)
- RX (Receive): None (Ignored)
Transmission (TX)
Transmission is handled by AP_GPS_Backend::send_mavlink_gps_rtk within libraries/AP_GPS/GPS_Backend.cpp:176.
Drivers
Only specific GPS drivers implement the supports_mavlink_gps_rtk_message() flag to enable this message:
- SBF: Septentrio
- SBP: Swift Navigation (Piksi)
- ERB: Emlid Reach
Data Fields
time_last_baseline_ms: Time since last baseline (ms) - Currently sent as 0.rtk_receiver_id: RTK receiver ID - Currently sent as 0.wn: GPS Week Number of last baseline.tow: GPS Time of Week of last baseline (ms).rtk_health: RTK health - Currently sent as 0.rtk_rate: RTK rate - Currently sent as 0.nsats: Number of satellites used for RTK.baseline_a_mm: RTK Baseline Coordinate A (mm) - (North or ECEF X).baseline_b_mm: RTK Baseline Coordinate B (mm) - (East or ECEF Y).baseline_c_mm: RTK Baseline Coordinate C (mm) - (Down or ECEF Z).accuracy: RTK accuracy (mm).iar_num_hypotheses: Integer Ambiguity Resolution hypotheses.
Practical Use Cases
- Dual-Antenna GPS Yaw:
- Scenario: A rover uses two Swift Navigation Piksi Multi receivers for moving baseline yaw.
- Action: The GCS monitors
GPS_RTK(Primary) andGPS2_RTK(Secondary) to verify that both units are calculating baselines correctly relative to the base station or each other.
Key Codebase Locations
- libraries/AP_GPS/GPS_Backend.cpp:176: Implementation of the sender.
SCALED_IMU3
Summary
The SCALED_IMU3 message provides high-frequency acceleration and rotation data from the vehicle's tertiary inertial sensor (IMU 2). This message is primarily used on high-end flight controllers with three or more IMUs, providing the final layer of redundancy for state estimation.
Status
Supported
Directionality
- TX (Transmit): All Vehicles (Tertiary IMU telemetry)
- RX (Receive): None (Ignored)
Transmission (TX)
The transmission logic is implemented in a unified helper GCS_MAVLINK::send_scaled_imu within libraries/GCS_MAVLink/GCS_Common.cpp:2259.
Data Sourcing
- Tertiary Instance: This message specifically transmits data from IMU 2.
- Time Source: Uses a millisecond timestamp (
AP_HAL::millis()). - Scaling: (Identical to
SCALED_IMUID 26)- Accelerometer: Scaled to milli-G (mG).
- Gyroscope: Scaled to millirad/s (rad/s * 1000).
- Magnetometer: Scaled to milli-Gauss (mGauss).
Scheduling
- Sent as part of the
MSG_SCALED_IMU3stream. - Triggered in
GCS_Common.cpp:6316within thetry_send_messageloop.
Data Fields
time_boot_ms: Timestamp (milliseconds since system boot).xacc: X acceleration (mg).yacc: Y acceleration (mg).zacc: Z acceleration (mg).xgyro: Angular speed around X axis (millirad /sec).ygyro: Angular speed around Y axis (millirad /sec).zgyro: Angular speed around Z axis (millirad /sec).xmag: X Magnetic field (milli tesla).ymag: Y Magnetic field (milli tesla).zmag: Z Magnetic field (milli tesla).
Practical Use Cases
- Triple Redundancy Voting:
- Scenario: A high-reliability flight controller uses a voting system between three IMUs.
- Action: If two IMUs agree but
SCALED_IMU3disagrees, the flight controller "votes out" the tertiary sensor. The GCS displays this disagreement using the streamed data from all three messages.
- Hardware Identification:
- Scenario: A developer is writing a driver for a new IMU chip mounted as the third sensor on a custom board.
- Action: The developer monitors
SCALED_IMU3to verify that the raw driver is correctly passing scaled values to the GCS.
Key Codebase Locations
- libraries/GCS_MAVLink/GCS_Common.cpp:2259: Core logic for scaling and sending IMU data.
- libraries/GCS_MAVLink/GCS_Common.cpp:6315: Dispatcher for the tertiary IMU stream.
DISTANCE_SENSOR
Summary
The DISTANCE_SENSOR message reports a single measurement from a distance sensor (LIDAR, Sonar, Radar). It provides the distance, sensor type, min/max range, and the sensor's orientation relative to the vehicle frame. This message is crucial for terrain following, precision landing, and obstacle avoidance.
Status
Supported
Directionality
- TX (Transmit): All Vehicles (Reports sensor data)
- RX (Receive): None (ArduPilot consumes
OBSTACLE_DISTANCEorOBSTACLE_DISTANCE_3Dfor reception typically, thoughDISTANCE_SENSORdecoding exists in some limited proximity contexts)
Transmission (TX)
The transmission logic is in GCS_MAVLINK::send_distance_sensor within libraries/GCS_MAVLink/GCS_Common.cpp:411.
Data Sourcing
ArduPilot aggregates data from two libraries:
AP_RangeFinder: For dedicated 1D sensors (e.g., downward facing altimeters).- Iterates through all healthy backends.
- Populates
type,orientation,min_distance,max_distance, andcurrent_distancedirectly from the driver.
AP_Proximity: For obstacle avoidance sensors (e.g., 360 LIDAR sectors).- Iterates through valid proximity sectors (0-7 for 8-way octomap).
- Synthesizes a "Virtual Sensor" message for each active sector.
idstarts atPROXIMITY_SENSOR_ID_START.
Data Fields
time_boot_ms: Timestamp (milliseconds since system boot).min_distance: Minimum distance the sensor can measure (cm).max_distance: Maximum distance the sensor can measure (cm).current_distance: Current distance reading (cm).type: Type of distance sensor (MAV_DISTANCE_SENSOR_LASER,ULTRASOUND, etc.).id: Onboard ID of the sensor.orientation: Direction the sensor faces (MAV_SENSOR_ORIENTATION). 0=Forward, 24=Down.covariance: Measurement covariance (cm^2), 0 for unknown.horizontal_fov: Horizontal Field of View (radians).vertical_fov: Vertical Field of View (radians).quaternion: Quaternion of the sensor orientation (w, x, y, z).signal_quality: Signal quality (0 = unknown, 1 = invalid, 100 = perfect).
Practical Use Cases
- Terrain Following:
- Scenario: A plane is flying at low altitude over hilly terrain.
- Action: The GCS monitors
DISTANCE_SENSOR(Orientation: Down) to verify the plane is maintaining the target AGL (Above Ground Level) altitude.
- Obstacle Visualization:
- Scenario: A copter is flying near a wall.
- Action: The GCS receives a stream of
DISTANCE_SENSORmessages with Orientations 0 (Forward), 2 (Right), etc., and draws a "Radar View" showing the distance to obstacles in each quadrant.
- Sensor Health Check:
- Scenario: A pilot suspects a sonar sensor is faulty.
- Action: Inspecting the message stream reveals that
current_distanceis stuck atmin_distance, indicating a hardware fault or noise floor issue.
Key Codebase Locations
- libraries/GCS_MAVLink/GCS_Common.cpp:411: Implementation of the sender.
- libraries/AP_RangeFinder/AP_RangeFinder.cpp: Source of rangefinder data.
SCALED_PRESSURE2
Summary
The SCALED_PRESSURE2 message provides calibrated environmental data from the vehicle's secondary sensors. It reports absolute pressure (from Barometer 2) and differential pressure (from Airspeed Sensor 2). This allows Ground Control Stations to monitor sensor redundancy and health.
Status
Supported
Directionality
- TX (Transmit): All Vehicles (Reports secondary sensor data)
- RX (Receive): None (Ignored)
Transmission (TX)
The transmission logic is implemented in GCS_MAVLINK::send_scaled_pressure2 within libraries/GCS_MAVLink/GCS_Common.cpp:2359.
Data Sourcing
- Absolute Pressure (
press_abs): Sourced from the secondary barometer (Index 1) viaAP_Baro. Values are in Hectopascals (hPa). - Differential Pressure (
press_diff): Sourced from the secondary airspeed sensor (Index 1) viaAP_Airspeed. Values are in hPa. - Temperature: Includes the barometer's ambient temperature reading in centidegrees Celsius.
- Temperature Differential: Includes the airspeed sensor's temperature reading in centidegrees Celsius.
Data Fields
time_boot_ms: Timestamp (milliseconds since system boot).press_abs: Absolute pressure (hectopascal).press_diff: Differential pressure 1 (hectopascal).temperature: Absolute pressure temperature (centidegrees Celsius).temperature_press_diff: Differential pressure temperature (centidegrees Celsius).
Practical Use Cases
- Redundancy Checks:
- Scenario: A pilot receives a "Bad Baro Health" warning.
- Action: The GCS graphs
SCALED_PRESSUREandSCALED_PRESSURE2side-by-side. IfSCALED_PRESSUREis flatlining butSCALED_PRESSURE2is responding to altitude changes, it confirms the primary sensor has failed.
- Dual Airspeed Setup:
- Scenario: A VTOL plane has a pitot tube on each wing.
- Action: The pilot monitors
press_difffrom both messages to ensure neither tube is blocked by ice or debris.
Key Codebase Locations
- libraries/GCS_MAVLink/GCS_Common.cpp:2359: Message dispatcher.
- libraries/GCS_MAVLink/GCS_Common.cpp:2308: Shared logic for populating pressure instances.
ATT_POS_MOCAP
Summary
The ATT_POS_MOCAP message provides high-precision position and attitude data from an external Motion Capture (MoCap) system, such as Vicon or OptiTrack. It is functionally very similar to VICON_POSITION_ESTIMATE (104) and VISION_POSITION_ESTIMATE (102), serving as another entry point for external navigation data.
Status
Supported
Directionality
- TX (Transmit): None
- RX (Receive): All Vehicles (Enables MoCap-based navigation)
Reception (RX)
Reception is handled by GCS_MAVLINK::handle_att_pos_mocap in libraries/GCS_MAVLink/GCS_Common.cpp:3948.
Data Processing
- Decoding: The message is decoded into local X, Y, and Z position ($m$) and a Quaternion ($w, x, y, z$) for attitude.
- Unification: The data is forwarded to the
AP_VisualOdomlibrary viahandle_pose_estimate. - EKF Fusion: The EKF fuses this data as an External Navigation source, allowing the vehicle to fly autonomously without GPS.
Data Fields
time_usec: Timestamp (microseconds since UNIX epoch or microseconds since system boot).q: Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0).x: X position (meters).y: Y position (meters).z: Z position (meters).covariance: Pose covariance matrix upper right triangle.
Practical Use Cases
- Indoor University Labs:
- Scenario: A researcher uses an older MoCap system that natively outputs the
ATT_POS_MOCAPpacket format. - Action: The researcher connects the MoCap computer to the drone's telemetry port. ArduPilot treats the data identically to
VICON_POSITION_ESTIMATE, enabling stable indoor loiter.
- Scenario: A researcher uses an older MoCap system that natively outputs the
Key Codebase Locations
- libraries/GCS_MAVLink/GCS_Common.cpp:3948: Message entry point.
- libraries/AP_VisualOdom/AP_VisualOdom.cpp: Core logic for handling pose estimates.
SCALED_PRESSURE3
Summary
The SCALED_PRESSURE3 message provides calibrated environmental data from the vehicle's tertiary sensors. It reports absolute pressure (from Barometer 3) and differential pressure (from Airspeed Sensor 3). This allows Ground Control Stations to monitor sensor redundancy and health.
Status
Supported
Directionality
- TX (Transmit): All Vehicles (Reports tertiary sensor data)
- RX (Receive): None (Ignored)
Transmission (TX)
The transmission logic is implemented in GCS_MAVLINK::send_scaled_pressure3 within libraries/GCS_MAVLink/GCS_Common.cpp:2364.
Data Sourcing
- Absolute Pressure (
press_abs): Sourced from the tertiary barometer (Index 2) viaAP_Baro. Values are in Hectopascals (hPa). - Differential Pressure (
press_diff): Sourced from the tertiary airspeed sensor (Index 2) viaAP_Airspeed. Values are in hPa. - Temperature: Includes the barometer's ambient temperature reading in centidegrees Celsius.
- Temperature Differential: Includes the airspeed sensor's temperature reading in centidegrees Celsius.
ArduSub Exception
In ArduSub, this message is repurposed to send water temperature data from the AP_TemperatureSensor library if enabled. The pressure fields are set to 0.
Data Fields
time_boot_ms: Timestamp (milliseconds since system boot).press_abs: Absolute pressure (hectopascal).press_diff: Differential pressure 1 (hectopascal).temperature: Absolute pressure temperature (centidegrees Celsius).temperature_press_diff: Differential pressure temperature (centidegrees Celsius).
Practical Use Cases
- Redundancy Checks:
- Scenario: A pilot receives a "Bad Baro Health" warning.
- Action: The GCS graphs
SCALED_PRESSUREandSCALED_PRESSURE3side-by-side. IfSCALED_PRESSUREis flatlining butSCALED_PRESSURE3is responding to altitude changes, it confirms the primary sensor has failed.
- Water Temperature Monitoring:
- Scenario: An ROV is diving in deep water.
- Action: The operator monitors the
temperaturefield ofSCALED_PRESSURE3to track the external water temperature.
Key Codebase Locations
- libraries/GCS_MAVLink/GCS_Common.cpp:2364: Message dispatcher.
- libraries/GCS_MAVLink/GCS_Common.cpp:2308: Shared logic for populating pressure instances.
- ArduSub/GCS_Mavlink.cpp:105: ArduSub override.
LANDING_TARGET
Summary
The LANDING_TARGET message is sent by a companion computer or smart camera to the autopilot. It contains the location of a landing target (like an IR beacon or AprilTag) relative to the vehicle. This data drives the Precision Landing feature.
Status
RX Only
Directionality
- TX (Transmit): None
- RX (Receive): All Vehicles (Enables Precision Landing)
Reception (RX)
Reception is handled by AC_PrecLand_Companion::handle_msg within libraries/AC_PrecLand/AC_PrecLand_Companion.cpp:22.
Protocol Logic
- Frame Check: ArduPilot expects
frameto beMAV_FRAME_BODY_FRDifposition_validis set. - Position Parsing:
- If
position_valid=1: Usesx,y,z(meters) to calculate a Line-of-Sight (LOS) vector. - If
position_valid=0: Usesangle_xandangle_y(radians) to compute the LOS vector.
- If
- Timestamp: The
time_usecis jitter-corrected to match the autopilot's time base. - Usage: The calculated LOS vector is fed into the Precision Landing EKF to estimate the target's position and velocity relative to the vehicle.
Data Fields
time_usec: Timestamp (micros).target_num: Target ID.frame: Coordinate frame (MAV_FRAME).angle_x: X-axis angular offset (radians).angle_y: Y-axis angular offset (radians).distance: Distance to the target (meters).size_x: Size of target along x-axis (radians).size_y: Size of target along y-axis (radians).x: X position (meters).y: Y position (meters).z: Z position (meters).q: Quaternion of landing target orientation.type: Type of landing target (LANDING_TARGET_TYPE).position_valid: Boolean indicating validity of x/y/z.
Practical Use Cases
- IR Lock:
- Scenario: A copter has an IR-Lock camera.
- Action: The IR-Lock driver (onboard or external) detects a beacon and streams
LANDING_TARGETmessages. The copter adjusts its descent to land precisely on the beacon.
- Vision-Based Landing:
- Scenario: A Raspberry Pi runs OpenCV to track an AprilTag.
- Action: The Pi sends
LANDING_TARGETmessages with the tag's relative position. ArduPilot guides the vehicle onto the tag.
Key Codebase Locations
- libraries/AC_PrecLand/AC_PrecLand_Companion.cpp:22: Implementation of the handler.
SENSOR_OFFSETS
Summary
The SENSOR_OFFSETS message was historically used to report raw calibration offsets for the IMU and Magnetometer.
Status
Unsupported
Directionality
- TX (Transmit): None
- RX (Receive): None
Description
ArduPilot does not implement this message. It is deprecated.
Calibration offsets are now handled via:
- Parameters:
INS_ACCOFFS_*,COMPASS_OFS_*. MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS(242): For setting offsets (though this is also largely superseded by onboard calibration routines).
Data Fields
mag_ofs_x: Magnetometer X offset.mag_ofs_y: Magnetometer Y offset.mag_ofs_z: Magnetometer Z offset.mag_declination: Magnetic declination (radians).raw_press: Raw pressure (Pa).raw_temp: Raw temperature (degC).gyro_cal_x: Gyro X calibration.gyro_cal_y: Gyro Y calibration.gyro_cal_z: Gyro Z calibration.accel_cal_x: Accel X calibration.accel_cal_y: Accel Y calibration.accel_cal_z: Accel Z calibration.
AP_ADC
Summary
The AP_ADC message reports raw values from the Analog-to-Digital Converter (ADC). Currently, it is only implemented in the ESP32 HAL for debugging purposes.
Status
Supported (Limited)
Directionality
- TX (Transmit): ESP32 Boards Only
- RX (Receive): None (Ignored)
Transmission (TX)
The transmission logic is located in AP_HAL_ESP32::AnalogIn within libraries/AP_HAL_ESP32/AnalogIn.cpp:377.
Usage
- It sends the raw count of the first 6 ADC channels.
- This appears to be a board-specific debug feature and is not generally broadcast by STM32 or other platforms.
Data Fields
adc1: ADC output 1.adc2: ADC output 2.adc3: ADC output 3.adc4: ADC output 4.adc5: ADC output 5.adc6: ADC output 6.
Practical Use Cases
- Hardware Debugging (ESP32):
- Scenario: A developer is porting ArduPilot to a new ESP32 flight controller.
- Action: They monitor
AP_ADCto verify that the analog pins (Current, Voltage, RSSI) are mapping correctly to the expected ADC channels.
Key Codebase Locations
- libraries/AP_HAL_ESP32/AnalogIn.cpp:377: Implementation of the sender.
WIND
Summary
Reports the estimated wind speed and direction. This data is derived from the EKF (Extended Kalman Filter) or a dedicated wind vane sensor.
Status
Supported (TX Only)
Directionality
- TX (Transmit): Copter, Plane, Blimp - Sends estimated wind vector.
- RX (Receive): None
Transmission (TX)
ArduPilot sends this message to report the wind estimate calculated by the AHRS/EKF or measured by AP_WindVane.
Source: ArduCopter/GCS_Mavlink.cpp
Protocol Logic
The system retrieves the wind vector (x, y, z) from AP::ahrs().wind_estimate() and converts it to polar coordinates (Direction, Speed) for transmission.
- Direction:
degrees(atan2f(-wind.y, -wind.x))(Direction the wind is coming from). - Speed:
wind.length(). - Vertical Speed:
wind.z.
Data Fields
direction: Wind direction (0..360 degrees). 0 = North, 90 = East. Direction wind is coming from.speed: Wind speed in m/s.speed_z: Vertical wind speed in m/s.
Practical Use Cases
-
Situational Awareness:
-
Glider Operations:
- Scenario: A glider pilot looks for thermals.
- Action: The vertical wind speed component (
speed_z) can indicate rising or sinking air masses.
Key Codebase Locations
- ArduCopter/GCS_Mavlink.cpp:1583: Copter sending implementation.
- ArduPlane/GCS_Mavlink.cpp:317: Plane sending implementation.
- libraries/AP_WindVane/AP_WindVane.cpp:432: Library implementation for vehicles with physical wind sensors.
RANGEFINDER
Summary
Raw output from the primary downward-facing rangefinder (lidar/sonar).
Status
Supported (TX Only)
Directionality
- TX (Transmit): Rover, Copter, Plane - Sends raw sensor data.
- RX (Receive): None
Transmission (TX)
ArduPilot sends this message to report the distance measured by the primary rangefinder.
Source: libraries/GCS_MAVLink/GCS_Common.cpp
Protocol Logic
The system queries AP::rangefinder() for the primary instance's distance and voltage.
- Distance: Converted to meters.
- Voltage: Raw voltage from analog sensors (if applicable).
Data Fields
distance: Distance in meters.voltage: Voltage in volts (for analog sensors).
Practical Use Cases
-
Precision Landing:
-
Obstacle Avoidance Tuning:
- Scenario: Calibrating a forward-facing ranger.
- Action: User checks if the reported distance matches the physical distance to an obstacle.
Key Codebase Locations
- libraries/GCS_MAVLink/GCS_Common.cpp:507: Sending implementation.
AIRSPEED_AUTOCAL
Summary
Reports the status of the in-flight airspeed calibration algorithm.
Status
Supported (TX Only)
Directionality
- TX (Transmit): Plane (and others with airspeed sensors) - Sends calibration metrics.
- RX (Receive): None
Transmission (TX)
ArduPilot sends this message when AP_AIRSPEED_AUTOCAL_ENABLE is true and an airspeed sensor is calibrating.
Source: libraries/AP_Airspeed/Airspeed_Calibration.cpp
Protocol Logic
The AP_Airspeed library calculates the ratio between GPS ground speed and airspeed to estimate the ratio error.
- Ratio: The estimated ratio.
- Diff/Scale: Error metrics (difference in X/Y/Z acceleration vs expected drag).
Data Fields
vx: Velocity X (m/s).vy: Velocity Y (m/s).vz: Velocity Z (m/s).diff_pressure: Differential pressure (Pa).EAS2TAS: Estimated True Airspeed ratio.ratio: The calculated airspeed ratio.state_x: Kalman filter state X.state_y: Kalman filter state Y.state_z: Kalman filter state Z.pax: Positive acceleration X.pby: Positive acceleration Y.pcz: Positive acceleration Z.
Practical Use Cases
- Calibration Verification:
- Scenario: Pilot performs loiter circles to calibrate the airspeed sensor.
- Action: The GCS plots
ratioto see if it converges to a stable value.
Key Codebase Locations
- libraries/AP_Airspeed/Airspeed_Calibration.cpp:207: Sending implementation.
COMPASSMOT_STATUS
Summary
Status of the compass motor interference calibration.
Status
Supported (TX Only)
Directionality
- TX (Transmit): Copter - Sends calibration progress.
- RX (Receive): None
Transmission (TX)
ArduPilot sends this message during the CompassMot calibration process.
Source: ArduCopter/compassmot.cpp
Protocol Logic
As the user raises the throttle, the system measures magnetic interference.
- throttle: Current throttle level.
- current: Current draw (Amps).
- interference: Magnitude of interference.
Data Fields
throttle: Throttle value (0-1000).current: Current (Amps).interference: Interference level (0-1000). 1000 = 100% of max acceptable.compensation_x: Compensation vector X.compensation_y: Compensation vector Y.compensation_z: Compensation vector Z.
Practical Use Cases
- Compass/Motor Calibration:
- Scenario: User performs the "CompassMot" procedure.
- Action: GCS displays a live graph of interference vs throttle using this message.
Key Codebase Locations
- ArduCopter/compassmot.cpp:222: Sending implementation.
RPM
Summary
RPM (Revolutions Per Minute) from up to two sensors.
Status
Supported (TX Only)
Directionality
- TX (Transmit): All Vehicles - Sends RPM data.
- RX (Receive): None
Transmission (TX)
ArduPilot sends this message to report data from the AP_RPM library.
Source: libraries/GCS_MAVLink/GCS_Common.cpp
Protocol Logic
Queries AP::rpm() for the speed of the first two configured RPM sensors.
Data Fields
rpm1: Speed of sensor 1 (RPM).rpm2: Speed of sensor 2 (RPM).
Practical Use Cases
- Heli Rotor Speed:
- Scenario: Helicopter pilot monitors head speed.
- Action: GCS displays
rpm1(Main Rotor) andrpm2(Tail Rotor).
Key Codebase Locations
- libraries/GCS_MAVLink/GCS_Common.cpp:1105: Streaming entry.
WIND_COV
Summary
Wind covariance report.
Status
Unsupported
Directionality
- TX (Transmit): None
- RX (Receive): None
Description
ArduPilot does not implement this message. It uses WIND (168) for wind estimation.
Theoretical Use Cases
Wind estimation with uncertainty metrics.
GPS_INPUT
Summary
Inject raw GPS data into the autopilot. This allows a companion computer or external system to act as a virtual GPS sensor.
Status
Supported (RX Only)
Directionality
- TX (Transmit): None
- RX (Receive): All Vehicles - Receives external GPS data.
Reception (RX)
Handled by AP_GPS::handle_msg. The data is fed into the AP_GPS_MAV backend.
Source: libraries/AP_GPS/AP_GPS_MAV.cpp
Protocol Logic
The autopilot treats this message as a reading from a physical GPS connected via MAVLink.
- Time: Must be synced or corrected.
- Flags: Indicate valid fields.
Data Fields
time_usec: Timestamp.gps_id: ID of the GPS sensor (0-3).ignore_flags: Flags for ignored fields.lat: Latitude.lon: Longitude.alt: Altitude.hdop: HDOP.vdop: VDOP.speed_accuracy: Speed accuracy.horiz_accuracy: Horizontal accuracy.vert_accuracy: Vertical accuracy.satellites_visible: Sat count.
Practical Use Cases
- Visual Odometry Bridge:
- Scenario: A companion computer runs VIO (Visual Inertial Odometry).
- Action: It converts VIO poses into
GPS_INPUTmessages so the flight controller can fly in "Loiter" mode without a real GPS.
Key Codebase Locations
- libraries/AP_GPS/AP_GPS_MAV.cpp:46: Handler.
GPS_RTCM_DATA
Summary
RTCM Real-Time Kinematic (RTK) corrections.
Status
Supported (RX Only)
Directionality
- TX (Transmit): None
- RX (Receive): All Vehicles - Receives RTK corrections.
Reception (RX)
Handled by AP_GPS::handle_msg.
Source: libraries/AP_GPS/AP_GPS.cpp
Protocol Logic
The autopilot receives these fragments of RTCMv3 data from the GCS (typically from an NTRIP caster or a local base station) and forwards them to the onboard GPS unit via I2C or Serial to enable RTK Fixed/Float modes.
- fragmentation: Max 180 bytes per message. Large RTCM packets are split across multiple messages.
Data Fields
flags: Fragmentation flags.len: Data length.data: RTCM data bytes.
Practical Use Cases
- Centimeter-Level Positioning:
- Scenario: Surveying mission.
- Action: GCS connects to a CORS network and streams
GPS_RTCM_DATAto the drone. The drone's GPS uses this to achieve 2cm accuracy.
Key Codebase Locations
- libraries/AP_GPS/AP_GPS.cpp:1253: Handler.
VIBRATION
Summary
The VIBRATION message provides real-time metrics on the mechanical noise being experienced by the flight controller's accelerometers. It reports vibration levels in the X, Y, and Z axes and tracks "Clipping" events (when a vibration is so intense that it exceeds the sensor's maximum range). This message is the primary diagnostic tool for identifying motor imbalances, damaged propellers, or inadequate vibration isolation.
Status
Supported
Directionality
- TX (Transmit): All Vehicles (Mechanical health telemetry)
- RX (Receive): None (Ignored)
Transmission (TX)
The transmission logic resides in GCS_MAVLINK::send_vibration within libraries/GCS_MAVLink/GCS_Common.cpp:3005.
Data Sourcing
Vibration metrics are calculated in the AP_InertialSensor library using a multi-stage filtering process (AP_InertialSensor.cpp:2236):
- Isolation: Raw acceleration is compared against a 5Hz low-pass filtered "floor" to isolate high-frequency noise from vehicle movement.
- Smoothing: The square of this difference is smoothed via a 2Hz low-pass filter.
- Root: The final vibration level is the square root of this smoothed value.
- Clipping: The
clipping_0,clipping_1, andclipping_2fields report the cumulative number of times each IMU has experienced an acceleration beyond its hard limit (e.g., 16G or 32G).
Data Fields
time_usec: Timestamp (microseconds since UNIX epoch or microseconds since system boot).vibration_x: Vibration levels on X-axis.vibration_y: Vibration levels on Y-axis.vibration_z: Vibration levels on Z-axis.clipping_0: first accelerometer clipping count.clipping_1: second accelerometer clipping count.clipping_2: third accelerometer clipping count.
Practical Use Cases
- Propeller Balancing:
- Scenario: A pilot installs a new set of carbon fiber propellers.
- Action: The GCS graphs
vibration_z. If the levels are significantly higher than with the previous propellers, the pilot knows the new set is unbalanced and needs mechanical correction.
- Post-Crash Inspection:
- Scenario: A drone survived a minor crash, but the pilot wants to ensure no internal damage occurred.
- Action: By checking the
clippingfields, the pilot can see if the motors are now producing extreme vibration spikes that weren't present before, indicating a bent motor shaft or a cracked frame arm.
- EKF Health Tuning:
- Scenario: A developer is seeing "EKF Lane Switches" in high-speed flight.
- Action: By monitoring the
VIBRATIONlevels, the developer can determine if the lane switches are being caused by mechanical noise "confusing" the state estimator.
Key Codebase Locations
- libraries/GCS_MAVLink/GCS_Common.cpp:3005: Implementation of the MAVLink packet construction.
- libraries/AP_InertialSensor/AP_InertialSensor.cpp:2236: Core vibration calculation logic (
calc_vibration_and_clipping).
ADSB_VEHICLE
Summary
Location and status of a nearby aircraft detected via ADS-B (Automatic Dependent Surveillance-Broadcast).
Status
Supported (RX & TX)
Directionality
- TX (Transmit): All Vehicles - Forwards traffic data to GCS.
- RX (Receive): All Vehicles - Receives traffic data from onboard ADSB receiver (e.g., PingRX).
Transmission (TX)
ArduPilot streams this message to the GCS if an onboard ADSB receiver detects a target. This allows the GCS to display traffic without its own ADSB receiver.
Source: libraries/GCS_MAVLink/GCS_Common.cpp
Reception (RX)
Handled by AP_ADSB::handle_message. The autopilot uses this data for "ADSB Avoidance" (fencing, climbing, or holding to avoid collision).
Source: libraries/AP_ADSB/AP_ADSB.cpp
Data Fields
ICAO_address: Unique aircraft ID.lat: Latitude.lon: Longitude.altitude: Altitude.heading: Heading.hor_velocity: Horizontal speed.ver_velocity: Vertical speed.callsign: Aircraft callsign.emitter_type: Type (Light, Heavy, Heli, etc.).tslc: Time since last communication.flags: Status flags.squawk: Transponder code.
Practical Use Cases
- Collision Avoidance:
- Scenario: A Cessna flies near the drone.
- Action: The onboard PingRX detects the ADS-B Out signal. ArduPilot receives
ADSB_VEHICLE, calculates a collision risk, and automatically initiates a descent to clear the airspace.
Key Codebase Locations
- libraries/AP_ADSB/AP_ADSB.cpp:820: Handler.
COLLISION
Summary
Information about a potential collision with an object (or aircraft).
Status
Supported (TX Only)
Directionality
- TX (Transmit): All Vehicles - Sends collision warning.
- RX (Receive): None
Transmission (TX)
ArduPilot sends this message when the AP_Avoidance library detects an impending collision (via ADSB or other sensors).
Source: libraries/AP_Avoidance/AP_Avoidance.cpp
Protocol Logic
- src: Source of threat (ADSB, MavLink, etc).
- id: ID of threat.
- action: Action taken (None, Report, Climb, Descend).
- threat_level: Severity.
- time_to_minimum_delta: Time until closest approach.
- altitude_minimum_delta: Closest vertical distance.
- horizontal_minimum_delta: Closest horizontal distance.
Data Fields
src: Source ID.id: Threat ID.action: Avoidance action.threat_level: Threat level.time_to_minimum_delta: Time to impact (seconds).altitude_minimum_delta: Vertical miss distance (meters).horizontal_minimum_delta: Horizontal miss distance (meters).
Practical Use Cases
- Pilot Alert:
- Scenario: Automatic avoidance triggers.
- Action: GCS flashes a big red "COLLISION ALERT" warning based on this message, informing the pilot why the drone just suddenly dove 10 meters.
Key Codebase Locations
- libraries/AP_Avoidance/AP_Avoidance.cpp:411: Sending implementation.
OBSTACLE_DISTANCE
Summary
The OBSTACLE_DISTANCE message carries 2D radial distance measurements from a 360-degree sensor (typically a spinning LIDAR or a ring of sonar/ToF sensors). It reports obstacles as an array of distances relative to the vehicle's heading.
Status
RX Only
Directionality
- TX (Transmit): None
- RX (Receive): Autopilot (Consumes sensor data for Obstacle Avoidance)
Reception (RX)
ArduPilot parses this message to populate its internal Proximity database, which in turn drives the Avoidance library (Simple Avoidance, BendyRuler, etc.).
Core Logic
The handler is implemented in AP_Proximity_MAV::handle_obstacle_distance_msg within libraries/AP_Proximity/AP_Proximity_MAV.cpp:120.
- Parsing: It reads the
distances[]array and theincrement(angular width of each sector). - Filtering: It validates each reading against
min_distanceandmax_distance. - Fusion: The valid points are pushed into the 3D Proximity Boundary (
frontend.boundary) and the Object Avoidance Database (database_push). - Correction: It applies any user-configured
PRX_YAW_CORRorPRX_ORIENToffsets to align the sensor data with the vehicle frame.
Data Fields
time_usec: Timestamp (microseconds since UNIX epoch or microseconds since system boot).sensor_type: Class id of the distance sensor type.distances: Distance of obstacles around the UAV with index 0 corresponding to local North + angle_offset, unless otherwise specified in the frame field.increment: Angular width in degrees of each array element.min_distance: Minimum distance the sensor can measure in centimeters.max_distance: Maximum distance the sensor can measure in centimeters.increment_f: Angular width in degrees of each array element.angle_offset: Relative angle offset of the 0-index element in the array.frame: Coordinate frame of reference for the yaw rotation and offset of the sensor data.
Practical Use Cases
- 360 LIDAR Avoidance:
- Scenario: A drone is equipped with an RP-LIDAR A2.
- Action: A companion computer (Raspberry Pi running ROS) reads the LIDAR, converts the point cloud into an
OBSTACLE_DISTANCEarray, and sends it to the flight controller. ArduPilot uses this to stop the drone before it hits a wall ("Simple Avoidance").
Key Codebase Locations
- libraries/AP_Proximity/AP_Proximity_MAV.cpp:120: Implementation of the handler.
ODOMETRY
Summary
The ODOMETRY message is a high-bandwidth packet designed to communicate visual odometry or VIO (Visual Inertial Odometry) data to the Autopilot. It is primarily used to provide external navigation data (Position, Velocity, Attitude) to the EKF3 when GPS is unavailable (e.g., indoor flight).
Status
RX Only
Directionality
- TX (Transmit): None
- RX (Receive): Autopilot (Consumes VIO data for EKF fusion)
Reception (RX)
ArduPilot acts as a consumer of this message, typically from a Companion Computer running ROS or a smart camera (like Realsense T265 or ModalAI VOXL).
Core Logic
The handler is implemented in GCS_MAVLINK::handle_odometry within libraries/GCS_MAVLink/GCS_Common.cpp:3882.
Strict Frame Requirements
ArduPilot is very strict about the coordinate frames used in this message. If these fields do not match exactly, the message is silently ignored:
frame_idMUST beMAV_FRAME_LOCAL_FRD(20).child_frame_idMUST beMAV_FRAME_BODY_FRD(12).
Data Fields
time_usec: Timestamp (microseconds since UNIX epoch or microseconds since system boot).frame_id: Coordinate frame of reference for the pose data.child_frame_id: Coordinate frame of reference for the velocity data.x: X Position (meters).y: Y Position (meters).z: Z Position (meters).q: Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation).vx: X Linear velocity (m/s).vy: Y Linear velocity (m/s).vz: Z Linear velocity (m/s).rollspeed: Roll angular speed (rad/s).pitchspeed: Pitch angular speed (rad/s).yawspeed: Yaw angular speed (rad/s).pose_covariance: Pose covariance matrix upper right triangle.velocity_covariance: Velocity covariance matrix upper right triangle.reset_counter: Estimate reset counter.estimator_type: Type of estimator that is providing the odometry.quality: Optional odometry quality metric as a percentage.
Practical Use Cases
- Indoor Non-GPS Flight:
- Scenario: A drone flying inside a warehouse using a Realsense T265.
- Action: The companion computer reads the camera, converts the pose to MAVLink
ODOMETRY(ensuring FRD frames), and sends it to the flight controller. The EKF3 fuses this data to hold position without GPS.
Key Codebase Locations
- libraries/GCS_MAVLink/GCS_Common.cpp:3882: Implementation of the handler.
RAW_RPM
Summary
The RAW_RPM message is designed to report the unscaled frequency/RPM from a sensor, often before applying scaling factors like pole count or gear ratio.
Status
Unsupported
Directionality
- TX (Transmit): None
- RX (Receive): None
Description
ArduPilot does not implement this message.
ArduPilot supports RPM reporting via:
RPM(226): For dedicated RPM sensors (Hall effect, Optical).ESC_TELEMETRY_1_TO_4(11030+): For RPM data coming directly from ESCs (BLHeli, DroneCAN).
The RAW_RPM message is not currently used in the ArduPilot MAVLink stream.
Intended Data Fields (Standard)
index: RPM Sensor index.frequency: Frequency in Hz.
Theoretical Use Cases
- Sensor Debugging:
- Scenario: A user is setting up a new RPM sensor but doesn't know the magnet layout on the flywheel.
- Action: The sensor reports
RAW_RPM(raw interrupts per second). The user revs the engine to a known speed (audible check) and compares it to the raw frequency to derive the correct scaling factor (Poles).
- Vibration Analysis:
- Scenario: Detecting prop imbalance.
- Action: High-frequency raw data might reveal micro-fluctuations in rotation speed within a single rotation (if sampled fast enough), indicating a damaged blade.
WHEEL_DISTANCE
Summary
The WHEEL_DISTANCE message reports the cumulative distance traveled by each individual wheel, as measured by wheel encoders. This data is critical for odometry-based navigation in ground vehicles (Rover).
Status
Supported (Rover Only)
Directionality
- TX (Transmit): Autopilot (Reports wheel odometry to GCS/Companion)
- RX (Receive): None
Transmission (TX)
The message is generated by the ArduRover firmware's GCS_Mavlink module. It is not currently implemented for Copter or Plane.
Core Logic
The implementation is in Rover::send_wheel_encoder_distance within Rover/GCS_Mavlink.cpp:406.
It iterates through the active wheel sensors (managed by AP_WheelEncoder) and populates the distance array.
Data Fields
time_usec: Timestamp (microseconds since UNIX epoch or microseconds since system boot).count: Number of wheels reported.distance: Distance traveled per wheel (meters).
Practical Use Cases
- Dead Reckoning:
- Scenario: A rover enters a tunnel and loses GPS.
- Action: The Companion Computer uses the
WHEEL_DISTANCEupdates (differential odometry) to estimate the vehicle's path and keep it centered in the lane.
- Slip Detection:
- Scenario: A rover is stuck in mud.
- Action: The
distancevalues increase rapidly while the IMU detects no acceleration. The autopilot detects the discrepancy and triggers a "Stuck" failsafe.
Key Codebase Locations
- Rover/GCS_Mavlink.cpp:406: Implementation of the sender.
VISION_POSITION_DELTA
Summary
The VISION_POSITION_DELTA message reports the change in position (delta) and change in angle (delta) of the vehicle frame since the last update. This is an alternative to providing absolute ODOMETRY and is often easier for optical flow sensors or visual SLAM systems to calculate.
Status
RX Only
Directionality
- TX (Transmit): None
- RX (Receive): Autopilot (Consumes VIO data for EKF fusion)
Reception (RX)
ArduPilot consumes this message via the AP_VisualOdom library.
Core Logic
The handler is implemented in AP_VisualOdom_Backend::handle_vision_position_delta_msg within libraries/AP_VisualOdom/AP_VisualOdom_Backend.cpp:41.
- Rotation: It rotates the incoming delta vectors based on the
VISO_ORIENTparameter (e.g., if the camera is facing down or backward). - Fusion: It calls
AP::[ahrs](/field-manual/mavlink-interface/ahrs.html)().writeBodyFrameOdomto send the delta measurements to the EKF3.
Data Fields
time_usec: Timestamp (us since UNIX epoch).time_delta_usec: Time since the last reported delta.angle_delta: Change in angular position (roll, pitch, yaw) in radians.position_delta: Change in position (x, y, z) in meters.confidence: Confidence level (0-100%).
Practical Use Cases
- Optical Flow:
- Scenario: A specialized optical flow sensor calculates the distance moved (delta) between frames rather than an absolute position.
- Action: The sensor sends
VISION_POSITION_DELTAupdates. The EKF integrates these deltas to estimate velocity and hold position.
Key Codebase Locations
- libraries/AP_VisualOdom/AP_VisualOdom_Backend.cpp:41: Implementation of the handler.
OBSTACLE_DISTANCE_3D
Summary
The OBSTACLE_DISTANCE_3D message provides the location of an obstacle as a 3D vector relative to the vehicle's body frame. Unlike the 2D OBSTACLE_DISTANCE array, this message reports individual points in 3D space, making it suitable for depth cameras (Realsense, OAK-D) that can detect obstacles above or below the vehicle.
Status
RX Only
Directionality
- TX (Transmit): None
- RX (Receive): Autopilot (Consumes sensor data for Avoidance)
Reception (RX)
ArduPilot acts as a consumer of this message, feeding the Proximity library.
Core Logic
The handler is implemented in AP_Proximity_MAV::handle_obstacle_distance_3d_msg within libraries/AP_Proximity/AP_Proximity_MAV.cpp:215.
- Frame Check: It strictly requires
MAV_FRAME_BODY_FRD. - Batching: It accumulates points into a temporary boundary buffer. When the
time_boot_mstimestamp changes (indicating a new frame of data), the accumulated points are pushed to the main 3D boundary. - Mapping: It calculates the pitch and yaw of the obstacle vector to assign it to the correct sector in the 3D spherical buffer.
Data Fields
time_boot_ms: Timestamp (ms since boot). All points belonging to the same "frame" (e.g., depth image) should share the same timestamp.sensor_type: Class id of the distance sensor type.frame: Coordinate frame (Must beMAV_FRAME_BODY_FRD).obstacle_id: Unique ID of the obstacle (unused by ArduPilot).x,y,z: Position of the obstacle in meters (FRD).min_distance: Minimum distance the sensor can measure.max_distance: Maximum distance the sensor can measure.
Practical Use Cases
- Depth Camera Avoidance:
- Scenario: A drone with a forward-facing Realsense D435.
- Action: The companion computer processes the depth map. For every "close" pixel cluster, it sends an
OBSTACLE_DISTANCE_3Dmessage. ArduPilot builds a local 3D map around the vehicle and prevents the pilot from flying forward into the wall.
Key Codebase Locations
- libraries/AP_Proximity/AP_Proximity_MAV.cpp:215: Implementation of the handler.
WATER_DEPTH
Summary
The WATER_DEPTH message reports the depth of the water column beneath a boat, along with the water temperature and the vehicle's geolocation/orientation. This is essential for hydrographic surveys and bathymetry.
Status
Supported (Rover Only)
Directionality
- TX (Transmit): Autopilot (Reports depth to GCS)
- RX (Receive): None
Transmission (TX)
The message is generated by the ArduRover firmware's GCS_Mavlink module. It requires the FRAME_CLASS parameter to be set to "Boat" and a RangeFinder driver to be configured with orientation PITCH_270 (Down).
Core Logic
The implementation is in GCS_MAVLINK_Rover::send_water_depth within Rover/GCS_Mavlink.cpp:189.
It iterates through all connected RangeFinders. If a sensor is facing down and has valid data, it populates the message.
Data Fields
time_boot_ms: Timestamp (ms since boot).id: RangeFinder instance ID.healthy: Sensor health flag.lat/lng: Vehicle Latitude/Longitude (degE7).alt: Vehicle Altitude (m).roll/pitch/yaw: Vehicle attitude (radians). This allows post-processing software to correct for "slant range" errors if the boat is rolling in waves.distance: Depth in meters.temperature: Water temperature in degC.
Practical Use Cases
- Bathymetric Mapping:
- Scenario: A survey boat follows a grid pattern on a lake.
- Action: The GCS records
WATER_DEPTHmessages. Post-processing software combineslat,lng, anddistance(corrected byroll/pitch) to generate a 3D topographic map of the lakebed.
Key Codebase Locations
- Rover/GCS_Mavlink.cpp:189: Implementation of the sender.
HYGROMETER_SENSOR
Summary
The HYGROMETER_SENSOR message reports the ambient temperature and relative humidity measured by an onboard sensor. In ArduPilot, this is typically sourced from high-precision airspeed sensors (like the Sensirion SDP3x series) that include integrated hygrometers.
Status
Supported (Plane Only)
Directionality
- TX (Transmit): Autopilot (Reports environmental data to GCS)
- RX (Receive): None
Transmission (TX)
The message is generated by the ArduPlane firmware's GCS_Mavlink module. It iterates through the configured Airspeed sensors and checks if they provide hygrometer data.
Core Logic
The implementation is in GCS_MAVLINK_Plane::send_hygrometer within ArduPlane/GCS_Mavlink.cpp:473.
It checks for fresh data (now - last_sample_ms < 2000) before transmitting, ensuring old or stale readings are not broadcast.
Data Fields
id: Sensor ID.temperature: Temperature in centi-degrees Celsius (degC * 100).humidity: Humidity in centi-percent (% * 100).
Practical Use Cases
- Icing Detection:
- Scenario: A UAV is flying in cold, damp conditions.
- Action: The GCS monitors
temperatureandhumidity. High humidity near 0°C indicates a high risk of carburetor icing (for gas engines) or wing icing. The pilot can descend or activate anti-ice systems.
- Meteorological Survey:
- Scenario: Weather profiling.
- Action: The drone performs a vertical ascent. The GCS logs
HYGROMETER_SENSORvs Altitude to generate a skew-T log-P diagram of the atmosphere.
Key Codebase Locations
- ArduPlane/GCS_Mavlink.cpp:473: Implementation of the sender.