APM:Libraries
Public Member Functions | Static Public Member Functions | Private Types | Private Member Functions | Static Private Member Functions | Private Attributes | Static Private Attributes | Friends | List of all members
AP_GPS_NMEA Class Reference

#include <AP_GPS_NMEA.h>

Inheritance diagram for AP_GPS_NMEA:
[legend]
Collaboration diagram for AP_GPS_NMEA:
[legend]

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::UARTDriverport
 UART we are attached to. More...
 
AP_GPSgps
 access to frontend (for parameters) More...
 
AP_GPS::GPS_Statestate
 public state for this instance More...
 

Detailed Description

NMEA parser

Definition at line 51 of file AP_GPS_NMEA.h.

Member Enumeration Documentation

◆ _sentence_types

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.

Constructor & Destructor Documentation

◆ AP_GPS_NMEA()

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.

Member Function Documentation

◆ _decode()

bool AP_GPS_NMEA::_decode ( char  c)
private

Update the decode state machine with a new character

Parameters
cThe next character in the NMEA input stream
Returns
True if processing the character has resulted in an update to the GPS state

Definition at line 84 of file AP_GPS_NMEA.cpp.

Referenced by read().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ _detect()

bool AP_GPS_NMEA::_detect ( struct NMEA_detect_state state,
uint8_t  data 
)
static

Definition at line 421 of file AP_GPS_NMEA.cpp.

Referenced by AP_GPS::detect_instance().

Here is the caller graph for this function:

◆ _from_hex()

int16_t AP_GPS_NMEA::_from_hex ( char  a)
private

Return the numeric value of an ascii hex character

Parameters
aThe character to be converted
Returns
The value of the character as a hex digit

Definition at line 125 of file AP_GPS_NMEA.cpp.

Referenced by _term_complete().

Here is the caller graph for this function:

◆ _have_new_message()

bool AP_GPS_NMEA::_have_new_message ( void  )
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().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ _parse_decimal_100()

int32_t AP_GPS_NMEA::_parse_decimal_100 ( const char *  p)
staticprivate

Parses the as a NMEA-style decimal number with up to 3 decimal digits.

Returns
The value expressed by the string in , 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().

Here is the caller graph for this function:

◆ _parse_degrees()

uint32_t AP_GPS_NMEA::_parse_degrees ( )
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.

Returns
The value expressed by the string in _term, multiplied by 1e7.

Definition at line 166 of file AP_GPS_NMEA.cpp.

Referenced by _term_complete().

Here is the caller graph for this function:

◆ _term_complete()

bool AP_GPS_NMEA::_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.

Returns
True if completing the term has resulted in an update to the GPS state.

Definition at line 237 of file AP_GPS_NMEA.cpp.

Referenced by _decode().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ name()

const char* AP_GPS_NMEA::name ( ) const
inlineoverridevirtual

Implements AP_GPS_Backend.

Definition at line 65 of file AP_GPS_NMEA.h.

◆ read()

bool AP_GPS_NMEA::read ( void  )
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.

Here is the call graph for this function:

Friends And Related Function Documentation

◆ AP_GPS_NMEA_Test

friend class AP_GPS_NMEA_Test
friend

Definition at line 53 of file AP_GPS_NMEA.h.

Member Data Documentation

◆ _gps_data_good

bool AP_GPS_NMEA::_gps_data_good
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().

◆ _initialisation_blob

const char AP_GPS_NMEA::_initialisation_blob[]
staticprivate

Definition at line 158 of file AP_GPS_NMEA.h.

◆ _is_checksum_term

bool AP_GPS_NMEA::_is_checksum_term
private

current term is the checksum

Definition at line 123 of file AP_GPS_NMEA.h.

Referenced by _decode(), and _term_complete().

◆ _last_GGA_ms

uint32_t AP_GPS_NMEA::_last_GGA_ms = 0
private

Definition at line 145 of file AP_GPS_NMEA.h.

Referenced by _have_new_message(), and _term_complete().

◆ _last_RMC_ms

uint32_t AP_GPS_NMEA::_last_RMC_ms = 0
private

Definition at line 144 of file AP_GPS_NMEA.h.

Referenced by _have_new_message(), and _term_complete().

◆ _last_VTG_ms

uint32_t AP_GPS_NMEA::_last_VTG_ms = 0
private

Definition at line 146 of file AP_GPS_NMEA.h.

Referenced by _have_new_message(), and _term_complete().

◆ _MTK_init_string

const char AP_GPS_NMEA::_MTK_init_string[]
staticprivate

init string for MediaTek units

Definition at line 154 of file AP_GPS_NMEA.h.

◆ _new_altitude

int32_t AP_GPS_NMEA::_new_altitude
private

altitude parsed from a term

Definition at line 137 of file AP_GPS_NMEA.h.

Referenced by _term_complete().

◆ _new_course

int32_t AP_GPS_NMEA::_new_course
private

course parsed from a term

Definition at line 139 of file AP_GPS_NMEA.h.

Referenced by _term_complete().

◆ _new_date

int32_t AP_GPS_NMEA::_new_date
private

date parsed from a term

Definition at line 134 of file AP_GPS_NMEA.h.

Referenced by _term_complete().

◆ _new_hdop

uint16_t AP_GPS_NMEA::_new_hdop
private

HDOP parsed from a term.

Definition at line 140 of file AP_GPS_NMEA.h.

Referenced by _term_complete().

◆ _new_latitude

int32_t AP_GPS_NMEA::_new_latitude
private

latitude parsed from a term

Definition at line 135 of file AP_GPS_NMEA.h.

Referenced by _term_complete().

◆ _new_longitude

int32_t AP_GPS_NMEA::_new_longitude
private

longitude parsed from a term

Definition at line 136 of file AP_GPS_NMEA.h.

Referenced by _term_complete().

◆ _new_quality_indicator

uint8_t AP_GPS_NMEA::_new_quality_indicator
private

GPS quality indicator parsed from a term.

Definition at line 142 of file AP_GPS_NMEA.h.

Referenced by _term_complete().

◆ _new_satellite_count

uint8_t AP_GPS_NMEA::_new_satellite_count
private

satellite count parsed from a term

Definition at line 141 of file AP_GPS_NMEA.h.

Referenced by _term_complete().

◆ _new_speed

int32_t AP_GPS_NMEA::_new_speed
private

speed parsed from a term

Definition at line 138 of file AP_GPS_NMEA.h.

Referenced by _term_complete().

◆ _new_time

int32_t AP_GPS_NMEA::_new_time
private

time parsed from a term

Definition at line 133 of file AP_GPS_NMEA.h.

Referenced by _term_complete().

◆ _parity

uint8_t AP_GPS_NMEA::_parity
private

NMEA message checksum accumulator.

Definition at line 122 of file AP_GPS_NMEA.h.

Referenced by _decode(), and _term_complete().

◆ _sentence_type

uint8_t AP_GPS_NMEA::_sentence_type
private

the sentence type currently being processed

Definition at line 125 of file AP_GPS_NMEA.h.

Referenced by _decode(), and _term_complete().

◆ _SiRF_init_string

const char AP_GPS_NMEA::_SiRF_init_string[]
staticprivate

init string for SiRF units

Definition at line 153 of file AP_GPS_NMEA.h.

◆ _term

char AP_GPS_NMEA::_term[15]
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().

◆ _term_number

uint8_t AP_GPS_NMEA::_term_number
private

term index within the current sentence

Definition at line 126 of file AP_GPS_NMEA.h.

Referenced by _decode(), and _term_complete().

◆ _term_offset

uint8_t AP_GPS_NMEA::_term_offset
private

character offset with the term being received

Definition at line 127 of file AP_GPS_NMEA.h.

Referenced by _decode().

◆ _ublox_init_string

const char AP_GPS_NMEA::_ublox_init_string[]
staticprivate

init string for ublox units

Definition at line 155 of file AP_GPS_NMEA.h.


The documentation for this class was generated from the following files: