MAVLINKHUD

HEARTBEAT

ID: 0
Unknown

Summary

The HEARTBEAT message is the most fundamental MAVLink packet. It announces the presence of a MAVLink component (System ID + Component ID) on the network. For ArduPilot, it serves as the primary "I am alive" signal, broadcasting the vehicle type, autopilot type (ARDUPILOTMEGA), system status, and current flight mode. It is also actively listened to by the autopilot to discover Ground Control Stations (GCS) and build the MAVLink routing table.

Directionality

  • TX (Transmit): All Vehicles (Broadcasts presence at 1Hz)
  • RX (Receive): All Vehicles (Discovers GCS and other components)

Transmission (TX)

The primary transmission logic is in GCS_MAVLINK::send_heartbeat within libraries/GCS_MAVLink/GCS_Common.cpp:3098.

Field Construction

  • type: Derived from gcs().frame_type(). Examples: MAV_TYPE_QUADROTOR, MAV_TYPE_FIXED_WING.
  • autopilot: Hardcoded to MAV_AUTOPILOT_ARDUPILOTMEGA (3).
  • base_mode: A bitmask representing the "Arming" state and "Custom Mode" flag. It is populated by the virtual function base_mode(), which maps internal states to MAVLink standard flags (e.g., MAV_MODE_FLAG_SAFETY_ARMED).
  • custom_mode: The raw integer value of the vehicle's specific flight mode (e.g., COPTER_MODE_LOITER = 5). This requires the type field to interpret correctly.
  • system_status: Represents the overall health (e.g., MAV_STATE_STANDBY, MAV_STATE_ACTIVE, MAV_STATE_CRITICAL). It is derived from AP_InternalError and battery/sensor health checks.

Scheduling

  • Frequency: Typically sent at 1Hz.
  • Mechanism: It is usually the first message scheduled in the try_send_message loop, ensuring it has high priority on the link.

Reception (RX)

Reception is handled by GCS_MAVLINK::handle_heartbeat in libraries/GCS_MAVLink/GCS_Common.cpp:4155.

Behaviors

  1. Routing Table Update: The MAVLink_routing library observes the System ID and Component ID of the incoming heartbeat to learn which interface (UART, UDP, etc.) a device is connected to.
  2. GCS Discovery: If a heartbeat arrives with a Component ID of MAV_COMP_ID_MISSIONPLANNER (190) or similar, ArduPilot marks that channel as having an active GCS. This enables GCS-specific failsafes.
  3. Failsafe Monitoring: The timestamp of the last received heartbeat is updated. If this "time since last heartbeat" exceeds a threshold (e.g., FS_GCS_TIMEOUT), the vehicle triggers a GCS Failsafe (RTL/Land).

Data Fields

  • type: Vehicle or component type (MAV_TYPE).
  • autopilot: Autopilot type (MAV_AUTOPILOT). ArduPilot always sends MAV_AUTOPILOT_ARDUPILOTMEGA (3).
  • base_mode: System mode bitfield (MAV_MODE_FLAG). Contains arming status.
  • custom_mode: A bitfield for use for autopilot-specific flags (e.g., flight mode).
  • system_status: System status flag (MAV_STATE).
  • mavlink_version: MAVLink version, not writable by user, added by protocol.

Practical Use Cases

  1. Connection Watchdog:
    • Scenario: An onboard computer (Raspberry Pi) wants to know if the USB connection to the flight controller is active.
    • Action: Listen for HEARTBEAT. If no message is received for 3 seconds, assume the link is down and restart the connection logic.
  2. Flight Mode Display:
    • Scenario: A custom ground station needs to show "LOITER" or "STABILIZE" to the pilot.
    • Action: Read the custom_mode field. Use the type field to determine which enum to map it against (e.g., Copter::Mode vs Plane::Mode).
  3. Arming Status:
    • Scenario: An LED strip on the drone needs to turn Red when Armed and Green when Disarmed.
    • Action: Check the base_mode bitmask for the MAV_MODE_FLAG_SAFETY_ARMED bit.

Key Codebase Locations

SYS_STATUS

ID: 1
Unknown

Summary

The SYS_STATUS message acts as the primary "Health Heartbeat" of the vehicle. It aggregates critical system information—including battery state, sensor health, system load, and internal error counters—into a single, high-frequency telemetry packet. While primarily transmitted by the autopilot to the GCS, it is also uniquely monitored by the ArduSub firmware to track companion computer status.

Directionality

  • TX (Transmit): All Vehicle Types (Copter, Plane, Rover, Sub, Blimp)
  • RX (Receive): ArduSub Only

Transmission (TX)

The primary transmission logic resides in GCS_MAVLINK::send_sys_status within libraries/GCS_MAVLink/GCS_Common.cpp:5754.

Data Sources

  • Power System:
    • voltage_battery (mV), current_battery (10mA units), and battery_remaining (%) are queried directly from the AP_BattMonitor library.
    • It uses the primary battery instance (Index 0).
  • System Load:
    • load (d%) is derived from AP::scheduler().load_average(), representing the MCU utilization.
  • Sensor Status:
    • onboard_control_sensors_present, onboard_control_sensors_enabled, and onboard_control_sensors_health are bitmasks populated by gcs().get_sensor_status_flags().
    • This helper function aggregates health flags from subsystems like AHRS, GPS, Compass, Barometer, and RC Input.
  • Error Tracking:
    • errors_count1, errors_count2, errors_count3, errors_count4 are populated by the AP_InternalError library, tracking software-level faults (e.g., watchdog resets, stack overflows).

Scheduling

  • Sent as part of the periodic telemetry stream.
  • Frequency is controlled by the MSG_SYS_STATUS stream rate parameter (typically SRx_EXT_STAT).

Reception (RX)

Reception logic is specific to ArduSub.

  • Handler: GCS_MAVLINK::handle_message in ArduSub/GCS_Mavlink.cpp:872.
  • Purpose: ArduSub decodes incoming SYS_STATUS messages, likely to monitor the health of the onboard computer (Raspberry Pi/BlueOS) or other MAVLink peripherals sharing the link. This allows the ROV to react to companion computer failures.

Data Fields

  • onboard_control_sensors_present: Bitmap of sensors present (MAV_SYS_STATUS_SENSOR).
  • onboard_control_sensors_enabled: Bitmap of sensors enabled (MAV_SYS_STATUS_SENSOR).
  • onboard_control_sensors_health: Bitmap of sensors healthy (MAV_SYS_STATUS_SENSOR).
  • load: Maximum usage in percent of the mainloop time. 1000 means 100%.
  • voltage_battery: Battery voltage (mV).
  • current_battery: Battery current (10mA).
  • battery_remaining: Battery energy remaining (0% - 100%).
  • drop_rate_comm: Comm error drop rate (0% - 100%).
  • errors_comm: Comm error count.
  • errors_count1: Autopilot-specific error count 1.
  • errors_count2: Autopilot-specific error count 2.
  • errors_count3: Autopilot-specific error count 3.
  • errors_count4: Autopilot-specific error count 4.

Practical Use Cases

  1. Custom Battery Widget:
    • Scenario: A custom OSD or HUD needs to display a battery bar.
    • Action: Read voltage_battery and current_battery. Note that current_battery is in centi-amperes (10mA steps), so divide by 100 to get Amps.
  2. Diagnostics Dashboard:
    • Scenario: A ground crew member sees "EKF Failsafe" and wants to know why.
    • Action: Inspect the onboard_control_sensors_health bitmask. If the bit corresponding to MAV_SYS_STATUS_SENSOR_3D_MAG is 0, the compass is unhealthy.
  3. MCU Overload Warning:
    • Scenario: Developers are testing a new Lua script and the drone feels sluggish.
    • Action: Monitor the load field. If it exceeds 800 (80%), the CPU is saturated, potentially causing loop time violations.

Key Codebase Locations

SYSTEM_TIME

ID: 2
Unknown

Summary

The SYSTEM_TIME message is critical for synchronizing the autopilot's internal clock with the outside world (Ground Control Station or Companion Computer). It serves a dual role: reporting the vehicle's current UTC time and boot time to the GCS (TX), and allowing an external authority to set the vehicle's UTC time (RX). This bidirectional flow is managed by the AP_RTC (Real Time Clock) library.

Directionality

  • TX (Transmit): All Vehicles (Broadcasts current time)
  • RX (Receive): All Vehicles (Updates internal clock)

Transmission (TX)

The transmission logic is implemented in GCS_MAVLINK::send_system_time within libraries/GCS_MAVLink/GCS_Common.cpp:2058.

Data Sources

  • Unix Time (time_unix_usec):
    • Sourced from AP::rtc().get_utc_usec(time_unix).
    • If the RTC has not been initialized (e.g., no GPS lock and no external time received), this value defaults to 0.
  • Boot Time (time_boot_ms):
    • Sourced from AP_HAL::millis().
    • Represents the number of milliseconds since the autopilot firmware started.

Scheduling

  • Sent periodically as part of the telemetry stream (MSG_SYSTEM_TIME).
  • This ensures the GCS can sync its logs with the drone's internal timeline.

Reception (RX)

Reception logic is handled by GCS_MAVLINK::handle_system_time_message in libraries/GCS_MAVLink/GCS_Common.cpp:3745.

Behavior

  1. Extraction: The function extracts time_unix_usec from the incoming message.
  2. Update RTC: It calls AP::rtc().set_utc_usec(time_unix_usec, AP_RTC::SOURCE_MAVLINK_SYSTEM_TIME).
  3. Prioritization: The AP_RTC library determines whether to accept this update.
    • ArduPilot supports multiple time sources (GPS, HW RTC, MAVLink).
    • Generally, GPS time is preferred over MAVLink time. MAVLink time is typically used to initialize the clock before a GPS lock is acquired (e.g., for logging timestamps).

Data Fields

  • time_unix_usec: Timestamp (microseconds since UNIX epoch).
  • time_boot_ms: Timestamp (milliseconds since system boot).

Practical Use Cases

  1. Log Synchronization:
    • Scenario: A user is analyzing flight logs ("DataFlash") alongside a GoPro video recording.
    • Action: Use SYSTEM_TIME to correlate the time_boot_ms in the telemetry log with the real-world UTC timestamp of the video file.
  2. Indoor Navigation (Non-GPS):
    • Scenario: A drone is flying indoors using Optical Flow and has no GPS lock. The logs all show "Jan 1 1970".
    • Action: The Companion Computer (or GCS) sends SYSTEM_TIME to the autopilot on boot. The autopilot accepts this (since no GPS is present) and stamps the logs with the correct date/time.
  3. Video Overlay Latency:
    • Scenario: An OSD developer wants to measure the glass-to-glass latency of the video link.
    • Action: Display time_boot_ms on the HUD. Film the HUD with a high-speed camera alongside a stopwatch. The difference between the displayed boot time and the actual elapsed time gives insight into link latency (though PING is better for round-trip).

Key Codebase Locations

PING

ID: 4
Unknown

Summary

The PING message is defined in the MAVLink standard to test connection latency and reliability. However, ArduPilot does not implement a handler for this message. Sending a PING to an ArduPilot flight controller will result in the message being ignored (or dropped) by the parser.

Directionality

  • TX (Transmit): None
  • RX (Receive): None (Ignored)

Reception (RX)

ArduPilot's MAVLink handling logic (primarily in GCS_Common.cpp) does not contain a switch case for MAVLINK_MSG_ID_PING (4).

  • Behavior: The message is parsed by the low-level MAVLink framer but discarded when no handler is found in the application layer.
  • Implication: You cannot use standard MAVLink PINGs to measure round-trip time (RTT) to the autopilot.

Data Fields (Standard)

  • time_usec: Timestamp (microseconds since UNIX epoch).
  • seq: PING sequence.
  • target_system: 0: request ping from all receiving systems. If greater than 0: message is a ping response and this is the system id of the drone which responded to the ping.
  • target_component: 0: request ping from all receiving components. If greater than 0: message is a ping response and this is the component id of the drone which responded to the ping.

Alternatives

To measure link latency, developers typically rely on:

  1. TIMESYNC (111): Used for sophisticated time synchronization.
  2. SYSTEM_TIME (2): Comparing time_boot_ms against reception time.
  3. Command Round-Trip: Sending a COMMAND_LONG (e.g., MAV_CMD_REQUEST_MESSAGE) and timing the arrival of the COMMAND_ACK.

Key Codebase Locations

Unknown

Summary

The CHANGE_OPERATOR_CONTROL message was designed to allow Ground Control Stations to request or release exclusive control of a vehicle, potentially using a passkey. ArduPilot does not implement this message.

Directionality

  • TX (Transmit): None
  • RX (Receive): None (Ignored)

Reception (RX)

ArduPilot does not have a handler for MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL (5).

Data Fields (Standard)

  • target_system: System the GCS requests control for.
  • control_request: 0: request control of this MAV, 1: Release control of this MAV.
  • version: 0: key as plaintext, 1-255: future, different hashing/encryption.
  • passkey: Password / Key, depending on version.

Use Case (Theoretical)

If implemented, this message would allow:

  • GCS Handover: Transferring control from a Pilot's tablet to a Command Center laptop securely.
  • Lockout: Preventing other GCS instances from sending commands during critical operations.

ArduPilot instead relies on:

  1. Routing Priorities: The GCS sending the most recent heartbeat/commands is generally "active".
  2. RC Override: RC_CHANNELS_OVERRIDE messages.
  3. Owner ID: Newer MAVLink 2.0 security features (though rare in open hobbyist setups).

Key Codebase Locations

Summary

This is the acknowledgement message for CHANGE_OPERATOR_CONTROL. Since the request itself is unsupported in ArduPilot, this acknowledgement is also not implemented.

Directionality

  • TX (Transmit): None
  • RX (Receive): None (Ignored)

Reception (RX)

ArduPilot logic does not contain a handler for MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK (6).

Data Fields (Standard)

  • gcs_system_id: ID of the GCS this is a reply to.
  • control_request: 0: request control of this MAV, 1: Release control of this MAV.
  • ack: 0: ACKs the request. 1: NACKs the request.

Key Codebase Locations

AUTH_KEY

ID: 7
Unknown

Summary

The AUTH_KEY message transmits a 32-byte session key for authenticated communication. ArduPilot does not implement this specific legacy authentication message.

Directionality

  • TX (Transmit): None
  • RX (Receive): None (Ignored)

Reception (RX)

ArduPilot logic does not contain a handler for MAVLINK_MSG_ID_AUTH_KEY (7).

Data Fields (Standard)

  • key: key.

Alternatives

ArduPilot supports MAVLink 2.0 packet signing, which provides cryptographic integrity and authentication at the protocol level (using SHA-256), rather than sending raw keys in a payload.

Key Codebase Locations

TIMESYNC

ID: 111
Supported (Critical)

Summary

The TIMESYNC message is the primary mechanism for high-precision time synchronization between ArduPilot and external MAVLink nodes (like a Ground Control Station or a Companion Computer). It allows systems to calculate the network latency (Round Trip Time) and the clock offset between the devices, ensuring that logs and events are perfectly aligned.

Status

Supported (Critical)

Directionality

  • TX (Transmit): All Vehicles (Requesting or Responding to sync)
  • RX (Receive): All Vehicles (Handling sync requests/responses)

Reception (RX)

Reception is handled by GCS_MAVLINK::handle_timesync in libraries/GCS_MAVLink/GCS_Common.cpp:3617.

Protocol Logic

The message uses two fields, tc1 and ts1, to implement a "Ping-Pong" sync:

  1. Request (tc1 == 0): An external system sends a packet with its current time in ts1. ArduPilot immediately responds by sending a packet back where ts1 is the same, but tc1 is ArduPilot's current system time (in nanoseconds).
  2. Response (tc1 != 0): If ArduPilot receives a packet where tc1 is non-zero, it recognizes it as a response to a request it previously sent. It calculates the Round Trip Time (RTT) and logs the sync event.

Implementation Detail

ArduPilot acts as the "Time Master" in most setups. It does not adjust its internal clock based on TIMESYNC from a GCS; instead, it provides the reference time for the GCS to adjust its own offsets.

Data Fields

  • tc1: Time sync timestamp 1 (nanoseconds).
  • ts1: Time sync timestamp 2 (nanoseconds).

Practical Use Cases

  1. Companion Computer Log Alignment:
    • Scenario: A Jetson Nano is recording video while the drone is flying.
    • Action: The Jetson Nano uses TIMESYNC to determine exactly how many milliseconds its system clock is ahead or behind the flight controller. It then uses this offset to stamp the video frames with the vehicle's time_boot_ms.
  2. Precision Camera Triggering:
    • Scenario: A surveyor is using a mapping camera that triggers via a MAVLink signal.
    • Action: By using TIMESYNC, the camera knows exactly when the "Trigger" message was sent by the autopilot, allowing it to record a capture timestamp that accounts for link latency.
  3. Link Quality Debugging:
    • Scenario: A pilot is experiencing "laggy" controls over a long-range radio.
    • Action: A developer monitors the RTT calculated from TIMESYNC. If the RTT spikes from 100ms to 500ms, it indicates a bottleneck or interference on the telemetry link.

Key Codebase Locations

POWER_STATUS

ID: 125
Supported

Summary

The POWER_STATUS message provides real-time diagnostics for the flight controller's internal power rails. It reports the board's supply voltage (Vcc), the servo rail voltage, and a series of health flags that indicate whether power sources (like a USB cable or a Power Brick) are connected and valid. This message is critical for identifying brownout risks and verifying power redundancy in professional flight systems.

Status

Supported

Directionality

  • TX (Transmit): All Vehicles (Reports internal power health)
  • RX (Receive): None (Ignored)

Transmission (TX)

The transmission logic is in GCS_MAVLINK::send_power_status within libraries/GCS_MAVLink/GCS_Common.cpp:216.

Data Sourcing

  • Voltages: Sourced from the Hardware Abstraction Layer (hal.analogin).
    • vcc: The 5V logic rail voltage in millivolts. Typically ~5000mV.
    • vservo: The voltage on the servo output rail in millivolts. Used to monitor the health of the BEC or battery powering the servos.
  • Flags: A bitmask (MAV_POWER_STATUS) updated in libraries/AP_HAL_ChibiOS/AnalogIn.cpp:792.
    • MAV_POWER_STATUS_BRICK_VALID: Indicates a healthy power supply from the primary battery brick.
    • MAV_POWER_STATUS_USB_CONNECTED: Indicates a USB cable is powering the board.
    • MAV_POWER_STATUS_CHANGED: Set if the power configuration changed during flight (e.g., a battery was lost).

Data Fields

  • Vcc: 5V rail voltage in millivolts.
  • Vservo: Servo rail voltage in millivolts.
  • flags: Power status flags (MAV_POWER_STATUS).

Practical Use Cases

  1. Brownout Prevention:
    • Scenario: A pilot is using high-torque servos that pull a lot of current from the 5V rail.
    • Action: The GCS monitors the vcc field. If the voltage drops below 4.5V during aggressive maneuvers, the GCS triggers a loud "Low Vcc Warning" to warn the pilot of an imminent crash.
  2. Redundancy Verification:
    • Scenario: A high-end drone has dual power bricks for reliability.
    • Action: Before takeoff, the pilot checks the flags field in the "Status" tab to ensure both MAV_POWER_STATUS_BRICK_VALID and a secondary source bit are set.
  3. USB Debugging:
    • Scenario: A user is trying to configure a drone but can't get the motors to spin.
    • Action: The GCS shows USB_CONNECTED is active. Since ArduPilot generally prohibits motor arming while on USB for safety, the pilot knows they must disconnect the cable and use telemetry to test the motors.

Key Codebase Locations

SERIAL_CONTROL

ID: 126
Supported

Summary

The SERIAL_CONTROL message allows a Ground Control Station (GCS) or companion computer to perform low-level read/write operations on the vehicle's serial ports. It serves as a "tunnel," allowing remote configuration of devices (like GPS modules or radios) attached to the autopilot without physical access.

Status

Supported

Directionality

  • TX (Transmit): All Vehicles (Response data)
  • RX (Receive): All Vehicles (Write data / Request read)

Mechanics

The implementation is in GCS_MAVLINK::handle_serial_control in libraries/GCS_MAVLink/GCS_serial_control.cpp:33.

Operations

  1. Port Selection: The device field targets a specific port (e.g., SERIAL_CONTROL_DEV_GPS1).
  2. Locking: Setting SERIAL_CONTROL_FLAG_EXCLUSIVE locks the port, preventing the normal driver (like AP_GPS) from reading/writing. This allows the GCS to take full control.
  3. Writing: Data in the data field is written to the UART.
  4. Reading: If SERIAL_CONTROL_FLAG_RESPOND is set, the autopilot waits up to timeout milliseconds for data to become available on the UART, then sends it back in a SERIAL_CONTROL reply (with SERIAL_CONTROL_FLAG_REPLY set).

Data Fields

  • device: Serial control device type (SERIAL_CONTROL_DEV enum). 0=Telem1, 2=GPS1, 10=Shell, 100+=Serial0...9.
  • flags: Bitmap of flags (SERIAL_CONTROL_FLAG enum).
    • 1: Reply (set by vehicle).
    • 2: Respond (request response).
    • 4: Exclusive (lock port).
    • 8: Blocking (wait for buffer space).
    • 16: Multi (allow multiple response packets).
  • timeout: Timeout for reply data in milliseconds.
  • baudrate: Baudrate of transfer. 0 to keep current.
  • count: How many bytes of data are valid.
  • data: Data payload (up to 70 bytes).

Practical Use Cases

  1. u-blox Pass-Through:
    • Scenario: A user wants to debug a GPS configuration using u-center.
    • Action: Mission Planner sends SERIAL_CONTROL messages to lock the GPS port and tunnel traffic between u-center (on PC) and the GPS module (on drone) via the MAVLink telemetry link.
  2. Remote Shell:
    • Scenario: A developer needs to run NSH commands on Pixhawk.
    • Action: Sending device=SERIAL_CONTROL_DEV_SHELL routes data to the NuttX Shell (NSH), allowing a remote terminal session.

Key Codebase Locations

Unsupported

Summary

The RESOURCE_REQUEST message allows a component to request a specific resource (like a file, image, or binary blob) from another component by URI.

Status

Unsupported

Directionality

  • TX (Transmit): None
  • RX (Receive): None

Description

ArduPilot does not implement this message.

ArduPilot uses specific protocols for resource management:

  1. FTP (FILE_TRANSFER_PROTOCOL): For file system access (logs, params, terrain).
  2. Mission Protocol: For waypoints.
  3. Parameter Protocol: For settings.

Intended Data Fields (Standard)

  • request_id: Request ID.
  • uri_type: The type of requested URI.
  • uri: The URI of the resource requested.
  • transfer_type: The transfer type.
  • storage: The storage ID.
Supported (Critical)

Summary

The AUTOPILOT_VERSION message is a critical diagnostic packet that defines the vehicle's identity and capabilities. It reports the firmware version (e.g., ArduCopter 4.5.1), the specific Git SHA hash of the build, and a bitmask of supported MAVLink features (e.g., whether the drone supports FTP, Mission Commands, or Geofencing). Ground Control Stations use this message during the initial connection handshake to tailor the user interface to the vehicle's specific features.

Status

Supported (Critical)

Directionality

  • TX (Transmit): All Vehicles (Identity and Capability report)
  • RX (Receive): None (Ignored)

Transmission (TX)

The transmission logic resides in GCS_MAVLINK::send_autopilot_version within libraries/GCS_MAVLink/GCS_Common.cpp:2912.

Data Sourcing

  • Version Info: Sourced from the AP_FWVersion library.
    • flight_sw_version: A packed integer representing Major, Minor, and Patch versions.
    • middleware_sw_version: Often contains the version of the underlying HAL (e.g., ChibiOS).
    • flight_custom_version: Stores the 8-byte Git SHA hash of the ArduPilot source tree.
  • Capabilities: A 64-bit bitmask calculated in GCS_MAVLink::capabilities() (GCS_Common.cpp:6980).
    • Flags include MAV_PROTOCOL_CAPABILITY_MISSION_INT, MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT, and MAV_PROTOCOL_CAPABILITY_COMMAND_INT.

Trigger Logic

ArduPilot typically sends this message:

  1. On Request: In response to MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES.
  2. Handshake: Automatically as part of the initial connection sequence with most modern Ground Control Stations.

Data Fields

  • capabilities: Bitmap of capabilities.
  • flight_sw_version: Firmware version number.
  • middleware_sw_version: Middleware version number.
  • os_sw_version: Operating system version number.
  • board_version: HW / board version (last 8 bytes should be silicon ID, if any).
  • flight_custom_version: Custom version field, commonly the first 8 bytes of the git hash.
  • middleware_custom_version: Custom version field, commonly the first 8 bytes of the git hash.
  • os_custom_version: Custom version field, commonly the first 8 bytes of the git hash.
  • vendor_id: ID of the board vendor.
  • product_id: ID of the product.
  • uid: UID if provided by hardware.
  • uid2: UID if provided by hardware.

Practical Use Cases

  1. UI Customization:
    • Scenario: A pilot connects a "Blimp" to Mission Planner.
    • Action: Mission Planner reads AUTOPILOT_VERSION, identifies the vehicle as a Blimp, and hides Copter-specific widgets (like "Motor Test") while showing Blimp-specific controls.
  2. Firmware Integrity Verification:
    • Scenario: An industrial operator needs to ensure all drones in a fleet are running an identical, certified firmware build.
    • Action: A script queries AUTOPILOT_VERSION and compares the flight_custom_version (Git SHA) against the certified hash. If they don't match, the drone is grounded.
  3. Feature Discovery:
    • Scenario: A developer is adding support for "MAVLink FTP" to a custom companion computer.
    • Action: The computer checks the capabilities bitmask. If MAV_PROTOCOL_CAPABILITY_FTP is not set, the computer falls back to standard parameter requests.

Key Codebase Locations

MEMINFO

ID: 152
Supported

Summary

The MEMINFO message provides diagnostics regarding the flight controller's internal memory usage. It reports the amount of free heap memory available to the system, which is critical for ensuring the stability of long-running tasks, Lua scripts, and communication buffers.

Status

Supported

Directionality

  • TX (Transmit): All Vehicles (Reports memory health)
  • RX (Receive): None (Ignored)

Transmission (TX)

The transmission logic is in GCS_MAVLINK::send_meminfo within libraries/GCS_MAVLink/GCS_Common.cpp:208.

Data Sourcing

  • Available Memory: Sourced via hal.util->available_memory(). This returns the number of bytes currently free in the system heap.
  • Fields:
    • brkval: Historically used for the heap break value. In modern ChibiOS-based ArduPilot, this is typically set to 0.
    • freemem: The primary field, reporting free memory in bytes. Note: The standard MAVLink message uses a 16-bit field for freemem, but ArduPilot uses an extension field (freemem32) to support modern MCUs with more than 64KB of RAM.

Data Fields

  • brkval: Heap top.
  • freemem: Free memory (16-bit field, legacy).
  • freemem32: Free memory (32-bit field, preferred).

Practical Use Cases

  1. Lua Script Debugging:
    • Scenario: A developer is writing a complex Lua script to perform autonomous package delivery.
    • Action: The developer monitors the freemem field in the GCS. If the free memory steadily decreases over time, it indicates a "memory leak" in the script (e.g., global variables being created inside a loop).
  2. State-of-Health Monitoring:
    • Scenario: An industrial drone is performing a 2-hour autonomous inspection.
    • Action: The GCS logs the MEMINFO message. If free memory drops below a safety threshold (e.g., 10% of total RAM), the GCS triggers a "Low Memory Warning," advising the operator to land and reboot.
  3. Firmware Stress Testing:
    • Scenario: Developers are testing a new feature that uses large internal buffers (e.g., Terrain following or advanced ADSB).
    • Action: By checking MEMINFO during flight, they can verify that the system has enough headroom to handle peak processing loads without crashing.

Key Codebase Locations

HWSTATUS

ID: 165
Supported

Summary

The HWSTATUS message reports basic hardware health metrics, specifically the board input voltage and I2C error counts.

Status

Supported

Directionality

  • TX (Transmit): All Vehicles (Reports hardware status)
  • RX (Receive): None (Ignored)

Transmission (TX)

Transmission is handled by GCS_MAVLINK::send_hwstatus within libraries/GCS_MAVLink/GCS_Common.cpp:5722.

Data Source

  • Vcc: Retrieved from hal.analogin->board_voltage().
  • I2Cerr: Hardcoded to 0 in modern ArduPilot versions (I2C errors are now typically tracked per-bus in other diagnostic messages).

Data Fields

  • Vcc: Board voltage (mV).
  • I2Cerr: I2C error count (legacy field, often 0).

Practical Use Cases

  1. Brownout Detection:
    • Scenario: A user suspects their flight controller is rebooting in flight.
    • Action: Reviewing the HWSTATUS.Vcc log shows dips below 4.5V, indicating an inadequate power supply or BEC brownout.

Key Codebase Locations

LIMITS_STATUS

ID: 167
Unsupported

Summary

Status of the legacy AP_Limits system. This module was the predecessor to the modern Geofence system.

Status

Unsupported

Directionality

  • TX (Transmit): None
  • RX (Receive): None

Description

This message is deprecated and no longer used in the ArduPilot codebase. It was previously used to report the status of the AP_Limits module (safety limits), which has been superseded by the AC_Fence library and messages like FENCE_STATUS.

Data Fields

  • limits_state: State of AP_Limits.
  • last_trigger: Time of last breach.
  • last_action: Action taken.
  • last_recovery: Recovery action.
  • last_clear: Time of last clear.
  • breach_count: Number of fence breaches.
  • mods_enabled: Bitmask of enabled modules.
  • mods_required: Bitmask of required modules.
  • mods_triggered: Bitmask of triggered modules.

Theoretical Use Cases

  1. Legacy Fence Monitoring:
    • Scenario: Older versions of ArduPilot used this to indicate if the vehicle had breached a geofence or altitude limit.
    • Alternative: Use FENCE_STATUS (162).
Supported (RX Only)

Summary

Request the AUTOPILOT_VERSION message from the vehicle.

Status

Supported (RX Only)

Directionality

  • TX (Transmit): None
  • RX (Receive): All Vehicles - Receives request and responds with version info.

Reception (RX)

Handled by GCS_MAVLINK::handle_send_autopilot_version.

Source: libraries/GCS_MAVLink/GCS_Common.cpp

Protocol Logic

  1. GCS sends AUTOPILOT_VERSION_REQUEST (optionally specifying target system/component).
  2. Vehicle checks if the request is for itself.
  3. Vehicle responds with AUTOPILOT_VERSION (148).

Data Fields

  • target_system: System ID.
  • target_component: Component ID.

Practical Use Cases

  1. Connecting to GCS:
    • Scenario: Mission Planner connects to the drone.
    • Action: It sends this request to determine firmware version, board capabilities, and custom version tags (Git hash).

Key Codebase Locations

  • libraries/GCS_MAVLink/GCS_Common.cpp:4244: Handler.
Supported

Summary

The MESSAGE_INTERVAL message provides information about the current frequency (interval) of a specific MAVLink message on a telemetry link. In ArduPilot, this message is used to respond to Ground Control Station queries about stream rates, allowing the GCS to verify that the vehicle is sending data at the requested speed.

Status

Supported

Directionality

  • TX (Transmit): All Vehicles (Reports current message interval)
  • RX (Receive): None (Use MAV_CMD_SET_MESSAGE_INTERVAL to change rates)

Transmission (TX)

ArduPilot sends MESSAGE_INTERVAL primarily in response to the MAV_CMD_GET_MESSAGE_INTERVAL command. The logic is implemented in GCS_MAVLINK::handle_command_get_message_interval within libraries/GCS_MAVLink/GCS_Common.cpp:3241.

Response Logic

  • Active Message: If the requested message ID is being streamed, ArduPilot sends the interval in microseconds.
  • Disabled Message: If the message is currently disabled, it sends -1.
  • Unsupported Message: If the message ID is unknown to the firmware, it sends 0.

Reception (RX)

ArduPilot does not handle the MESSAGE_INTERVAL message if received from an external system. To change a message rate, a GCS must use the command protocol:

  • MAV_CMD_SET_MESSAGE_INTERVAL (511): Used to request a specific message ID at a specific interval. Handled in GCS_MAVLINK::set_message_interval (GCS_Common.cpp:3126).

Data Fields

  • message_id: The ID of the message for which this interval is being reported.
  • interval_us: The interval between two messages, in microseconds. A value of -1 indicates this message is disabled, 0 indicates the message is not supported, > 0 indicates the interval in microseconds.

Practical Use Cases

  1. Dynamic HUD Refresh Rates:
    • Scenario: A GCS wants to show high-speed orientation data ($50Hz$) during takeoff but reduce it to $10Hz$ during cruise to save battery and bandwidth.
    • Action: The GCS sends MAV_CMD_SET_MESSAGE_INTERVAL for ATTITUDE (30). It then sends MAV_CMD_GET_MESSAGE_INTERVAL to verify ArduPilot has successfully applied the $20000\mu s$ (50Hz) interval.
  2. Telemetry Bandwidth Management:
    • Scenario: A pilot is using a low-speed satellite link.
    • Action: The GCS queries the intervals of all active streams. It can then identify high-bandwidth messages that aren't strictly necessary and disable them to prioritize critical telemetry.

Key Codebase Locations

MEMORY_VECT

ID: 249
Unsupported

Summary

Send raw memory content.

Status

Unsupported

Directionality

  • TX (Transmit): None
  • RX (Receive): None

Description

ArduPilot does not implement this message.

Theoretical Use Cases

Debugging.

DEBUG_VECT

ID: 250
Unsupported

Summary

Named vector debug data.

Status

Unsupported

Directionality

  • TX (Transmit): None
  • RX (Receive): None

Description

ArduPilot does not implement this message. It prefers NAMED_VALUE_FLOAT.

Theoretical Use Cases

Debugging.

Supported (RX & TX)

Summary

Key-value pair of a string name and a float value. Used extensively for debugging and Lua scripting integration.

Status

Supported (RX & TX)

Directionality

  • TX (Transmit): All Vehicles - Sends debug/script data.
  • RX (Receive): All Vehicles - Receives debug/script data.

Transmission (TX)

Lua scripts often use gcs:send_named_float('my_var', value) to output debug data to the GCS graph.

Source: libraries/GCS_MAVLink/GCS.cpp

Reception (RX)

Handled by GCS_MAVLink::handle_named_value. Useful for injecting data into scripts or logging external events.

Source: libraries/GCS_MAVLink/GCS_Common.cpp

Data Fields

  • time_boot_ms: Timestamp.
  • name: Name string (10 chars max).
  • value: Float value.

Practical Use Cases

  1. Lua Script Debugging:
    • Scenario: Developing a complex Lua script for thermal soaring.
    • Action: The script sends gcs:send_named_float('vario', climb_rate) to visualize the internal climb rate filter on the GCS tuning graph.

Key Codebase Locations

  • libraries/GCS_MAVLink/GCS.cpp:122: Sending.

NAMED_VALUE_INT

ID: 252
Supported (RX Only)

Summary

Key-value pair of a string name and an integer value.

Status

Supported (RX Only)

Directionality

  • TX (Transmit): None
  • RX (Receive): Copter (Toy Mode) - Receives control events.

Reception (RX)

Handled by ToyMode::handle_message in ArduCopter. Used for interactions with specific "Toy" controllers (SkyViper).

Source: ArduCopter/GCS_Mavlink.cpp

Data Fields

  • time_boot_ms: Timestamp.
  • name: Name string (10 chars max).
  • value: Int value.

Practical Use Cases

  1. Toy Controller Buttons:
    • Scenario: A SkyViper controller button is pressed.
    • Action: It sends a NAMED_VALUE_INT (e.g., "BTN_A", 1). ArduPilot receives this and triggers a flip or mode change.

Key Codebase Locations

  • ArduCopter/GCS_Mavlink.cpp:1511: Handler.

STATUSTEXT

ID: 253
Supported (RX & TX)

Summary

Text message status report. This is the primary way ArduPilot communicates errors, warnings, and info messages to the user.

Status

Supported (RX & TX)

Directionality

  • TX (Transmit): All Vehicles - Sends status messages.
  • RX (Receive): All Vehicles - Receives status messages (e.g., from companion computer).

Transmission (TX)

ArduPilot sends this message whenever gcs().send_text() is called. This covers everything from "Armed" messages to "EKF Variance" errors.

Reception (RX)

Handled by GCS_MAVLink::handle_statustext.

  • Logging: Logs the text to the Dataflash log.
  • Forwarding: Forwards the message to other active MAVLink channels (e.g., forwarding a message from a companion computer to the GCS).

Source: libraries/GCS_MAVLink/GCS_Common.cpp

Data Fields

  • severity: Severity level (MAV_SEVERITY_EMERGENCY to MAV_SEVERITY_DEBUG).
  • text: Text string (50 chars max).

Practical Use Cases

  1. Failsafe Notification:
    • Scenario: Battery low.
    • Action: ArduPilot sends STATUSTEXT (Severity: CRITICAL) "Battery Low!". The GCS speaks this alert to the pilot.

Key Codebase Locations

  • libraries/GCS_MAVLink/GCS_Common.cpp:4328: Handler.

DEBUG

ID: 254
Unsupported

Summary

Generic debug message.

Status

Unsupported

Directionality

  • TX (Transmit): None
  • RX (Receive): None

Description

ArduPilot does not implement this message.

Theoretical Use Cases

Debugging.

SETUP_SIGNING

ID: 256
Supported (RX Only)

Summary

Setup a secret key for MAVLink packet signing.

Status

Supported (RX Only)

Directionality

  • TX (Transmit): None
  • RX (Receive): All Vehicles - Receives new signing key.

Reception (RX)

Handled by GCS_MAVLink::handle_setup_signing.

Source: libraries/GCS_MAVLink/GCS_Common.cpp

Protocol Logic

Sets the 32-byte secret key and the initial timestamp. This enables cryptographic authentication of MAVLink packets.

Data Fields

  • target_system: System ID.
  • target_component: Component ID.
  • secret_key: 32-byte secret key.
  • initial_timestamp: Initial timestamp.

Practical Use Cases

  1. Securing the Link:
    • Scenario: Preventing hijacking.
    • Action: GCS generates a key and sends SETUP_SIGNING. The drone now ignores commands that aren't signed with this key.

Key Codebase Locations

  • libraries/GCS_MAVLink/GCS_Common.cpp:4181: Handler.
Unsupported

Summary

The PROTOCOL_VERSION message is designed to allow a MAVLink node to report the range of protocol versions it supports (e.g., MAVLink 1.0 vs 2.0). ArduPilot does not currently implement or transmit this message.

Status

Unsupported

Directionality

  • TX (Transmit): None
  • RX (Receive): None (Ignored)

Analysis

ArduPilot handles protocol versioning implicitly at the communication layer.

  • Discovery: Ground Control Stations detect the MAVLink version by inspecting the start-of-frame byte ($0xFE$ for v1.0, $0xFD$ for v2.0).
  • Capabilities: Comprehensive capability and version reporting are handled by the AUTOPILOT_VERSION (148) message, which ArduPilot fully supports.
  • Absence: There is no handler or sender for ID 300 in the GCS_MAVLink libraries.

Key Codebase Locations

Unsupported

Summary

The DEBUG_FLOAT_ARRAY message allows sending a large array of floating-point values for debugging purposes. It is useful for dumping internal state vectors or matrices.

Status

Unsupported

Directionality

  • TX (Transmit): None
  • RX (Receive): None

Description

ArduPilot does not implement this message.

For debugging, ArduPilot typically uses:

Intended Data Fields (Standard)

  • time_usec: Timestamp.
  • name: Name ID.
  • array_id: Unique ID for the array.
  • data: Array of floats.

Theoretical Use Cases

  1. Visualizing Internal State:
    • Scenario: Tuning a new neural network controller.
    • Action: The autopilot outputs the entire 64-float activation layer of the neural net via DEBUG_FLOAT_ARRAY at 50Hz. A visualizer tool plots this heatmap in real-time, helping the developer understand what features the network is activating on.
  2. Spectral Analysis:
    • Scenario: In-flight vibration analysis.
    • Action: The autopilot performs an FFT on the gyro data and downlinks the frequency bins as a float array. The engineer sees a spike at 80Hz and knows the props need balancing.

DEVICE_OP_READ

ID: 11000
Supported

Summary

The DEVICE_OP_READ message provides a mechanism for low-level debugging of I2C and SPI devices connected to the Autopilot. It allows a developer to read raw registers from sensors or peripherals directly via MAVLink, bypassing the standard driver abstractions.

Status

Supported

Directionality

  • TX (Transmit): None
  • RX (Receive): Autopilot (Executes the read operation)

Usage

This message is typically sent by a developer tool (like MAVProxy) to diagnose hardware issues (e.g., "Is the compass responding on I2C bus 0 at address 0x1E?").

Core Logic

The handler is implemented in GCS_MAVLINK::handle_device_op_read within libraries/GCS_MAVLink/GCS_DeviceOp.cpp:34.

  1. Device Lookup: It resolves the device using hal.i2c_mgr->get_device() or hal.spi->get_device() based on the bustype.
  2. Semaphore: It attempts to take the bus semaphore to ensure atomic access.
  3. Read: It performs the read operation (read_bank_registers or transfer_bank).
  4. Reply: It sends a DEVICE_OP_READ_REPLY (11001) with the data or an error code.

Data Fields

  • target_system / target_component: Targeted component.
  • request_id: ID to match request with reply.
  • bustype: DEVICE_OP_BUSTYPE_I2C (0) or DEVICE_OP_BUSTYPE_SPI (1).
  • bus: I2C Bus ID.
  • address: I2C Device Address.
  • busname: SPI Bus Name (string).
  • regstart: First register to read.
  • count: Number of bytes to read.
  • bank: Bank number (for devices with banked registers).

Practical Use Cases

  1. Sensor Debugging:
    • Scenario: A new Compass sensor is not being detected.
    • Action: The developer sends DEVICE_OP_READ to the sensor's "WHO_AM_I" register (e.g., 0x75). If the reply contains the correct ID, the hardware is working, and the issue is likely in the driver initialization.

Key Codebase Locations

Supported

Summary

The DEVICE_OP_READ_REPLY message is the response to a DEVICE_OP_READ (11000) command. It returns the requested register data from an I2C or SPI device, along with a result code indicating success or failure.

Status

Supported

Directionality

  • TX (Transmit): Autopilot (Reports read results to GCS)
  • RX (Receive): None

Transmission (TX)

The message is generated by the GCS_MAVLINK library immediately after attempting the requested device read operation.

Core Logic

The implementation is in GCS_MAVLINK::handle_device_op_read within libraries/GCS_MAVLink/GCS_DeviceOp.cpp:77.

It populates the data buffer with the bytes read from the device.

Data Fields

  • request_id: ID matching the request.
  • result: 0=Success, 1=Unknown bus, 2=Unknown device, 3=Semaphore error, 4=Read error, 5=Buffer overflow.
  • regstart: The starting register that was read.
  • count: Number of bytes read.
  • data: Raw data buffer (up to 128 bytes).
  • bank: Bank number.

DEVICE_OP_WRITE

ID: 11002
Supported

Summary

The DEVICE_OP_WRITE message provides a mechanism for low-level debugging of I2C and SPI devices. It allows a developer to write raw values to registers on sensors or peripherals directly via MAVLink.

Status

Supported

Directionality

  • TX (Transmit): None
  • RX (Receive): Autopilot (Executes the write operation)

Usage

WARNING: Using this message allows direct hardware manipulation. Writing incorrect values to sensor registers can crash drivers, disable sensors, or cause physical damage. Use with extreme caution.

Core Logic

The handler is implemented in GCS_MAVLINK::handle_device_op_write within libraries/GCS_MAVLink/GCS_DeviceOp.cpp:101.

  1. Device Lookup: Resolves the device via I2C bus/address or SPI name.
  2. Write: Performs write_bank_register or transfer_bank (if regstart == 0xff).
  3. Reply: Sends DEVICE_OP_WRITE_REPLY (11003) with the result code.

Data Fields

  • target_system / target_component: Targeted component.
  • request_id: ID to match request with reply.
  • bustype: DEVICE_OP_BUSTYPE_I2C (0) or DEVICE_OP_BUSTYPE_SPI (1).
  • bus: I2C Bus ID.
  • address: I2C Device Address.
  • busname: SPI Bus Name (string).
  • regstart: First register to write. Set to 0xFF for raw transfer.
  • count: Number of bytes to write.
  • data: Raw data buffer (up to 128 bytes).
  • bank: Bank number.
Supported

Summary

The DEVICE_OP_WRITE_REPLY message is the response to a DEVICE_OP_WRITE (11002) command. It indicates whether the low-level register write operation was successful.

Status

Supported

Directionality

  • TX (Transmit): Autopilot (Reports write status to GCS)
  • RX (Receive): None

Transmission (TX)

The message is generated by the GCS_MAVLINK library immediately after attempting the requested device write operation.

Core Logic

The implementation is in GCS_MAVLINK::handle_device_op_write within libraries/GCS_MAVLink/GCS_DeviceOp.cpp:140.

Data Fields

  • request_id: ID matching the request.
  • result: 0=Success, 1=Unknown bus, 2=Unknown device, 3=Semaphore error, 4=Write error.

SECURE_COMMAND

ID: 11004
Supported

Summary

The SECURE_COMMAND message allows a Ground Control Station (GCS) to perform sensitive, privileged operations on the Autopilot or connected peripherals. These operations, such as updating bootloader keys or configuring Remote ID, are protected by a digital signature to prevent unauthorized access.

Status

Supported

Directionality

  • TX (Transmit): None
  • RX (Receive): Autopilot (Executes the secure command)

Usage

The command payload must be signed using a private key corresponding to a public key already known to the Autopilot. The signature covers the sequence number, operation, data, and a session key (retrieved via SECURE_COMMAND_GET_SESSION_KEY).

Core Logic

The handler is implemented in AP_CheckFirmware::handle_secure_command within libraries/AP_CheckFirmware/AP_CheckFirmware_secure_command.cpp:270.

  1. Verification: It calls check_signature() to verify the command payload against the stored public keys.
  2. Execution: If valid, it performs the requested operation (e.g., updating the bootloader's key table).
  3. Reply: It sends a SECURE_COMMAND_REPLY (11005) with the result.

Operations (SECURE_COMMAND_OP)

  • GET_SESSION_KEY: Retrieve a temporary session key.
  • GET_REMOTEID_SESSION_KEY: Retrieve session key for Remote ID module.
  • REMOVE_PUBLIC_KEYS: Clear public keys.
  • GET_PUBLIC_KEYS: Read stored public keys.
  • SET_PUBLIC_KEYS: Write new public keys.
  • GET_REMOTEID_CONFIG: Read Remote ID config.
  • SET_REMOTEID_CONFIG: Write Remote ID config.
  • FLASH_BOOTLOADER: Update the bootloader.

Data Fields

  • target_system / target_component: Targeted component.
  • sequence: Sequence number to prevent replay attacks.
  • operation: Operation ID (SECURE_COMMAND_OP).
  • data_length: Length of data payload.
  • sig_length: Length of signature.
  • data: Payload followed by Signature (max 220 bytes total).
Supported

Summary

The SECURE_COMMAND_REPLY message is the response to a SECURE_COMMAND (11004). It indicates the success or failure of the requested secure operation and returns any requested data (e.g., session keys, public keys).

Status

Supported

Directionality

  • TX (Transmit): Autopilot (Reports result to GCS)
  • RX (Receive): None

Transmission (TX)

The message is generated by the AP_CheckFirmware library immediately after processing the secure command.

Core Logic

The implementation is in AP_CheckFirmware::handle_secure_command within libraries/AP_CheckFirmware/AP_CheckFirmware_secure_command.cpp:386.

Data Fields

  • sequence: Sequence number from the request.
  • operation: Operation ID from the request.
  • result: Result code (MAV_RESULT).
    • ACCEPTED: Success.
    • DENIED: Signature verification failed.
    • UNSUPPORTED: Unknown operation.
    • FAILED: Internal error (e.g., flash write failed).
  • data_length: Length of return data.
  • data: Return data (up to 220 bytes), such as the Session Key.

OSD_PARAM_CONFIG

ID: 11033
Supported

Summary

The OSD_PARAM_CONFIG message allows a Ground Control Station (GCS) to configure the "Parameter Tuning Screens" of the onboard OSD. This feature enables pilots to tune specific parameters (like PIDs or Rates) using the RC transmitter sticks and the OSD menu, without needing a GCS connected.

Status

Supported

Directionality

  • TX (Transmit): None
  • RX (Receive): Autopilot (Configures OSD screens)

Usage

The GCS sends this message to define which parameters appear on which OSD screen and in what order.

Core Logic

The handler is implemented in AP_OSD::handle_write_msg (which delegates to AP_OSD_ParamScreen) within libraries/AP_OSD/AP_OSD.cpp:654.

It writes the configuration to the OSD_ParamScreen backend.

Data Fields

  • target_system / target_component: Targeted component.
  • request_id: ID to match request with reply.
  • osd_screen: OSD Screen index (1-based).
  • osd_screen_param_index: Index within the screen (0-based).
  • param_id: Parameter name (string).
  • config_type: OSD_PARAM_CONFIG_TYPE (e.g., Min, Max, Step, Value).
  • min_value: Minimum value for tuning.
  • max_value: Maximum value for tuning.
  • increment: Step size for tuning.

Practical Use Cases

  1. Field Tuning:
    • Scenario: A pilot is tuning a new racing drone at the field.
    • Action: They use the GCS to map ATC_RAT_RLL_P, ATC_RAT_RLL_I, and ATC_RAT_RLL_D to OSD Screen 1 using OSD_PARAM_CONFIG. Now, they can land, adjust PIDs using their goggles and sticks, and take off again instantly.
  2. Mission Configuration:
    • Scenario: A survey drone needs adjustable overlap.
    • Action: The integrator maps the custom script parameter SURVEY_OVERLAP to the OSD menu, allowing the operator to change the mission parameter without a laptop.
Supported

Summary

The OSD_PARAM_CONFIG_REPLY message is the response to an OSD_PARAM_CONFIG (11033) command. It indicates whether the requested OSD parameter configuration was accepted or rejected.

Status

Supported

Directionality

  • TX (Transmit): Autopilot (Reports config result to GCS)
  • RX (Receive): None

Transmission (TX)

The message is generated by the AP_OSD library immediately after processing the configuration command.

Core Logic

The implementation is in AP_OSD_ParamScreen::handle_write_msg within libraries/AP_OSD/AP_OSD_ParamScreen.cpp:597.

Data Fields

  • request_id: ID matching the request.
  • result: OSD_PARAM_CONFIG_ERROR enum (Success, Invalid Screen, Invalid Parameter, etc.).

Practical Use Cases

  1. Validation:
    • Scenario: A user tries to map a non-existent parameter "FOO_BAR" to the OSD.
    • Action: The Autopilot replies with OSD_PARAM_CONFIG_REPLY containing OSD_PARAM_INVALID_PARAMETER. The GCS displays an error message to the user: "Parameter not found."
  2. Sync Confirmation:
    • Scenario: A GCS is restoring a saved OSD layout.
    • Action: It sends 10 config messages in rapid succession. It waits for 10 OSD_PARAM_CONFIG_REPLY messages with SUCCESS to confirm the layout has been fully applied to the flight controller.
Supported

Summary

The OSD_PARAM_SHOW_CONFIG message allows a Ground Control Station (GCS) to query the current configuration of the OSD Parameter Tuning screens. This allows the GCS to display or edit the current layout of the OSD menu.

Status

Supported

Directionality

  • TX (Transmit): None
  • RX (Receive): Autopilot (Processes the query)

Usage

The GCS requests information about a specific entry in the OSD parameter list.

Core Logic

The handler is implemented in AP_OSD_ParamScreen::handle_read_msg within libraries/AP_OSD/AP_OSD_ParamScreen.cpp:606.

It looks up the parameter configured at the requested index and replies with its name, limits, and type.

Data Fields

  • target_system / target_component: Targeted component.
  • request_id: ID to match request with reply.
  • osd_screen: OSD Screen index.
  • osd_screen_param_index: Index within the screen.
Supported

Summary

The OSD_PARAM_SHOW_CONFIG_REPLY message is the response to an OSD_PARAM_SHOW_CONFIG (11035) query. It returns the details of a specific parameter configured on the OSD screen, including its name, min/max limits, and tuning increment.

Status

Supported

Directionality

  • TX (Transmit): Autopilot (Reports config to GCS)
  • RX (Receive): None

Transmission (TX)

The message is generated by the AP_OSD library immediately after processing the query.

Core Logic

The implementation is in AP_OSD_ParamScreen::handle_read_msg within libraries/AP_OSD/AP_OSD_ParamScreen.cpp:606.

Data Fields

  • request_id: ID matching the request.
  • result: OSD_PARAM_CONFIG_ERROR enum.
  • param_id: Parameter name string.
  • config_type: Config type (OSD_PARAM_CONFIG_TYPE).
  • min_value: Minimum value.
  • max_value: Maximum value.
  • increment: Step size.

MCU_STATUS

ID: 11039
Supported

Summary

The MCU_STATUS message reports the health telemetry of the Flight Controller's microcontroller unit (MCU). This includes the core temperature and the input voltage to the MCU rail (VDD_5V or VDD_3V3 depending on board design).

Status

Supported

Directionality

  • TX (Transmit): Autopilot (Reports MCU health to GCS)
  • RX (Receive): None

Transmission (TX)

The message is generated by the GCS_MAVLINK library using data from the HAL (Hardware Abstraction Layer).

Core Logic

The implementation is in GCS_MAVLINK::send_mcu_status within libraries/GCS_MAVLink/GCS_Common.cpp:244.

It reads directly from the hal.analogin interface:

  • mcu_temperature(): Internal temperature sensor of the STM32.
  • mcu_voltage(): Voltage measured on the VDD pin or internal reference.

Data Fields

  • MCU_Temperature: Temperature in centi-degrees Celsius (degC * 100).
  • MCU_Voltage: Voltage in milli-volts (mV).
  • MCU_Voltage_min: Minimum voltage recorded since boot (mV).
  • MCU_Voltage_max: Maximum voltage recorded since boot (mV).
  • id: MCU instance ID (usually 0).

Practical Use Cases

  1. Overheating Warning:
    • Scenario: A flight controller is enclosed in a sealed box with no airflow.
    • Action: The GCS monitors MCU_Temperature. If it exceeds 85°C, it warns the pilot of potential thermal shutdown or IMU degradation.
  2. Brownout Detection:
    • Scenario: The 5V BEC powering the flight controller is overloaded by a servo.
    • Action: The MCU_Voltage_min field drops below 4500mV. Post-flight logs reveal the dip, explaining why the GPS glitched (as its voltage also sagged).

Key Codebase Locations