AP_GPS Detailed Reference¶
Header¶
File: libraries/AP_GPS/AP_GPS.h
#include <AP_GPS.h>
Class Documentation¶
-
class AP_GPS¶
GPS driver main class
Public Types
-
enum GPS_Status¶
GPS status codes. These are kept aligned with MAVLink by static_assert in AP_GPS.cpp
Values:
-
enumerator NO_GPS¶
No GPS connected/detected.
-
enumerator NO_FIX¶
Receiving valid GPS messages but no lock.
-
enumerator GPS_OK_FIX_2D¶
Receiving valid messages and 2D lock.
-
enumerator GPS_OK_FIX_3D¶
Receiving valid messages and 3D lock.
-
enumerator GPS_OK_FIX_3D_DGPS¶
Receiving valid messages and 3D lock with differential improvements.
-
enumerator GPS_OK_FIX_3D_RTK_FLOAT¶
Receiving valid messages and 3D RTK Float.
-
enumerator GPS_OK_FIX_3D_RTK_FIXED¶
Receiving valid messages and 3D RTK Fixed.
-
enumerator NO_GPS¶
Public Functions
-
void init()¶
Startup initialisation.
-
void update(void)¶
Update GPS state based on possible bytes received from the module. This routine must be called periodically (typically at 10Hz or more) to process incoming data.
-
inline GPS_Status status(uint8_t instance) const¶
Query GPS status.
-
void lock_port(uint8_t instance, bool locked)¶
Lock a GPS port, preventing the GPS driver from using it. This can be used to allow a user to control a GPS port via the SERIAL_CONTROL protocol
-
uint64_t time_epoch_usec(uint8_t instance) const¶
calculate current time since the unix epoch in microseconds
-
uint64_t last_message_epoch_usec(uint8_t instance) const¶
calculate last message time since the unix epoch in microseconds
Public Static Functions
-
static uint64_t istate_time_to_epoch_ms(uint16_t gps_week, uint32_t gps_ms)¶
convert GPS week and milliseconds to unix epoch in milliseconds
Private Functions
-
void update_primary(void)¶
Update primary instance.
Private Members
-
uint8_t primary_instance¶
primary GPS instance
-
uint8_t num_instances¶
number of GPS instances present
-
struct detect_state¶
-
struct GPS_State¶
Public Members
-
GPS_Status status¶
driver fix status
-
uint32_t time_week_ms¶
GPS time (milliseconds from start of GPS week)
-
uint16_t time_week¶
GPS week number.
-
Location location¶
last fix location
-
float ground_speed¶
ground speed in m/s
-
float ground_course¶
ground course in degrees, wrapped 0-360
-
float gps_yaw¶
GPS derived yaw information, if available (degrees)
-
uint32_t gps_yaw_time_ms¶
timestamp of last GPS yaw reading
-
bool gps_yaw_configured¶
GPS is configured to provide yaw.
-
uint16_t hdop¶
horizontal dilution of precision, scaled by a factor of 100 (155 means the HDOP value is 1.55)
-
uint16_t vdop¶
vertical dilution of precision, scaled by a factor of 100 (155 means the VDOP value is 1.55)
-
uint8_t num_sats¶
Number of visible satellites.
-
Vector3f velocity¶
3D velocity in m/s, in NED format
-
float speed_accuracy¶
3D velocity RMS accuracy estimate in m/s
-
float horizontal_accuracy¶
horizontal RMS accuracy estimate in m
-
float vertical_accuracy¶
vertical RMS accuracy estimate in m
-
float gps_yaw_accuracy¶
heading accuracy of the GPS in degrees
-
bool have_vertical_velocity¶
does GPS give vertical velocity? Set to true only once available.
-
bool have_speed_accuracy¶
does GPS give speed accuracy? Set to true only once available.
-
bool have_horizontal_accuracy¶
does GPS give horizontal position accuracy? Set to true only once available.
-
bool have_vertical_accuracy¶
does GPS give vertical position accuracy? Set to true only once available.
-
bool have_gps_yaw¶
does GPS give yaw? Set to true only once available.
-
bool have_gps_yaw_accuracy¶
does the GPS give a heading accuracy estimate? Set to true only once available
-
bool have_undulation¶
do we have a value for the undulation
-
uint32_t last_gps_time_ms¶
the system time we got the last GPS timestamp, milliseconds
-
bool announced_detection¶
true once we have announced GPS has been seen to the user
-
uint64_t last_corrected_gps_time_us¶
the system time we got the last corrected GPS timestamp, microseconds
-
bool corrected_timestamp_updated¶
true if the corrected timestamp has been updated
-
uint32_t lagged_sample_count¶
number of samples with 50ms more lag than expected
-
uint32_t rtk_time_week_ms¶
GPS Time of Week of last baseline in milliseconds.
-
uint16_t rtk_week_number¶
GPS Week Number of last baseline.
-
uint32_t rtk_age_ms¶
GPS age of last baseline correction in milliseconds (0 when no corrections, 0xFFFFFFFF indicates overflow)
-
uint8_t rtk_num_sats¶
Current number of satellites used for RTK calculation.
-
uint8_t rtk_baseline_coords_type¶
Coordinate system of baseline. 0 == ECEF, 1 == NED.
-
int32_t rtk_baseline_x_mm¶
Current baseline in ECEF x or NED north component in mm.
-
int32_t rtk_baseline_y_mm¶
Current baseline in ECEF y or NED east component in mm.
-
int32_t rtk_baseline_z_mm¶
Current baseline in ECEF z or NED down component in mm.
-
uint32_t rtk_accuracy¶
Current estimate of 3D baseline accuracy (receiver dependent, typical 0 to 9999)
-
int32_t rtk_iar_num_hypotheses¶
Current number of integer ambiguity hypotheses.
-
float relPosHeading¶
Reported Heading in degrees.
-
float relPosLength¶
Reported Position horizontal distance in meters.
-
float relPosD¶
Reported Vertical distance in meters.
-
float accHeading¶
Reported Heading Accuracy in degrees.
-
uint32_t relposheading_ts¶
True if new data has been received since last time it was false.
-
GPS_Status status¶
-
struct GPS_timing¶
-
class Params¶
-
struct rtcm_buffer¶
-
enum GPS_Status¶
Detailed Description¶
AP_GPS is the core GPS driver for ArduPilot, supporting multiple GPS protocols including NMEA, UBX, SBF, and more. It provides position, velocity, time, and satellite information for autonomous navigation.
Key Features:
Multiple GPS backend support (NMEA, UBX, SBF, ERB, etc.)
RTK (Real-Time Kinematic) positioning support
GPS blending for multiple sensors
Singleton pattern for easy access
Inheritance¶
This class does not inherit from any other class. It is a top-level driver class.
Derived Classes:
:doxygen:`AP_GPS_UBLOX` - u-blox GPS driver
:doxygen:`AP_GPS_NMEA` - NMEA GPS driver
:doxygen:`AP_GPS_SBF` - Septentrio GPS driver
Related Classes:
:doxygen:`AP_GPS_Backend` - Base class for GPS backends
:doxygen:`AP_GPS_Blended` - Blended multi-GPS instance
Public Types¶
-
enum AP_GPS::Status¶
GPS fix status indicating the quality of the position fix.
- Noindex:
NO_GPS = 0, // No GPS detected NO_FIX = 1, // No position fix GPS_OK_FIX_2D = 2, // 2D position fix GPS_OK_FIX_3D = 3, // 3D position fix GPS_OK_FIX_3D_DGPS = 4, // 3D with DGPS GPS_OK_FIX_3D_RTK_FLOAT = 5, // 3D with RTK float GPS_OK_FIX_3D_RTK_FIXED = 6 // 3D with RTK fixed
-
enum AP_GPS::GPS_Status
Alias for Status enum for backward compatibility.
Public Member Variables¶
-
AP_GPS::Params AP_GPS::params[GPS_MAX_RECEIVERS]¶
GPS parameters for each instance. Contains configuration like GPS_TYPE, GPS_RATE, GPS_POS_X, GPS_POS_Y, GPS_POS_Z for antenna position.
Public Member Functions¶
Initialization¶
-
void AP_GPS::init()
Initialize GPS driver. Should be called once at system startup.
// Typical usage in setup() gps->init();
-
void AP_GPS::update()
Update GPS data. Must be called in main loop at 10-20Hz.
// Typical usage in main loop gps->update();
Singleton¶
Status Checking¶
-
AP_GPS::Status AP_GPS::status() const¶
Get current GPS fix status of primary instance.
- Returns:
GPS_Status enum (NO_GPS, NO_FIX, GPS_OK_FIX_2D, GPS_OK_FIX_3D, etc.)
-
AP_GPS::Status AP_GPS::status(uint8_t instance) const
Get GPS fix status for specific instance.
- Parameters:
instance – GPS instance index (0 or 1)
- Returns:
GPS_Status enum
-
uint8_t AP_GPS::num_sats() const¶
Get number of satellites being used for position fix.
- Returns:
Number of satellites (0-50)
Position Data¶
Velocity Data¶
-
const Vector3f &AP_GPS::velocity() const¶
Get ground velocity in NED (North-East-Down) frame.
- Returns:
Vector3f containing velocity in m/s (x=North, y=East, z=Down)
-
float AP_GPS::ground_speed() const¶
Get horizontal ground speed magnitude.
- Returns:
Ground speed in m/s
Accuracy Data¶
-
bool AP_GPS::speed_accuracy(float &sacc) const¶
Get estimated speed accuracy.
- Parameters:
sacc – Output parameter for speed accuracy in m/s
- Returns:
true if accuracy data is available
float speed_accuracy; if (gps->speed_accuracy(speed_accuracy)) { // Use speed_accuracy }
Time Data¶
HDOP/VDOP¶
Configuration¶
RTK Support¶
Complete Usage Example¶
#include <AP_GPS.h>
AP_GPS *gps;
void setup() {
gps = AP_GPS::get_singleton();
if (gps == nullptr) {
Serial.println("GPS not available");
return;
}
gps->init();
}
void loop() {
// Update at 10Hz
gps->update();
// Check status
AP_GPS::Status status = gps->status();
if (status >= AP_GPS::GPS_OK_FIX_3D) {
// Get position
Location loc = gps->location();
Serial.printf("Position: %d, %d, %d\n",
loc.lat, loc.lng, loc.alt);
// Get velocity
Vector3f vel = gps->velocity();
Serial.printf("Velocity: %.2f, %.2f, %.2f m/s\n",
vel.x, vel.y, vel.z);
// Get ground speed and course
float ground_speed = gps->ground_speed();
float ground_course = gps->ground_course();
Serial.printf("Ground: %.2f m/s at %.1f degrees\n",
ground_speed, ground_course);
// Get satellite count
uint8_t num_sats = gps->num_sats();
Serial.printf("Satellites: %d\n", num_sats);
// Get accuracy
float speed_acc, horiz_acc, vert_acc;
gps->speed_accuracy(speed_acc);
gps->horizontal_accuracy(horiz_acc);
gps->vertical_accuracy(vert_acc);
Serial.printf("Accuracy: speed=%.2f, horiz=%.2f, vert=%.2f\n",
speed_acc, horiz_acc, vert_acc);
}
}
See Also¶
Sensor Libraries - Overview of sensor libraries
Sensor Libraries - Sensors overview
AP_GPS_UBLOX - u-blox specific driver (see libraries/AP_GPS/)
AP_GPS_Backend - Backend driver base class (see libraries/AP_GPS/)
AP_GPS_Blended - Multi-GPS blending (see libraries/AP_GPS/)