APM:Libraries
AP_GPS_NMEA.h
Go to the documentation of this file.
1 /*
2  This program is free software: you can redistribute it and/or modify
3  it under the terms of the GNU General Public License as published by
4  the Free Software Foundation, either version 3 of the License, or
5  (at your option) any later version.
6 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 
16 //
17 // NMEA parser, adapted by Michael Smith from TinyGPS v9:
18 //
19 // TinyGPS - a small GPS library for Arduino providing basic NMEA parsing
20 // Copyright (C) 2008-9 Mikal Hart
21 // All rights reserved.
22 //
23 //
24 
44 #pragma once
45 
46 #include "AP_GPS.h"
47 #include "GPS_Backend.h"
48 
52 {
53  friend class AP_GPS_NMEA_Test;
54 
55 public:
57 
61  bool read();
62 
63  static bool _detect(struct NMEA_detect_state &state, uint8_t data);
64 
65  const char *name() const override { return "NMEA"; }
66 
67 private:
69  enum _sentence_types { //there are some more than 10 fields in some sentences , thus we have to increase these value.
74  };
75 
82  bool _decode(char c);
83 
89  int16_t _from_hex(char a);
90 
97  static int32_t _parse_decimal_100(const char *p);
98 
107  uint32_t _parse_degrees();
108 
117  bool _term_complete();
118 
120  bool _have_new_message(void);
121 
122  uint8_t _parity;
124  char _term[15];
125  uint8_t _sentence_type;
126  uint8_t _term_number;
127  uint8_t _term_offset;
129 
130  // The result of parsing terms within a message is stored temporarily until
131  // the message is completely processed and the checksum validated.
132  // This avoids the need to buffer the entire message.
133  int32_t _new_time;
134  int32_t _new_date;
135  int32_t _new_latitude;
136  int32_t _new_longitude;
137  int32_t _new_altitude;
138  int32_t _new_speed;
139  int32_t _new_course;
140  uint16_t _new_hdop;
143 
144  uint32_t _last_RMC_ms = 0;
145  uint32_t _last_GGA_ms = 0;
146  uint32_t _last_VTG_ms = 0;
147 
152 
153  static const char _SiRF_init_string[];
154  static const char _MTK_init_string[];
155  static const char _ublox_init_string[];
156 
157 
158  static const char _initialisation_blob[];
159 };
Definition: AP_GPS.h:48
_sentence_types
Coding for the GPS sentences that the parser handles.
Definition: AP_GPS_NMEA.h:69
int32_t _new_time
time parsed from a term
Definition: AP_GPS_NMEA.h:133
uint8_t _new_quality_indicator
GPS quality indicator parsed from a term.
Definition: AP_GPS_NMEA.h:142
static const char _SiRF_init_string[]
init string for SiRF units
Definition: AP_GPS_NMEA.h:153
uint32_t _last_VTG_ms
Definition: AP_GPS_NMEA.h:146
bool _gps_data_good
set when the sentence indicates data is good
Definition: AP_GPS_NMEA.h:128
static const char _MTK_init_string[]
init string for MediaTek units
Definition: AP_GPS_NMEA.h:154
uint16_t _new_hdop
HDOP parsed from a term.
Definition: AP_GPS_NMEA.h:140
bool _term_complete()
static bool _detect(struct NMEA_detect_state &state, uint8_t data)
char _term[15]
buffer for the current term within the current sentence
Definition: AP_GPS_NMEA.h:124
uint8_t _new_satellite_count
satellite count parsed from a term
Definition: AP_GPS_NMEA.h:141
bool _have_new_message(void)
return true if we have a new set of NMEA messages
uint8_t _parity
NMEA message checksum accumulator.
Definition: AP_GPS_NMEA.h:122
static const char _ublox_init_string[]
init string for ublox units
Definition: AP_GPS_NMEA.h:155
uint32_t _parse_degrees()
AP_GPS::GPS_State & state
public state for this instance
Definition: GPS_Backend.h:71
int32_t _new_latitude
latitude parsed from a term
Definition: AP_GPS_NMEA.h:135
int32_t _new_speed
speed parsed from a term
Definition: AP_GPS_NMEA.h:138
uint8_t _term_number
term index within the current sentence
Definition: AP_GPS_NMEA.h:126
uint32_t _last_GGA_ms
Definition: AP_GPS_NMEA.h:145
int32_t _new_longitude
longitude parsed from a term
Definition: AP_GPS_NMEA.h:136
const char * name() const override
Definition: AP_GPS_NMEA.h:65
int16_t _from_hex(char a)
uint8_t _term_offset
character offset with the term being received
Definition: AP_GPS_NMEA.h:127
int32_t _new_date
date parsed from a term
Definition: AP_GPS_NMEA.h:134
static int32_t _parse_decimal_100(const char *p)
bool _decode(char c)
Definition: AP_GPS_NMEA.cpp:84
uint32_t _last_RMC_ms
Definition: AP_GPS_NMEA.h:144
uint8_t _sentence_type
the sentence type currently being processed
Definition: AP_GPS_NMEA.h:125
AP_GPS_NMEA(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port)
Definition: AP_GPS_NMEA.cpp:53
int32_t _new_altitude
altitude parsed from a term
Definition: AP_GPS_NMEA.h:137
bool _is_checksum_term
current term is the checksum
Definition: AP_GPS_NMEA.h:123
static const char _initialisation_blob[]
Definition: AP_GPS_NMEA.h:158
int32_t _new_course
course parsed from a term
Definition: AP_GPS_NMEA.h:139