Skip to content

Commit

Permalink
AP_GPS: add an AP_GPS_FixType header
Browse files Browse the repository at this point in the history
useful when you need nice symbols for the numbers, but are not compiling the GPS headers in
  • Loading branch information
peterbarker committed Sep 27, 2023
1 parent 8cfdf10 commit bd16608
Show file tree
Hide file tree
Showing 2 changed files with 29 additions and 0 deletions.
11 changes: 11 additions & 0 deletions libraries/AP_GPS/AP_GPS.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -53,6 +53,7 @@

#include <AP_AHRS/AP_AHRS.h>
#include <AP_Logger/AP_Logger.h>
#include "AP_GPS_FixType.h"

#define GPS_RTK_INJECT_TO_ALL 127
#ifndef GPS_MAX_RATE_MS
Expand Down Expand Up @@ -111,6 +112,16 @@ static_assert((uint32_t)AP_GPS::GPS_Status::GPS_OK_FIX_3D_RTK_FLOAT == (uint32_t
static_assert((uint32_t)AP_GPS::GPS_Status::GPS_OK_FIX_3D_RTK_FIXED == (uint32_t)GPS_FIX_TYPE_RTK_FIXED, "FIX_RTK_FIXED incorrect");
#endif

// ensure that our own enum-class status is equivalent to the
// ArduPilot-scoped AP_GPS_FixType enumeration:
static_assert((uint32_t)AP_GPS::GPS_Status::NO_GPS == (uint8_t)AP_GPS_FixType::NO_GPS, "NO_GPS incorrect");
static_assert((uint32_t)AP_GPS::GPS_Status::NO_FIX == (uint8_t)AP_GPS_FixType::NONE, "NO_FIX incorrect");
static_assert((uint32_t)AP_GPS::GPS_Status::GPS_OK_FIX_2D == (uint8_t)AP_GPS_FixType::FIX_2D, "FIX_2D incorrect");
static_assert((uint32_t)AP_GPS::GPS_Status::GPS_OK_FIX_3D == (uint8_t)AP_GPS_FixType::FIX_3D, "FIX_3D incorrect");
static_assert((uint32_t)AP_GPS::GPS_Status::GPS_OK_FIX_3D_DGPS == (uint8_t)AP_GPS_FixType::DGPS, "FIX_DGPS incorrect");
static_assert((uint32_t)AP_GPS::GPS_Status::GPS_OK_FIX_3D_RTK_FLOAT == (uint8_t)AP_GPS_FixType::RTK_FLOAT, "FIX_RTK_FLOAT incorrect");
static_assert((uint32_t)AP_GPS::GPS_Status::GPS_OK_FIX_3D_RTK_FIXED == (uint8_t)AP_GPS_FixType::RTK_FIXED, "FIX_RTK_FIXED incorrect");

AP_GPS *AP_GPS::_singleton;

// table of user settable parameters
Expand Down
18 changes: 18 additions & 0 deletions libraries/AP_GPS/AP_GPS_FixType.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,18 @@
#pragma once

// a AP_GPS-library-independent enumeration which lists the commonly
// accepted set of GPS Fix Types which GPSs report. This header can
// be used even if AP_GPS is not compiled in.

// this is not enum-class as many places in the code want to check for
// "a fix at least this good" using "<".

enum AP_GPS_FixType {
NO_GPS = 0, ///< No GPS connected/detected
NONE = 1, ///< Receiving valid GPS messages but no lock
FIX_2D = 2, ///< Receiving valid messages and 2D lock
FIX_3D = 3, ///< Receiving valid messages and 3D lock
DGPS = 4, ///< Receiving valid messages and 3D lock with differential improvements
RTK_FLOAT = 5, ///< Receiving valid messages and 3D RTK Float
RTK_FIXED = 6, ///< Receiving valid messages and 3D RTK Fixed
};

0 comments on commit bd16608

Please sign in to comment.