mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
uncrustify libraries/AP_GPS/AP_GPS_NMEA.h
This commit is contained in:
parent
39f71f750d
commit
87299da0dd
@ -58,17 +58,17 @@ public:
|
|||||||
/// Perform a (re)initialisation of the GPS; sends the
|
/// Perform a (re)initialisation of the GPS; sends the
|
||||||
/// protocol configuration messages.
|
/// protocol configuration messages.
|
||||||
///
|
///
|
||||||
virtual void init(enum GPS_Engine_Setting nav_setting = GPS_ENGINE_NONE);
|
virtual void init(enum GPS_Engine_Setting nav_setting = GPS_ENGINE_NONE);
|
||||||
|
|
||||||
/// Checks the serial receive buffer for characters,
|
/// Checks the serial receive buffer for characters,
|
||||||
/// attempts to parse NMEA data and updates internal state
|
/// attempts to parse NMEA data and updates internal state
|
||||||
/// accordingly.
|
/// accordingly.
|
||||||
///
|
///
|
||||||
virtual bool read();
|
virtual bool read();
|
||||||
|
|
||||||
private:
|
private:
|
||||||
/// Coding for the GPS sentences that the parser handles
|
/// Coding for the GPS sentences that the parser handles
|
||||||
enum _sentence_types { //there are some more than 10 fields in some sentences , thus we have to increase these value.
|
enum _sentence_types { //there are some more than 10 fields in some sentences , thus we have to increase these value.
|
||||||
_GPS_SENTENCE_GPRMC = 32,
|
_GPS_SENTENCE_GPRMC = 32,
|
||||||
_GPS_SENTENCE_GPGGA = 64,
|
_GPS_SENTENCE_GPGGA = 64,
|
||||||
_GPS_SENTENCE_GPVTG = 96,
|
_GPS_SENTENCE_GPVTG = 96,
|
||||||
@ -81,14 +81,14 @@ private:
|
|||||||
/// @returns True if processing the character has resulted in
|
/// @returns True if processing the character has resulted in
|
||||||
/// an update to the GPS state
|
/// an update to the GPS state
|
||||||
///
|
///
|
||||||
bool _decode(char c);
|
bool _decode(char c);
|
||||||
|
|
||||||
/// Return the numeric value of an ascii hex character
|
/// Return the numeric value of an ascii hex character
|
||||||
///
|
///
|
||||||
/// @param a The character to be converted
|
/// @param a The character to be converted
|
||||||
/// @returns The value of the character as a hex digit
|
/// @returns The value of the character as a hex digit
|
||||||
///
|
///
|
||||||
int16_t _from_hex(char a);
|
int16_t _from_hex(char a);
|
||||||
|
|
||||||
/// Parses the current term as a NMEA-style decimal number with
|
/// Parses the current term as a NMEA-style decimal number with
|
||||||
/// up to two decimal digits.
|
/// up to two decimal digits.
|
||||||
@ -96,7 +96,7 @@ private:
|
|||||||
/// @returns The value expressed by the string in _term,
|
/// @returns The value expressed by the string in _term,
|
||||||
/// multiplied by 100.
|
/// multiplied by 100.
|
||||||
///
|
///
|
||||||
uint32_t _parse_decimal();
|
uint32_t _parse_decimal();
|
||||||
|
|
||||||
/// Parses the current term as a NMEA-style degrees + minutes
|
/// Parses the current term as a NMEA-style degrees + minutes
|
||||||
/// value with up to four decimal digits.
|
/// value with up to four decimal digits.
|
||||||
@ -106,7 +106,7 @@ private:
|
|||||||
/// @returns The value expressed by the string in _term,
|
/// @returns The value expressed by the string in _term,
|
||||||
/// multiplied by 10000.
|
/// multiplied by 10000.
|
||||||
///
|
///
|
||||||
uint32_t _parse_degrees();
|
uint32_t _parse_degrees();
|
||||||
|
|
||||||
/// Processes the current term when it has been deemed to be
|
/// Processes the current term when it has been deemed to be
|
||||||
/// complete.
|
/// complete.
|
||||||
@ -116,44 +116,44 @@ private:
|
|||||||
///
|
///
|
||||||
/// @returns True if completing the term has resulted in
|
/// @returns True if completing the term has resulted in
|
||||||
/// an update to the GPS state.
|
/// an update to the GPS state.
|
||||||
bool _term_complete();
|
bool _term_complete();
|
||||||
|
|
||||||
uint8_t _parity; ///< NMEA message checksum accumulator
|
uint8_t _parity; ///< NMEA message checksum accumulator
|
||||||
bool _is_checksum_term; ///< current term is the checksum
|
bool _is_checksum_term; ///< current term is the checksum
|
||||||
char _term[15]; ///< buffer for the current term within the current sentence
|
char _term[15]; ///< buffer for the current term within the current sentence
|
||||||
uint8_t _sentence_type; ///< the sentence type currently being processed
|
uint8_t _sentence_type; ///< the sentence type currently being processed
|
||||||
uint8_t _term_number; ///< term index within the current sentence
|
uint8_t _term_number; ///< term index within the current sentence
|
||||||
uint8_t _term_offset; ///< character offset with the term being received
|
uint8_t _term_offset; ///< character offset with the term being received
|
||||||
bool _gps_data_good; ///< set when the sentence indicates data is good
|
bool _gps_data_good; ///< set when the sentence indicates data is good
|
||||||
|
|
||||||
// The result of parsing terms within a message is stored temporarily until
|
// The result of parsing terms within a message is stored temporarily until
|
||||||
// the message is completely processed and the checksum validated.
|
// the message is completely processed and the checksum validated.
|
||||||
// This avoids the need to buffer the entire message.
|
// This avoids the need to buffer the entire message.
|
||||||
int32_t _new_time; ///< time parsed from a term
|
int32_t _new_time; ///< time parsed from a term
|
||||||
int32_t _new_date; ///< date parsed from a term
|
int32_t _new_date; ///< date parsed from a term
|
||||||
int32_t _new_latitude; ///< latitude parsed from a term
|
int32_t _new_latitude; ///< latitude parsed from a term
|
||||||
int32_t _new_longitude; ///< longitude parsed from a term
|
int32_t _new_longitude; ///< longitude parsed from a term
|
||||||
int32_t _new_altitude; ///< altitude parsed from a term
|
int32_t _new_altitude; ///< altitude parsed from a term
|
||||||
int32_t _new_speed; ///< speed parsed from a term
|
int32_t _new_speed; ///< speed parsed from a term
|
||||||
int32_t _new_course; ///< course parsed from a term
|
int32_t _new_course; ///< course parsed from a term
|
||||||
int16_t _new_hdop; ///< HDOP parsed from a term
|
int16_t _new_hdop; ///< HDOP parsed from a term
|
||||||
uint8_t _new_satellite_count; ///< satellite count parsed from a term
|
uint8_t _new_satellite_count; ///< satellite count parsed from a term
|
||||||
|
|
||||||
/// @name Init strings
|
/// @name Init strings
|
||||||
/// In ::init, an attempt is made to configure the GPS
|
/// In ::init, an attempt is made to configure the GPS
|
||||||
/// unit to send just the messages that we are interested
|
/// unit to send just the messages that we are interested
|
||||||
/// in using these strings
|
/// in using these strings
|
||||||
//@{
|
//@{
|
||||||
static const prog_char _SiRF_init_string[]; ///< init string for SiRF units
|
static const prog_char _SiRF_init_string[]; ///< init string for SiRF units
|
||||||
static const prog_char _MTK_init_string[]; ///< init string for MediaTek units
|
static const prog_char _MTK_init_string[]; ///< init string for MediaTek units
|
||||||
static const prog_char _ublox_init_string[]; ///< init string for ublox units
|
static const prog_char _ublox_init_string[]; ///< init string for ublox units
|
||||||
//@}
|
//@}
|
||||||
|
|
||||||
/// @name GPS message identifier strings
|
/// @name GPS message identifier strings
|
||||||
//@{
|
//@{
|
||||||
static const prog_char _gprmc_string[];
|
static const prog_char _gprmc_string[];
|
||||||
static const prog_char _gpgga_string[];
|
static const prog_char _gpgga_string[];
|
||||||
static const prog_char _gpvtg_string[];
|
static const prog_char _gpvtg_string[];
|
||||||
//@}
|
//@}
|
||||||
};
|
};
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user