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.

AP_GPS is the unified front-end library that manages every GPS and GNSS receiver connected to an ArduPilot autopilot. It abstracts hardware-specific protocols behind a single API, routes incoming serial data to the correct backend driver, maintains per-instance fix state, and exposes position, velocity, and accuracy data to the rest of the flight stack. All other libraries — EKF, AHRS, navigation modes — consume GPS data exclusively through this interface.

Supported protocols

ArduPilot ships backend drivers for a wide range of receivers. The active driver is selected by the GPS_TYPE parameter (one per GPS port).

u-blox (UBX)

Industry-standard binary protocol. Supports F9P, M8P, M9N, and other series. RTK base and rover roles are available via GPS_TYPE 17/18.

NMEA

Generic ASCII sentence protocol. Used by most low-cost receivers, Hemisphere (GPS_TYPE 16), AllyStar (GPS_TYPE 20), and Unicore (GPS_TYPE 24).

SBF (Septentrio)

Binary format from Septentrio receivers, including dual-antenna support (GPS_TYPE 26) for GPS-derived yaw.

DroneCAN

Receives GPS data over CAN bus from DroneCAN-capable modules (GPS_TYPE 9). Supports RTK base/rover over CAN (GPS_TYPE 22/23).

Swift SBP / SBP2

Swift Navigation binary protocol for Piksi and Duro receivers (GPS_TYPE 8).

Novatel GSOF / NOVA

GSOF binary (GPS_TYPE 11) and NovAtel OEMV text (GPS_TYPE 15) formats for survey-grade receivers.
Setting GPS_TYPE 1 (AUTO) instructs ArduPilot to probe each connected receiver at startup and select the correct driver automatically. This is the recommended default for most setups.

Fix types

The AP_GPS_FixType enum (aliased as constants on AP_GPS) describes the quality of the current position solution. Your code should always check the fix type before using position data for flight control.
ConstantValueMeaning
NO_GPS0No GPS hardware detected
NO_FIX1Hardware present but no position lock
GPS_OK_FIX_2D22-D fix (altitude unreliable)
GPS_OK_FIX_3D3Standard 3-D fix
GPS_OK_FIX_3D_DGPS4DGPS-corrected 3-D fix
GPS_OK_FIX_3D_RTK_FLOAT5RTK float solution
GPS_OK_FIX_3D_RTK_FIXED6RTK fixed solution (centimetre accuracy)
For autonomous navigation, require at least GPS_OK_FIX_3D. For precision operations such as survey or precision landing, require GPS_OK_FIX_3D_RTK_FIXED.

Key API methods

The AP_GPS class follows ArduPilot’s singleton pattern. Access the global instance through AP::gps(). Every method below has an overload that accepts a uint8_t instance argument to query a specific GPS unit directly.
AP_GPS_FixType status(void) const;
AP_GPS_FixType status(uint8_t instance) const;
Returns the current fix type for the primary GPS or a named instance. Always check this before trusting position or velocity data.
const Location &location(void) const;
const Location &location(uint8_t instance) const;
Returns the Location struct from the most recent fix. The struct contains latitude (×10⁷ degrees), longitude (×10⁷ degrees), and altitude in centimetres.
const Vector3f &velocity(void) const;
const Vector3f &velocity(uint8_t instance) const;
Returns a Vector3f in NED frame (North, East, Down) in metres per second. Use have_vertical_velocity() to confirm the vertical component is valid.
float ground_speed(void) const;          // m/s
float ground_course(void) const;         // degrees, 0–360
int32_t ground_course_cd(void) const;    // centidegrees
Horizontal speed over ground and heading derived from GPS velocity.
uint8_t num_sats(void) const;
uint8_t num_sats(uint8_t instance) const;
Number of satellites currently contributing to the fix. The EKF pre-arm check typically requires at least 6.
uint16_t get_hdop(void) const;
uint16_t get_vdop(void) const;
Horizontal and vertical dilution of precision, scaled by 100. A value of 155 means HDOP = 1.55. Values of UINT16_MAX indicate the receiver did not report DOP.
bool have_vertical_velocity(void) const;
bool have_vertical_velocity(uint8_t instance) const;
Returns true once the backend has provided at least one valid vertical velocity reading. Not all receivers populate this field.
bool is_healthy(void) const;
bool is_healthy(uint8_t instance) const;
Returns true if the GPS exists and has produced a message within the last 500 ms at a rate greater than 4 Hz. Use this for health reporting rather than checking status() alone.
bool horizontal_accuracy(float &hacc) const;
bool vertical_accuracy(float &vacc) const;
bool speed_accuracy(float &sacc) const;
Returns receiver-reported RMS accuracy estimates in metres (position) or m/s (speed). Each returns false if the receiver does not provide that metric.

Multi-GPS and blending

ArduPilot supports up to two physical GPS receivers simultaneously. The GPS_AUTO_SWITCH parameter controls how multiple instances are combined.
GPS_AUTO_SWITCHBehaviour
0 (NONE)Always use the instance set by GPS_PRIMARY
1 (USE_BEST)Automatically promote the instance with the better fix type
2 (BLEND)Blend both receivers using a weighted average; result appears as a third virtual instance
4 (USE_PRIMARY_IF_3D_FIX)Use primary if it has a 3-D fix, otherwise fall back
GPS blending (GPS_AUTO_SWITCH 2) increases noise on some setups. Always log and review blending performance before relying on it in production missions.
The blended output is accessible at instance index GPS_MAX_INSTANCES - 1 and is exposed through the same AP_GPS API methods as a physical receiver.

GPS engine navigation mode

The GPS_NAVFILTER parameter configures the navigation dynamics model reported to compatible receivers (primarily u-blox). Selecting the wrong model degrades accuracy.
ValueModeRecommended for
6AIRBORNE_1GFixed-wing aircraft
7AIRBORNE_2GMultirotors
8AIRBORNE_4GHigh-accel platforms, racers
0PORTABLEGeneral / testing

Usage example

The following snippet shows the typical pattern for reading GPS data in a library or vehicle mode. Always access GPS through AP::gps() — never create a new AP_GPS instance directly.
#include <AP_GPS/AP_GPS.h>

void example_gps_read()
{
    const AP_GPS &gps = AP::gps();

    // Check fix quality before using position
    if (gps.status() < AP_GPS::GPS_OK_FIX_3D) {
        return; // not usable
    }

    // Read last fix location
    const Location &loc = gps.location();

    // Read 3-D NED velocity
    const Vector3f &vel = gps.velocity();

    // Horizontal speed and course
    float speed_ms  = gps.ground_speed();    // m/s
    float course_deg = gps.ground_course();  // degrees 0–360

    // Satellite and precision info
    uint8_t  sats = gps.num_sats();
    uint16_t hdop = gps.get_hdop();          // scaled ×100

    // Vertical velocity (only if supported by this receiver)
    if (gps.have_vertical_velocity()) {
        float climb = -vel.z; // NED: negative Z is up
    }

    // Per-instance query (second GPS, index 1)
    if (gps.num_sensors() > 1) {
        AP_GPS_FixType fix1 = gps.status(1);
    }
}

GPS yaw (dual-antenna)

Some receivers (u-blox F9P in moving-baseline mode, Septentrio SBF dual-antenna) can provide a GPS-derived yaw angle independent of the compass. This is useful in environments with high magnetic interference.
float yaw_deg, accuracy_deg;
uint32_t time_ms;

if (AP::gps().have_gps_yaw()) {
    AP::gps().gps_yaw_deg(yaw_deg, accuracy_deg, time_ms);
}
Enable dual-antenna yaw by setting:
  • GPS_TYPE = 17 (u-blox RTK Base) on one port
  • GPS_TYPE = 18 (u-blox RTK Rover) on the other port
GPS-derived yaw requires both antennas to be separated by at least 30 cm and rigidly mounted to the airframe. The baseline vector is calibrated automatically at startup.
ParameterDescription
GPS_TYPE / GPS_TYPE2Protocol type per instance (1 = AUTO)
GPS_AUTO_SWITCHMulti-GPS switching/blending strategy
GPS_PRIMARYPreferred primary instance when AUTO_SWITCH = 0
GPS_NAVFILTERNavigation dynamics model sent to u-blox receivers
GPS_GNSS_MODEGNSS constellation mask (GPS, GLONASS, Galileo, BeiDou)
GPS_DRV_OPTIONSDriver option flags (baud rate, RTCM decode, etc.)
GPS_DELAY_MSManual lag override in milliseconds

Build docs developers (and LLMs) love