65 const char *
name()
const override {
return "NMEA"; }
_sentence_types
Coding for the GPS sentences that the parser handles.
int32_t _new_time
time parsed from a term
uint8_t _new_quality_indicator
GPS quality indicator parsed from a term.
static const char _SiRF_init_string[]
init string for SiRF units
bool _gps_data_good
set when the sentence indicates data is good
static const char _MTK_init_string[]
init string for MediaTek units
uint16_t _new_hdop
HDOP parsed from a term.
static bool _detect(struct NMEA_detect_state &state, uint8_t data)
char _term[15]
buffer for the current term within the current sentence
uint8_t _new_satellite_count
satellite count parsed from a term
bool _have_new_message(void)
return true if we have a new set of NMEA messages
uint8_t _parity
NMEA message checksum accumulator.
static const char _ublox_init_string[]
init string for ublox units
uint32_t _parse_degrees()
AP_GPS::GPS_State & state
public state for this instance
int32_t _new_latitude
latitude parsed from a term
int32_t _new_speed
speed parsed from a term
uint8_t _term_number
term index within the current sentence
int32_t _new_longitude
longitude parsed from a term
const char * name() const override
int16_t _from_hex(char a)
uint8_t _term_offset
character offset with the term being received
int32_t _new_date
date parsed from a term
static int32_t _parse_decimal_100(const char *p)
uint8_t _sentence_type
the sentence type currently being processed
AP_GPS_NMEA(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port)
int32_t _new_altitude
altitude parsed from a term
bool _is_checksum_term
current term is the checksum
static const char _initialisation_blob[]
int32_t _new_course
course parsed from a term