Skip to main content

Documentation Index

Fetch the complete documentation index at: https://mintlify.com/Ardupilot/ardupilot/llms.txt

Use this file to discover all available pages before exploring further.

The GCS_MAVLink library is ArduPilot’s implementation of the MAVLink protocol. It manages every aspect of ground-station communication: sending telemetry streams, handling incoming commands and parameter requests, routing messages between multiple serial ports, and optionally authenticating links with cryptographic signing. Every ArduPilot vehicle type builds on this library.

Telemetry Streaming

Periodic messages (attitude, GPS, battery, RC) are organised into named streams and sent at configurable rates via the SR0_*SR5_* parameters.

Command Handling

Incoming COMMAND_LONG and COMMAND_INT messages are dispatched to per-command handlers and acknowledged with MAV_RESULT values.

Multi-Port Support

Up to 8 simultaneous MAVLink channels (5 on smaller boards) can be active at once, each with independent stream rates and options.

Message Routing

The MAVLink_routing class automatically learns component routes and forwards packets to the correct port, enabling companion-computer topologies.

Core classes

Two classes divide the work: GCS is the global singleton that owns all active channels and provides convenience helpers, while GCS_MAVLINK handles one physical serial port.
ClassRole
GCSGlobal singleton; broadcasts messages to all channels, owns the status-text queue
GCS_MAVLINKPer-channel object; encodes/decodes MAVLink frames, manages stream buckets
MAVLink_routingStatic routing table; learns and forwards messages between channels
GCS_FTPFile-transfer-over-MAVLink implementation (enabled by AP_MAVLINK_FTP_ENABLED)

Sending messages

Status text

The recommended way to send a human-readable message to a GCS is the GCS_SEND_TEXT macro. Unlike calling gcs().send_text() directly, the macro is evaluated lazily and avoids formatting overhead when no GCS is connected.
// Preferred — macro handles severity and format string
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Calibration complete, offset %.2f", offset);

// Also available on the singleton (thread-safe, queued)
gcs().send_text(MAV_SEVERITY_WARNING, "Battery low: %d%%", pct);
MAV_SEVERITY levels (from highest to lowest): EMERGENCY, ALERT, CRITICAL, ERROR, WARNING, NOTICE, INFO, DEBUG.

Named float

send_named_float() sends a NAMED_VALUE_FLOAT MAVLink message — useful for publishing a custom scalar without defining a full log message type:
// Per-channel variant
gcs().chan(0)->send_named_float("MY_SENSOR", value);

// Broadcast to all channels
gcs().send_named_float("MY_SENSOR", value);
Any pre-encoded MAVLink struct can be sent via the low-level send_message() overload that accepts a raw packet pointer and a mavlink_msg_entry_t:
mavlink_my_msg_t pkt {};
pkt.value = 42;
GCS_MAVLINK::send_to_components(
    MAVLINK_MSG_ID_MY_MSG,
    (const char *)&pkt,
    sizeof(pkt));

Telemetry stream rates

Telemetry messages are grouped into named streams. Each stream has a corresponding parameter family SRn_* where n is the port index (0–5).
Stream enumParameter suffixTypical messages
STREAM_RAW_SENSORSRAW_SENSRAW_IMU, SCALED_PRESSURE, SCALED_IMU2
STREAM_EXTENDED_STATUSEXT_STATSYS_STATUS, MEMINFO, NAV_CONTROLLER_OUTPUT
STREAM_RC_CHANNELSRC_CHANSERVO_OUTPUT_RAW, RC_CHANNELS
STREAM_RAW_CONTROLLERRAW_CTRL(reserved for raw controller data)
STREAM_POSITIONPOSITIONGLOBAL_POSITION_INT, LOCAL_POSITION_NED
STREAM_EXTRA1EXTRA1ATTITUDE, SIMSTATE
STREAM_EXTRA2EXTRA2VFR_HUD
STREAM_EXTRA3EXTRA3AHRS, HWSTATUS, WIND, RANGEFINDER
STREAM_PARAMSPARAMSPARAM_VALUE (parameter list streaming)
STREAM_ADSBADSBADSB_VEHICLE
Stream rates are in Hz. A value of 0 disables the stream. Mission Planner and QGroundControl request stream rates on connect via REQUEST_DATA_STREAM.
Set SRn_* parameters to non-zero values in your vehicle’s default parameter file when shipping a product so the GCS receives data immediately, even before it can negotiate rates.

Message routing

MAVLink_routing maintains a table of up to 20 routes. Each route maps a (sysid, compid) pair to the mavlink_channel_t on which that component was last seen. Routes are learned automatically from incoming heartbeats and other messages.
GCS_MAVLINK::routing.check_and_forward()
  ↓ learns the sender's route
  ↓ looks up target sysid/compid
  ↓ forwards to the correct channel (or broadcasts if target is 0)
  → returns true if the message should also be processed locally
Key routing methods (all static, accessible as GCS_MAVLINK::find_by_mavtype(…)):
MethodPurpose
find_by_mavtype(mav_type, sysid, compid, channel)Locate a component by MAV_TYPE
find_by_mavtype_and_compid(mav_type, compid, sysid, channel)Locate by type and component ID
send_to_components(msgid, pkt, pkt_len)Broadcast to all learned components
disable_channel_routing(chan)Prevent forwarding on a channel (e.g. for high-latency links)
MAVLink 2 signing (authentication) is available when AP_MAVLINK_SIGNING_ENABLED is defined. The signing key is stored in EEPROM/flash and loaded at startup.
// Signing is enabled or disabled per-channel via the options bitmask.
// Bit 0 of SERIALn_OPTIONS disables signing on a specific port.
enum class Option : uint16_t {
    MAVLINK2_SIGNING_DISABLED = (1U << 0),
    NO_FORWARD                = (1U << 1),
    NOSTREAMOVERRIDE          = (1U << 2),
    FORWARD_BAD_CRC           = (1U << 3),
};
The signing timestamp is updated automatically when a GPS lock is acquired, preventing replay attacks:
// Called internally when GPS time is valid:
GCS_MAVLINK::update_signing_timestamp(timestamp_usec);
Disabling signing (MAVLINK2_SIGNING_DISABLED) on a radio-connected port is a security risk on vehicles where unauthorised command injection is a concern. Only disable it on trusted, physically secured links.
When AP_MAVLINK_FTP_ENABLED is set, the GCS_FTP class implements the MAVLink FTP sub-protocol (message ID FILE_TRANSFER_PROTOCOL). This allows Mission Planner and QGroundControl to:
  • Download log files directly from the SD card.
  • Upload parameter files.
  • Browse and delete files on the flight controller’s filesystem.
The GCS_MAVLINK channel locks itself (_locked = true) during an active FTP session so that the port is not used for normal MAVLink traffic simultaneously.

Handling incoming commands

COMMAND_LONG and COMMAND_INT

All COMMAND_LONG messages are internally converted to COMMAND_INT via convert_COMMAND_LONG_to_COMMAND_INT(), then dispatched through handle_command_int_packet(). Vehicle subclasses override this method to handle vehicle-specific commands.
// In your vehicle's GCS subclass (e.g. GCS_MAVLINK_Copter):
MAV_RESULT GCS_MAVLINK_MyVehicle::handle_command_int_packet(
    const mavlink_command_int_t &packet,
    const mavlink_message_t &msg)
{
    switch (packet.command) {
    case MAV_CMD_DO_MY_THING:
        return handle_my_thing(packet);
    default:
        return GCS_MAVLINK::handle_command_int_packet(packet, msg);
    }
}
The handler must return a MAV_RESULT value. The base class sends the COMMAND_ACK automatically.

Adding a new message handler

To handle a new incoming MAVLink message type, override handle_message() in your vehicle’s GCS_MAVLINK subclass:
void GCS_MAVLINK_MyVehicle::handle_message(const mavlink_message_t &msg)
{
    switch (msg.msgid) {
    case MAVLINK_MSG_ID_MY_CUSTOM_MSG: {
        mavlink_my_custom_msg_t pkt;
        mavlink_msg_my_custom_msg_decode(&msg, &pkt);
        // process pkt ...
        break;
    }
    default:
        GCS_MAVLINK::handle_message(msg);   // call base for all other IDs
        break;
    }
}
Always call GCS_MAVLINK::handle_message(msg) in the default branch. The base class handles many essential messages (heartbeat, param, mission, timesync, etc.) that must not be silently dropped.

Payload space guards

Before sending a message, check that there is room in the transmit buffer to avoid dropped packets:
// Inside a GCS_MAVLINK method — returns false if no space:
if (!HAVE_PAYLOAD_SPACE(chan, ATTITUDE)) {
    return false;
}
mavlink_msg_attitude_send(chan, ...);

// Shorthand macro that returns false from the current function:
CHECK_PAYLOAD_SIZE(ATTITUDE);
mavlink_msg_attitude_send(chan, ...);

Complete example: custom status and command

// ---- Sending a status text and a named float ----

void MyLibrary::update()
{
    if (some_condition) {
        // Broadcast to all GCS channels
        GCS_SEND_TEXT(MAV_SEVERITY_INFO, "MyLib: event triggered (val=%.1f)", _value);
        gcs().send_named_float("MYLIB_VAL", _value);
    }
}

// ---- Handling a custom COMMAND_INT in a vehicle subclass ----

MAV_RESULT GCS_MAVLINK_MyVehicle::handle_command_int_packet(
    const mavlink_command_int_t &packet,
    const mavlink_message_t &msg)
{
    switch (packet.command) {
    case MAV_CMD_USER_1:
        // packet.param1 .. packet.param7 hold the command arguments
        if (!mylib.do_action((uint8_t)packet.param1)) {
            return MAV_RESULT_FAILED;
        }
        return MAV_RESULT_ACCEPTED;

    default:
        return GCS_MAVLINK::handle_command_int_packet(packet, msg);
    }
}

Key parameters

Set a serial port to MAVLink 1 (1) or MAVLink 2 (2) by setting SERIALn_PROTOCOL. The baud rate is set with SERIALn_BAUD.
Per-channel stream rates in Hz. SR0_* applies to the first MAVLink port, SR1_* to the second, and so on up to SR5_*.
Bitmask of per-port options. Bit 0 disables MAVLink 2 signing. Bit 1 (NO_FORWARD) prevents packets being forwarded to or from this port. Bit 2 (NOSTREAMOVERRIDE) ignores REQUEST_DATA_STREAM from GCS.

Build docs developers (and LLMs) love