APM:Libraries
|
#include <AP_GPS_NMEA.h>
Public Member Functions | |
AP_GPS_NMEA (AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port) | |
bool | read () |
const char * | name () const override |
Public Member Functions inherited from AP_GPS_Backend | |
AP_GPS_Backend (AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port) | |
virtual | ~AP_GPS_Backend (void) |
virtual AP_GPS::GPS_Status | highest_supported_status (void) |
virtual bool | is_configured (void) |
virtual void | inject_data (const uint8_t *data, uint16_t len) |
virtual bool | supports_mavlink_gps_rtk_message () |
virtual void | send_mavlink_gps_rtk (mavlink_channel_t chan) |
virtual void | broadcast_configuration_failure_reason (void) const |
virtual void | handle_msg (const mavlink_message_t *msg) |
virtual void | handle_gnss_msg (const AP_GPS::GPS_State &msg) |
virtual bool | get_lag (float &lag) const |
virtual bool | is_healthy (void) const |
void | broadcast_gps_type () const |
virtual void | Write_DataFlash_Log_Startup_messages () const |
virtual bool | prepare_for_arming (void) |
Static Public Member Functions | |
static bool | _detect (struct NMEA_detect_state &state, uint8_t data) |
Private Types | |
enum | _sentence_types { _GPS_SENTENCE_RMC = 32, _GPS_SENTENCE_GGA = 64, _GPS_SENTENCE_VTG = 96, _GPS_SENTENCE_OTHER = 0 } |
Coding for the GPS sentences that the parser handles. More... | |
Private Member Functions | |
bool | _decode (char c) |
int16_t | _from_hex (char a) |
uint32_t | _parse_degrees () |
bool | _term_complete () |
bool | _have_new_message (void) |
return true if we have a new set of NMEA messages More... | |
Static Private Member Functions | |
static int32_t | _parse_decimal_100 (const char *p) |
Private Attributes | |
uint8_t | _parity |
NMEA message checksum accumulator. More... | |
bool | _is_checksum_term |
current term is the checksum More... | |
char | _term [15] |
buffer for the current term within the current sentence More... | |
uint8_t | _sentence_type |
the sentence type currently being processed More... | |
uint8_t | _term_number |
term index within the current sentence More... | |
uint8_t | _term_offset |
character offset with the term being received More... | |
bool | _gps_data_good |
set when the sentence indicates data is good More... | |
int32_t | _new_time |
time parsed from a term More... | |
int32_t | _new_date |
date parsed from a term More... | |
int32_t | _new_latitude |
latitude parsed from a term More... | |
int32_t | _new_longitude |
longitude parsed from a term More... | |
int32_t | _new_altitude |
altitude parsed from a term More... | |
int32_t | _new_speed |
speed parsed from a term More... | |
int32_t | _new_course |
course parsed from a term More... | |
uint16_t | _new_hdop |
HDOP parsed from a term. More... | |
uint8_t | _new_satellite_count |
satellite count parsed from a term More... | |
uint8_t | _new_quality_indicator |
GPS quality indicator parsed from a term. More... | |
uint32_t | _last_RMC_ms = 0 |
uint32_t | _last_GGA_ms = 0 |
uint32_t | _last_VTG_ms = 0 |
Static Private Attributes | |
static const char | _initialisation_blob [] |
Init strings | |
In init, an attempt is made to configure the GPS unit to send just the messages that we are interested in using these strings | |
static const char | _SiRF_init_string [] |
init string for SiRF units More... | |
static const char | _MTK_init_string [] |
init string for MediaTek units More... | |
static const char | _ublox_init_string [] |
init string for ublox units More... | |
Friends | |
class | AP_GPS_NMEA_Test |
Additional Inherited Members | |
Protected Member Functions inherited from AP_GPS_Backend | |
int32_t | swap_int32 (int32_t v) const |
int16_t | swap_int16 (int16_t v) const |
void | fill_3d_velocity (void) |
void | make_gps_time (uint32_t bcd_date, uint32_t bcd_milliseconds) |
void | _detection_message (char *buffer, uint8_t buflen) const |
bool | should_df_log () const |
Protected Attributes inherited from AP_GPS_Backend | |
AP_HAL::UARTDriver * | port |
UART we are attached to. More... | |
AP_GPS & | gps |
access to frontend (for parameters) More... | |
AP_GPS::GPS_State & | state |
public state for this instance More... | |
NMEA parser
Definition at line 51 of file AP_GPS_NMEA.h.
|
private |
Coding for the GPS sentences that the parser handles.
Enumerator | |
---|---|
_GPS_SENTENCE_RMC | |
_GPS_SENTENCE_GGA | |
_GPS_SENTENCE_VTG | |
_GPS_SENTENCE_OTHER |
Definition at line 69 of file AP_GPS_NMEA.h.
AP_GPS_NMEA::AP_GPS_NMEA | ( | AP_GPS & | _gps, |
AP_GPS::GPS_State & | _state, | ||
AP_HAL::UARTDriver * | _port | ||
) |
Definition at line 53 of file AP_GPS_NMEA.cpp.
|
private |
Update the decode state machine with a new character
c | The next character in the NMEA input stream |
Definition at line 84 of file AP_GPS_NMEA.cpp.
Referenced by read().
|
static |
Definition at line 421 of file AP_GPS_NMEA.cpp.
Referenced by AP_GPS::detect_instance().
|
private |
Return the numeric value of an ascii hex character
a | The character to be converted |
Definition at line 125 of file AP_GPS_NMEA.cpp.
Referenced by _term_complete().
|
private |
return true if we have a new set of NMEA messages
Definition at line 211 of file AP_GPS_NMEA.cpp.
Referenced by _term_complete().
|
staticprivate |
Parses the as
a NMEA-style decimal number with up to 3 decimal digits.
, multiplied by 100. Definition at line 135 of file AP_GPS_NMEA.cpp.
Referenced by _term_complete(), and AP_GPS_NMEA_Test::parse_decimal_100().
|
private |
Parses the current term as a NMEA-style degrees + minutes value with up to four decimal digits.
This gives a theoretical resolution limit of around 1cm.
Definition at line 166 of file AP_GPS_NMEA.cpp.
Referenced by _term_complete().
|
private |
Processes the current term when it has been deemed to be complete.
Each GPS message is broken up into terms separated by commas. Each term is then processed by this function as it is received.
Definition at line 237 of file AP_GPS_NMEA.cpp.
Referenced by _decode().
|
inlineoverridevirtual |
Implements AP_GPS_Backend.
Definition at line 65 of file AP_GPS_NMEA.h.
|
virtual |
Checks the serial receive buffer for characters, attempts to parse NMEA data and updates internal state accordingly.
Implements AP_GPS_Backend.
Definition at line 60 of file AP_GPS_NMEA.cpp.
|
friend |
Definition at line 53 of file AP_GPS_NMEA.h.
|
private |
set when the sentence indicates data is good
Definition at line 128 of file AP_GPS_NMEA.h.
Referenced by _decode(), and _term_complete().
|
staticprivate |
Definition at line 158 of file AP_GPS_NMEA.h.
|
private |
current term is the checksum
Definition at line 123 of file AP_GPS_NMEA.h.
Referenced by _decode(), and _term_complete().
|
private |
Definition at line 145 of file AP_GPS_NMEA.h.
Referenced by _have_new_message(), and _term_complete().
|
private |
Definition at line 144 of file AP_GPS_NMEA.h.
Referenced by _have_new_message(), and _term_complete().
|
private |
Definition at line 146 of file AP_GPS_NMEA.h.
Referenced by _have_new_message(), and _term_complete().
|
staticprivate |
init string for MediaTek units
Definition at line 154 of file AP_GPS_NMEA.h.
|
private |
altitude parsed from a term
Definition at line 137 of file AP_GPS_NMEA.h.
Referenced by _term_complete().
|
private |
course parsed from a term
Definition at line 139 of file AP_GPS_NMEA.h.
Referenced by _term_complete().
|
private |
date parsed from a term
Definition at line 134 of file AP_GPS_NMEA.h.
Referenced by _term_complete().
|
private |
HDOP parsed from a term.
Definition at line 140 of file AP_GPS_NMEA.h.
Referenced by _term_complete().
|
private |
latitude parsed from a term
Definition at line 135 of file AP_GPS_NMEA.h.
Referenced by _term_complete().
|
private |
longitude parsed from a term
Definition at line 136 of file AP_GPS_NMEA.h.
Referenced by _term_complete().
|
private |
GPS quality indicator parsed from a term.
Definition at line 142 of file AP_GPS_NMEA.h.
Referenced by _term_complete().
|
private |
satellite count parsed from a term
Definition at line 141 of file AP_GPS_NMEA.h.
Referenced by _term_complete().
|
private |
speed parsed from a term
Definition at line 138 of file AP_GPS_NMEA.h.
Referenced by _term_complete().
|
private |
time parsed from a term
Definition at line 133 of file AP_GPS_NMEA.h.
Referenced by _term_complete().
|
private |
NMEA message checksum accumulator.
Definition at line 122 of file AP_GPS_NMEA.h.
Referenced by _decode(), and _term_complete().
|
private |
the sentence type currently being processed
Definition at line 125 of file AP_GPS_NMEA.h.
Referenced by _decode(), and _term_complete().
|
staticprivate |
init string for SiRF units
Definition at line 153 of file AP_GPS_NMEA.h.
|
private |
buffer for the current term within the current sentence
Definition at line 124 of file AP_GPS_NMEA.h.
Referenced by _decode(), _parse_degrees(), _term_complete(), and AP_GPS_NMEA().
|
private |
term index within the current sentence
Definition at line 126 of file AP_GPS_NMEA.h.
Referenced by _decode(), and _term_complete().
|
private |
character offset with the term being received
Definition at line 127 of file AP_GPS_NMEA.h.
Referenced by _decode().
|
staticprivate |
init string for ublox units
Definition at line 155 of file AP_GPS_NMEA.h.