Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/libraries/AP_GPS/AP_GPS_NMEA.h
Views: 1798
/*1This program is free software: you can redistribute it and/or modify2it under the terms of the GNU General Public License as published by3the Free Software Foundation, either version 3 of the License, or4(at your option) any later version.56This program is distributed in the hope that it will be useful,7but WITHOUT ANY WARRANTY; without even the implied warranty of8MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the9GNU General Public License for more details.1011You should have received a copy of the GNU General Public License12along with this program. If not, see <http://www.gnu.org/licenses/>.13*/1415//16// NMEA parser, adapted by Michael Smith from TinyGPS v9:17//18// TinyGPS - a small GPS library for Arduino providing basic NMEA parsing19// Copyright (C) 2008-9 Mikal Hart20// All rights reserved.21//22//2324/// @file AP_GPS_NMEA.h25/// @brief NMEA protocol parser26///27/// This is a lightweight NMEA parser, derived originally from the28/// TinyGPS parser by Mikal Hart. It is frugal in its use of memory29/// and tries to avoid unnecessary arithmetic.30///31/// The parser handles GPGGA, GPRMC and GPVTG messages, and attempts to be32/// robust in the face of occasional corruption in the input stream. It33/// makes a basic effort to configure GPS' that are likely to be connected in34/// NMEA mode (SiRF, MediaTek and ublox) to emit the correct message35/// stream, but does not validate that the correct stream is being received.36/// In particular, a unit emitting just GPRMC will show as having a fix37/// even though no altitude data is being received.38///39/// GPVTG data is parsed, but as the message may not contain the the40/// qualifier field (this is common with e.g. older SiRF units) it is41/// not considered a source of fix-valid information.42///43#pragma once4445#include "AP_GPS.h"46#include "GPS_Backend.h"4748#if AP_GPS_NMEA_ENABLED49/// NMEA parser50///51class AP_GPS_NMEA : public AP_GPS_Backend52{53friend class AP_GPS_NMEA_Test;5455public:5657using AP_GPS_Backend::AP_GPS_Backend;5859/// Checks the serial receive buffer for characters,60/// attempts to parse NMEA data and updates internal state61/// accordingly.62bool read() override;6364static bool _detect(struct NMEA_detect_state &state, uint8_t data);6566const char *name() const override { return "NMEA"; }6768// driver specific health, returns true if the driver is healthy69bool is_healthy(void) const override;7071// get lag in seconds72bool get_lag(float &lag_sec) const override;7374#if HAL_LOGGING_ENABLED75void Write_AP_Logger_Log_Startup_messages() const override;76#endif7778private:79/// Coding for the GPS sentences that the parser handles80enum _sentence_types : uint16_t { //there are some more than 10 fields in some sentences , thus we have to increase these value.81_GPS_SENTENCE_RMC = 32,82_GPS_SENTENCE_GGA = 64,83_GPS_SENTENCE_VTG = 96,84_GPS_SENTENCE_HDT = 128,85_GPS_SENTENCE_PHD = 138, // extension for AllyStar GPS modules86_GPS_SENTENCE_THS = 160, // True heading with quality indicator, available on Trimble MB-Two87_GPS_SENTENCE_KSXT = 170, // extension for Unicore, 21 fields88_GPS_SENTENCE_AGRICA = 193, // extension for Unicore, 65 fields89_GPS_SENTENCE_VERSIONA = 270, // extension for Unicore, version, 10 fields90_GPS_SENTENCE_UNIHEADINGA = 290, // extension for Unicore, uniheadinga, 20 fields91_GPS_SENTENCE_OTHER = 092};9394/// Update the decode state machine with a new character95///96/// @param c The next character in the NMEA input stream97/// @returns True if processing the character has resulted in98/// an update to the GPS state99///100bool _decode(char c);101102/// Parses the @p as a NMEA-style decimal number with103/// up to 3 decimal digits.104///105/// @returns The value expressed by the string in @p,106/// multiplied by 100.107///108static int32_t _parse_decimal_100(const char *p);109110/// Parses the current term as a NMEA-style degrees + minutes111/// value with up to four decimal digits.112///113/// This gives a theoretical resolution limit of around 1cm.114///115/// @returns The value expressed by the string in _term,116/// multiplied by 1e7.117///118uint32_t _parse_degrees();119120/// Processes the current term when it has been deemed to be121/// complete.122///123/// Each GPS message is broken up into terms separated by commas.124/// Each term is then processed by this function as it is received.125///126/// @returns True if completing the term has resulted in127/// an update to the GPS state.128bool _term_complete();129130/// return true if we have a new set of NMEA messages131bool _have_new_message(void);132133#if AP_GPS_NMEA_UNICORE_ENABLED134/*135parse an AGRICA field136*/137void parse_agrica_field(uint16_t term_number, const char *term);138139// parse VERSIONA field140void parse_versiona_field(uint16_t term_number, const char *term);141142#if GPS_MOVING_BASELINE143// parse UNIHEADINGA field144void parse_uniheadinga_field(uint16_t term_number, const char *term);145#endif146#endif147148149uint8_t _parity; ///< NMEA message checksum accumulator150uint32_t _crc32; ///< CRC for unicore messages151bool _is_checksum_term; ///< current term is the checksum152char _term[30]; ///< buffer for the current term within the current sentence153uint16_t _sentence_type; ///< the sentence type currently being processed154bool _is_unicore; ///< true if in a unicore '#' sentence155uint16_t _term_number; ///< term index within the current sentence156uint8_t _term_offset; ///< character offset with the term being received157uint16_t _sentence_length;158bool _sentence_done; ///< set when a sentence has been fully decoded159160// The result of parsing terms within a message is stored temporarily until161// the message is completely processed and the checksum validated.162// This avoids the need to buffer the entire message.163int32_t _new_time; ///< time parsed from a term164int32_t _new_date; ///< date parsed from a term165int32_t _new_latitude; ///< latitude parsed from a term166int32_t _new_longitude; ///< longitude parsed from a term167int32_t _new_altitude; ///< altitude parsed from a term168int32_t _new_speed; ///< speed parsed from a term169int32_t _new_course; ///< course parsed from a term170float _new_gps_yaw; ///< yaw parsed from a term171uint16_t _new_hdop; ///< HDOP parsed from a term172uint8_t _new_satellite_count; ///< satellite count parsed from a term173uint8_t _new_quality_indicator; ///< GPS quality indicator parsed from a term174175uint32_t _last_RMC_ms;176uint32_t _last_GGA_ms;177uint32_t _last_VTG_ms;178uint32_t _last_yaw_ms;179uint32_t _last_vvelocity_ms;180uint32_t _last_vaccuracy_ms;181uint32_t _last_3D_velocity_ms;182uint32_t _last_KSXT_pos_ms;183uint32_t _last_AGRICA_ms;184uint32_t _last_fix_ms;185186/// @name Init strings187/// In ::init, an attempt is made to configure the GPS188/// unit to send just the messages that we are interested189/// in using these strings190//@{191static const char _SiRF_init_string[]; ///< init string for SiRF units192static const char _ublox_init_string[]; ///< init string for ublox units193//@}194195static const char _initialisation_blob[];196197/*198the $PHD message is an extension from AllyStar that gives199vertical velocity and more accuracy estimates. It is designed as200a mapping from ublox UBX protocol messages to NMEA. So class 1,201message 12 is a mapping to NMEA of the NAV-VELNED UBX message202and contains the same fields. Class 1 message 26 is called203"NAV-PVERR", but does not correspond to a UBX message204205example:206$PHD,01,12,TIIITTITT,,245808000,0,0,0,0,0,10260304,0,0*27207$PHD,01,26,TTTTTTT,,245808000,877,864,1451,11,11,17*17208*/209struct {210uint8_t msg_class;211uint8_t msg_id;212uint32_t itow;213int32_t fields[8];214} _phd;215216/*217The KSXT message is an extension from Unicore that gives 3D velocity and yaw218example: $KSXT,20211016083433.00,116.31296102,39.95817066,49.4911,223.57,-11.32,330.19,0.024,,1,3,28,27,,,,-0.012,0.021,0.020,,*2D219*/220struct {221double fields[21];222} _ksxt;223224#if AP_GPS_NMEA_UNICORE_ENABLED225/*226unicore AGRICA message parsing227*/228struct {229uint32_t start_byte;230uint8_t rtk_status;231uint8_t heading_status;232Vector3f vel_NED;233Vector3f vel_stddev;234double lat, lng;235float alt;236uint32_t itow;237float undulation;238Vector3f pos_stddev;239} _agrica;240241// unicore VERSIONA parsing242struct {243char type[10];244char version[20];245char build_date[13];246} _versiona;247bool _have_unicore_versiona;248249#if GPS_MOVING_BASELINE250// unicore UNIHEADINGA parsing251struct {252float baseline_length;253float heading;254float pitch;255float heading_sd;256} _uniheadinga;257#endif258#endif // AP_GPS_NMEA_UNICORE_ENABLED259bool _expect_agrica;260261// last time we sent type specific config strings262uint32_t last_config_ms;263264// send type specific config strings265void send_config(void);266};267268#if AP_GPS_NMEA_UNICORE_ENABLED && !defined(NMEA_UNICORE_SETUP)269// we don't know what port the GPS may be using, so configure all 3. We need to get it sending270// one message to allow the NMEA detector to run271#define NMEA_UNICORE_SETUP "CONFIG COM1 230400 8 n 1\r\nCONFIG COM2 230400 8 n 1\r\nCONFIG COM3 230400 8 n 1\r\nGPGGA 0.2\r\n"272#endif273274#endif // AP_GPS_NMEA_ENABLED275276277278