APM:Libraries
AP_GPS_NMEA.cpp
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 
30 
31 #include <AP_Common/AP_Common.h>
32 
33 #include <ctype.h>
34 #include <stdint.h>
35 #include <stdlib.h>
36 
37 #include "AP_GPS_NMEA.h"
38 
39 extern const AP_HAL::HAL& hal;
40 
41 // optionally log all NMEA data for debug purposes
42 // #define NMEA_LOG_PATH "nmea.log"
43 
44 #ifdef NMEA_LOG_PATH
45 #include <stdio.h>
46 #endif
47 
48 // Convenience macros //////////////////////////////////////////////////////////
49 //
50 #define DIGIT_TO_VAL(_x) (_x - '0')
51 #define hexdigit(x) ((x)>9?'A'+((x)-10):'0'+(x))
52 
54  AP_GPS_Backend(_gps, _state, _port)
55 {
56  // this guarantees that _term is always nul terminated
57  memset(_term, 0, sizeof(_term));
58 }
59 
61 {
62  int16_t numc;
63  bool parsed = false;
64 
65  numc = port->available();
66  while (numc--) {
67  char c = port->read();
68 #ifdef NMEA_LOG_PATH
69  static FILE *logf = nullptr;
70  if (logf == nullptr) {
71  logf = fopen(NMEA_LOG_PATH, "wb");
72  }
73  if (logf != nullptr) {
74  ::fwrite(&c, 1, 1, logf);
75  }
76 #endif
77  if (_decode(c)) {
78  parsed = true;
79  }
80  }
81  return parsed;
82 }
83 
85 {
86  bool valid_sentence = false;
87 
88  switch (c) {
89  case ',': // term terminators
90  _parity ^= c;
92  case '\r':
93  case '\n':
94  case '*':
95  if (_term_offset < sizeof(_term)) {
96  _term[_term_offset] = 0;
97  valid_sentence = _term_complete();
98  }
99  ++_term_number;
100  _term_offset = 0;
101  _is_checksum_term = c == '*';
102  return valid_sentence;
103 
104  case '$': // sentence begin
106  _parity = 0;
108  _is_checksum_term = false;
109  _gps_data_good = false;
110  return valid_sentence;
111  }
112 
113  // ordinary characters
114  if (_term_offset < sizeof(_term) - 1)
115  _term[_term_offset++] = c;
116  if (!_is_checksum_term)
117  _parity ^= c;
118 
119  return valid_sentence;
120 }
121 
122 //
123 // internal utilities
124 //
125 int16_t AP_GPS_NMEA::_from_hex(char a)
126 {
127  if (a >= 'A' && a <= 'F')
128  return a - 'A' + 10;
129  else if (a >= 'a' && a <= 'f')
130  return a - 'a' + 10;
131  else
132  return a - '0';
133 }
134 
135 int32_t AP_GPS_NMEA::_parse_decimal_100(const char *p)
136 {
137  char *endptr = nullptr;
138  long ret = 100 * strtol(p, &endptr, 10);
139  int sign = ret < 0 ? -1 : 1;
140 
141  if (ret >= (long)INT32_MAX) {
142  return INT32_MAX;
143  }
144  if (ret <= (long)INT32_MIN) {
145  return INT32_MIN;
146  }
147  if (endptr == nullptr || *endptr != '.') {
148  return ret;
149  }
150 
151  if (isdigit(endptr[1])) {
152  ret += sign * 10 * DIGIT_TO_VAL(endptr[1]);
153  if (isdigit(endptr[2])) {
154  ret += sign * DIGIT_TO_VAL(endptr[2]);
155  if (isdigit(endptr[3])) {
156  ret += sign * (DIGIT_TO_VAL(endptr[3]) >= 5);
157  }
158  }
159  }
160  return ret;
161 }
162 
163 /*
164  parse a NMEA latitude/longitude degree value. The result is in degrees*1e7
165  */
167 {
168  char *p, *q;
169  uint8_t deg = 0, min = 0;
170  float frac_min = 0;
171  int32_t ret = 0;
172 
173  // scan for decimal point or end of field
174  for (p = _term; *p && isdigit(*p); p++)
175  ;
176  q = _term;
177 
178  // convert degrees
179  while ((p - q) > 2 && *q) {
180  if (deg)
181  deg *= 10;
182  deg += DIGIT_TO_VAL(*q++);
183  }
184 
185  // convert minutes
186  while (p > q && *q) {
187  if (min)
188  min *= 10;
189  min += DIGIT_TO_VAL(*q++);
190  }
191 
192  // convert fractional minutes
193  if (*p == '.') {
194  q = p + 1;
195  float frac_scale = 0.1f;
196  while (*q && isdigit(*q)) {
197  frac_min += DIGIT_TO_VAL(*q) * frac_scale;
198  q++;
199  frac_scale *= 0.1f;
200  }
201  }
202  ret = (deg * (int32_t)10000000UL);
203  ret += (min * (int32_t)10000000UL / 60);
204  ret += (int32_t) (frac_min * (1.0e7f / 60.0f));
205  return ret;
206 }
207 
208 /*
209  see if we have a new set of NMEA messages
210  */
212 {
213  if (_last_RMC_ms == 0 ||
214  _last_GGA_ms == 0) {
215  return false;
216  }
217  uint32_t now = AP_HAL::millis();
218  if (now - _last_RMC_ms > 150 ||
219  now - _last_GGA_ms > 150) {
220  return false;
221  }
222  if (_last_VTG_ms != 0 &&
223  now - _last_VTG_ms > 150) {
224  return false;
225  }
226  // prevent these messages being used again
227  if (_last_VTG_ms != 0) {
228  _last_VTG_ms = 1;
229  }
230  _last_GGA_ms = 1;
231  _last_RMC_ms = 1;
232  return true;
233 }
234 
235 // Processes a just-completed term
236 // Returns true if new sentence has just passed checksum test and is validated
238 {
239  // handle the last term in a message
240  if (_is_checksum_term) {
241  uint8_t checksum = 16 * _from_hex(_term[0]) + _from_hex(_term[1]);
242  if (checksum == _parity) {
243  if (_gps_data_good) {
244  uint32_t now = AP_HAL::millis();
245  switch (_sentence_type) {
246  case _GPS_SENTENCE_RMC:
247  _last_RMC_ms = now;
248  //time = _new_time;
249  //date = _new_date;
252  state.ground_speed = _new_speed*0.01f;
255  state.last_gps_time_ms = now;
257  break;
258  case _GPS_SENTENCE_GGA:
259  _last_GGA_ms = now;
264  state.hdop = _new_hdop;
265  switch(_new_quality_indicator) {
266  case 0: // Fix not available or invalid
268  break;
269  case 1: // GPS SPS Mode, fix valid
271  break;
272  case 2: // Differential GPS, SPS Mode, fix valid
274  break;
275  case 3: // GPS PPS Mode, fix valid
277  break;
278  case 4: // Real Time Kinematic. System used in RTK mode with fixed integers
280  break;
281  case 5: // Float RTK. Satellite system used in RTK mode, floating integers
283  break;
284  case 6: // Estimated (dead reckoning) Mode
286  break;
287  default://to maintain compatibility with MAV_GPS_INPUT and others
289  break;
290  }
291  break;
292  case _GPS_SENTENCE_VTG:
293  _last_VTG_ms = now;
294  state.ground_speed = _new_speed*0.01f;
297  // VTG has no fix indicator, can't change fix status
298  break;
299  }
300  } else {
301  switch (_sentence_type) {
302  case _GPS_SENTENCE_RMC:
303  case _GPS_SENTENCE_GGA:
304  // Only these sentences give us information about
305  // fix status.
307  }
308  }
309  // see if we got a good message
310  return _have_new_message();
311  }
312  // we got a bad message, ignore it
313  return false;
314  }
315 
316  // the first term determines the sentence type
317  if (_term_number == 0) {
318  /*
319  The first two letters of the NMEA term are the talker
320  ID. The most common is 'GP' but there are a bunch of others
321  that are valid. We accept any two characters here.
322  */
323  if (_term[0] < 'A' || _term[0] > 'Z' ||
324  _term[1] < 'A' || _term[1] > 'Z') {
326  return false;
327  }
328  const char *term_type = &_term[2];
329  if (strcmp(term_type, "RMC") == 0) {
331  } else if (strcmp(term_type, "GGA") == 0) {
333  } else if (strcmp(term_type, "VTG") == 0) {
335  // VTG may not contain a data qualifier, presume the solution is good
336  // unless it tells us otherwise.
337  _gps_data_good = true;
338  } else {
340  }
341  return false;
342  }
343 
344  // 32 = RMC, 64 = GGA, 96 = VTG
346  switch (_sentence_type + _term_number) {
347  // operational status
348  //
349  case _GPS_SENTENCE_RMC + 2: // validity (RMC)
350  _gps_data_good = _term[0] == 'A';
351  break;
352  case _GPS_SENTENCE_GGA + 6: // Fix data (GGA)
353  _gps_data_good = _term[0] > '0';
354  _new_quality_indicator = _term[0] - '0';
355  break;
356  case _GPS_SENTENCE_VTG + 9: // validity (VTG) (we may not see this field)
357  _gps_data_good = _term[0] != 'N';
358  break;
359  case _GPS_SENTENCE_GGA + 7: // satellite count (GGA)
360  _new_satellite_count = atol(_term);
361  break;
362  case _GPS_SENTENCE_GGA + 8: // HDOP (GGA)
363  _new_hdop = (uint16_t)_parse_decimal_100(_term);
364  break;
365 
366  // time and date
367  //
368  case _GPS_SENTENCE_RMC + 1: // Time (RMC)
369  case _GPS_SENTENCE_GGA + 1: // Time (GGA)
371  break;
372  case _GPS_SENTENCE_RMC + 9: // Date (GPRMC)
373  _new_date = atol(_term);
374  break;
375 
376  // location
377  //
378  case _GPS_SENTENCE_RMC + 3: // Latitude
379  case _GPS_SENTENCE_GGA + 2:
381  break;
382  case _GPS_SENTENCE_RMC + 4: // N/S
383  case _GPS_SENTENCE_GGA + 3:
384  if (_term[0] == 'S')
386  break;
387  case _GPS_SENTENCE_RMC + 5: // Longitude
388  case _GPS_SENTENCE_GGA + 4:
390  break;
391  case _GPS_SENTENCE_RMC + 6: // E/W
392  case _GPS_SENTENCE_GGA + 5:
393  if (_term[0] == 'W')
395  break;
396  case _GPS_SENTENCE_GGA + 9: // Altitude (GPGGA)
398  break;
399 
400  // course and speed
401  //
402  case _GPS_SENTENCE_RMC + 7: // Speed (GPRMC)
403  case _GPS_SENTENCE_VTG + 5: // Speed (VTG)
404  _new_speed = (_parse_decimal_100(_term) * 514) / 1000; // knots-> m/sec, approximiates * 0.514
405  break;
406  case _GPS_SENTENCE_RMC + 8: // Course (GPRMC)
407  case _GPS_SENTENCE_VTG + 1: // Course (VTG)
409  break;
410  }
411  }
412 
413  return false;
414 }
415 
416 /*
417  detect a NMEA GPS. Adds one byte, and returns true if the stream
418  matches a NMEA string
419  */
420 bool
422 {
423  switch (state.step) {
424  case 0:
425  state.ck = 0;
426  if ('$' == data) {
427  state.step++;
428  }
429  break;
430  case 1:
431  if ('*' == data) {
432  state.step++;
433  } else {
434  state.ck ^= data;
435  }
436  break;
437  case 2:
438  if (hexdigit(state.ck>>4) == data) {
439  state.step++;
440  } else {
441  state.step = 0;
442  }
443  break;
444  case 3:
445  if (hexdigit(state.ck&0xF) == data) {
446  state.step = 0;
447  return true;
448  }
449  state.step = 0;
450  break;
451  }
452  return false;
453 }
Definition: AP_GPS.h:48
int32_t _new_time
time parsed from a term
Definition: AP_GPS_NMEA.h:133
uint32_t last_gps_time_ms
the system time we got the last GPS timestamp, milliseconds
Definition: AP_GPS.h:149
#define DIGIT_TO_VAL(_x)
Definition: AP_GPS_NMEA.cpp:50
uint8_t _new_quality_indicator
GPS quality indicator parsed from a term.
Definition: AP_GPS_NMEA.h:142
#define FALLTHROUGH
Definition: AP_Common.h:50
uint32_t _last_VTG_ms
Definition: AP_GPS_NMEA.h:146
GPS_Status status
driver fix status
Definition: AP_GPS.h:132
bool _gps_data_good
set when the sentence indicates data is good
Definition: AP_GPS_NMEA.h:128
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)
int32_t lat
param 3 - Latitude * 10**7
Definition: AP_Common.h:143
Receiving valid messages and 3D RTK Fixed.
Definition: AP_GPS.h:103
char _term[15]
buffer for the current term within the current sentence
Definition: AP_GPS_NMEA.h:124
const AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14
uint8_t _new_satellite_count
satellite count parsed from a term
Definition: AP_GPS_NMEA.h:141
float wrap_360(const T angle, float unit_mod)
Definition: AP_Math.cpp:123
bool _have_new_message(void)
return true if we have a new set of NMEA messages
int32_t alt
param 2 - Altitude in centimeters (meters * 100) see LOCATION_ALT_MAX_M
Definition: AP_Common.h:142
Receiving valid messages and 3D lock with differential improvements.
Definition: AP_GPS.h:101
uint8_t _parity
NMEA message checksum accumulator.
Definition: AP_GPS_NMEA.h:122
#define f(i)
Receiving valid messages and 3D RTK Float.
Definition: AP_GPS.h:102
#define hexdigit(x)
Definition: AP_GPS_NMEA.cpp:51
uint32_t millis()
Definition: system.cpp:157
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
virtual int16_t read()=0
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
Common definitions and utility routines for the ArduPilot libraries.
int32_t _new_longitude
longitude parsed from a term
Definition: AP_GPS_NMEA.h:136
virtual uint32_t available()=0
Location location
last fix location
Definition: AP_GPS.h:135
int32_t lng
param 4 - Longitude * 10**7
Definition: AP_Common.h:144
FILE * fopen(const char *path, const char *mode)
POSIX Open a file with path name and ascii file mode string.
Definition: posix.c:772
void fill_3d_velocity(void)
int16_t _from_hex(char a)
Receiving valid GPS messages but no lock.
Definition: AP_GPS.h:98
uint8_t _term_offset
character offset with the term being received
Definition: AP_GPS_NMEA.h:127
NMEA protocol parser.
void make_gps_time(uint32_t bcd_date, uint32_t bcd_milliseconds)
Definition: GPS_Backend.cpp:76
int32_t _new_date
date parsed from a term
Definition: AP_GPS_NMEA.h:134
static int32_t _parse_decimal_100(const char *p)
AP_HAL::UARTDriver * port
UART we are attached to.
Definition: GPS_Backend.h:69
size_t fwrite(const void *ptr, size_t size, size_t nmemb, FILE *stream)
POSIX write nmemb elements from buf, size bytes each, to the stream fd.
Definition: posix.c:858
float ground_speed
ground speed in m/sec
Definition: AP_GPS.h:136
bool _decode(char c)
Definition: AP_GPS_NMEA.cpp:84
Receiving valid messages and 3D lock.
Definition: AP_GPS.h:100
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
uint16_t hdop
horizontal dilution of precision in cm
Definition: AP_GPS.h:138
bool _is_checksum_term
current term is the checksum
Definition: AP_GPS_NMEA.h:123
uint8_t num_sats
Number of visible satellites.
Definition: AP_GPS.h:140
int32_t _new_course
course parsed from a term
Definition: AP_GPS_NMEA.h:139
float ground_course
ground course in degrees
Definition: AP_GPS.h:137