2013-08-29 02:34:34 -03:00
|
|
|
/*
|
|
|
|
This program is free software: you can redistribute it and/or modify
|
|
|
|
it under the terms of the GNU General Public License as published by
|
|
|
|
the Free Software Foundation, either version 3 of the License, or
|
|
|
|
(at your option) any later version.
|
|
|
|
|
|
|
|
This program is distributed in the hope that it will be useful,
|
|
|
|
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
|
|
|
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
|
|
|
GNU General Public License for more details.
|
|
|
|
|
|
|
|
You should have received a copy of the GNU General Public License
|
|
|
|
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
|
|
|
*/
|
2011-01-09 21:55:45 -04:00
|
|
|
|
|
|
|
//
|
|
|
|
// NMEA parser, adapted by Michael Smith from TinyGPS v9:
|
|
|
|
//
|
|
|
|
// TinyGPS - a small GPS library for Arduino providing basic NMEA parsing
|
|
|
|
// Copyright (C) 2008-9 Mikal Hart
|
|
|
|
// All rights reserved.
|
|
|
|
//
|
|
|
|
|
|
|
|
/// @file AP_GPS_NMEA.cpp
|
|
|
|
/// @brief NMEA protocol parser
|
|
|
|
///
|
|
|
|
/// This is a lightweight NMEA parser, derived originally from the
|
|
|
|
/// TinyGPS parser by Mikal Hart.
|
|
|
|
///
|
|
|
|
|
2015-08-11 03:28:43 -03:00
|
|
|
#include <AP_Common/AP_Common.h>
|
2011-01-09 21:55:45 -04:00
|
|
|
|
|
|
|
#include <ctype.h>
|
|
|
|
#include <stdint.h>
|
2012-09-27 02:18:44 -03:00
|
|
|
#include <stdlib.h>
|
2011-01-09 21:55:45 -04:00
|
|
|
|
2010-09-06 17:16:50 -03:00
|
|
|
#include "AP_GPS_NMEA.h"
|
|
|
|
|
2013-10-23 21:10:32 -03:00
|
|
|
extern const AP_HAL::HAL& hal;
|
|
|
|
|
2015-07-28 22:07:01 -03:00
|
|
|
// optionally log all NMEA data for debug purposes
|
|
|
|
// #define NMEA_LOG_PATH "nmea.log"
|
|
|
|
|
|
|
|
#ifdef NMEA_LOG_PATH
|
|
|
|
#include <stdio.h>
|
|
|
|
#endif
|
|
|
|
|
2011-01-09 21:55:45 -04:00
|
|
|
// Convenience macros //////////////////////////////////////////////////////////
|
|
|
|
//
|
2012-08-21 23:19:51 -03:00
|
|
|
#define DIGIT_TO_VAL(_x) (_x - '0')
|
2016-06-05 18:36:31 -03:00
|
|
|
#define hexdigit(x) ((x)>9?'A'+((x)-10):'0'+(x))
|
2011-01-09 21:55:45 -04:00
|
|
|
|
|
|
|
bool AP_GPS_NMEA::read(void)
|
2010-09-06 17:16:50 -03:00
|
|
|
{
|
2012-08-18 04:35:38 -03:00
|
|
|
int16_t numc;
|
2011-10-28 15:52:50 -03:00
|
|
|
bool parsed = false;
|
|
|
|
|
2014-03-28 16:52:27 -03:00
|
|
|
numc = port->available();
|
2011-10-28 15:52:50 -03:00
|
|
|
while (numc--) {
|
2015-07-28 22:07:01 -03:00
|
|
|
char c = port->read();
|
|
|
|
#ifdef NMEA_LOG_PATH
|
2016-10-30 02:24:21 -03:00
|
|
|
static FILE *logf = nullptr;
|
|
|
|
if (logf == nullptr) {
|
2015-07-28 22:07:01 -03:00
|
|
|
logf = fopen(NMEA_LOG_PATH, "wb");
|
|
|
|
}
|
2016-10-30 02:24:21 -03:00
|
|
|
if (logf != nullptr) {
|
2015-07-28 22:07:01 -03:00
|
|
|
::fwrite(&c, 1, 1, logf);
|
|
|
|
}
|
|
|
|
#endif
|
|
|
|
if (_decode(c)) {
|
2011-10-28 15:52:50 -03:00
|
|
|
parsed = true;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
return parsed;
|
2010-09-06 17:16:50 -03:00
|
|
|
}
|
|
|
|
|
2011-01-09 21:55:45 -04:00
|
|
|
bool AP_GPS_NMEA::_decode(char c)
|
2010-09-06 17:16:50 -03:00
|
|
|
{
|
2011-10-28 15:52:50 -03:00
|
|
|
bool valid_sentence = false;
|
|
|
|
|
2018-06-14 21:50:48 -03:00
|
|
|
_sentence_length++;
|
|
|
|
|
2011-10-28 15:52:50 -03:00
|
|
|
switch (c) {
|
|
|
|
case ',': // term terminators
|
|
|
|
_parity ^= c;
|
2017-08-22 14:28:10 -03:00
|
|
|
FALLTHROUGH;
|
2011-10-28 15:52:50 -03:00
|
|
|
case '\r':
|
|
|
|
case '\n':
|
|
|
|
case '*':
|
|
|
|
if (_term_offset < sizeof(_term)) {
|
|
|
|
_term[_term_offset] = 0;
|
|
|
|
valid_sentence = _term_complete();
|
|
|
|
}
|
|
|
|
++_term_number;
|
|
|
|
_term_offset = 0;
|
|
|
|
_is_checksum_term = c == '*';
|
|
|
|
return valid_sentence;
|
|
|
|
|
|
|
|
case '$': // sentence begin
|
|
|
|
_term_number = _term_offset = 0;
|
|
|
|
_parity = 0;
|
|
|
|
_sentence_type = _GPS_SENTENCE_OTHER;
|
|
|
|
_is_checksum_term = false;
|
|
|
|
_gps_data_good = false;
|
2018-06-14 21:50:48 -03:00
|
|
|
_sentence_length = 1;
|
2011-10-28 15:52:50 -03:00
|
|
|
return valid_sentence;
|
|
|
|
}
|
|
|
|
|
|
|
|
// ordinary characters
|
|
|
|
if (_term_offset < sizeof(_term) - 1)
|
|
|
|
_term[_term_offset++] = c;
|
|
|
|
if (!_is_checksum_term)
|
|
|
|
_parity ^= c;
|
|
|
|
|
|
|
|
return valid_sentence;
|
2010-09-06 17:16:50 -03:00
|
|
|
}
|
|
|
|
|
2016-05-19 10:10:49 -03:00
|
|
|
int32_t AP_GPS_NMEA::_parse_decimal_100(const char *p)
|
2011-01-09 21:55:45 -04:00
|
|
|
{
|
2016-05-19 15:38:11 -03:00
|
|
|
char *endptr = nullptr;
|
|
|
|
long ret = 100 * strtol(p, &endptr, 10);
|
|
|
|
int sign = ret < 0 ? -1 : 1;
|
2016-05-19 10:10:49 -03:00
|
|
|
|
2016-05-19 15:38:11 -03:00
|
|
|
if (ret >= (long)INT32_MAX) {
|
|
|
|
return INT32_MAX;
|
|
|
|
}
|
|
|
|
if (ret <= (long)INT32_MIN) {
|
|
|
|
return INT32_MIN;
|
|
|
|
}
|
|
|
|
if (endptr == nullptr || *endptr != '.') {
|
|
|
|
return ret;
|
2016-02-09 13:12:23 -04:00
|
|
|
}
|
2016-05-19 10:10:49 -03:00
|
|
|
|
2016-05-19 15:38:11 -03:00
|
|
|
if (isdigit(endptr[1])) {
|
|
|
|
ret += sign * 10 * DIGIT_TO_VAL(endptr[1]);
|
|
|
|
if (isdigit(endptr[2])) {
|
|
|
|
ret += sign * DIGIT_TO_VAL(endptr[2]);
|
|
|
|
if (isdigit(endptr[3])) {
|
|
|
|
ret += sign * (DIGIT_TO_VAL(endptr[3]) >= 5);
|
2016-02-09 13:12:23 -04:00
|
|
|
}
|
2011-10-28 15:52:50 -03:00
|
|
|
}
|
|
|
|
}
|
|
|
|
return ret;
|
2010-09-06 17:16:50 -03:00
|
|
|
}
|
|
|
|
|
2013-08-14 01:28:34 -03:00
|
|
|
/*
|
2013-10-23 21:10:32 -03:00
|
|
|
parse a NMEA latitude/longitude degree value. The result is in degrees*1e7
|
2013-08-14 01:28:34 -03:00
|
|
|
*/
|
2012-03-04 05:32:56 -04:00
|
|
|
uint32_t AP_GPS_NMEA::_parse_degrees()
|
2011-01-09 21:55:45 -04:00
|
|
|
{
|
2011-10-28 15:52:50 -03:00
|
|
|
char *p, *q;
|
|
|
|
uint8_t deg = 0, min = 0;
|
2013-08-14 01:28:34 -03:00
|
|
|
float frac_min = 0;
|
2012-08-21 23:19:51 -03:00
|
|
|
int32_t ret = 0;
|
2011-10-28 15:52:50 -03:00
|
|
|
|
|
|
|
// scan for decimal point or end of field
|
2014-11-15 23:08:20 -04:00
|
|
|
for (p = _term; *p && isdigit(*p); p++)
|
2011-10-28 15:52:50 -03:00
|
|
|
;
|
|
|
|
q = _term;
|
|
|
|
|
|
|
|
// convert degrees
|
2014-11-15 23:08:20 -04:00
|
|
|
while ((p - q) > 2 && *q) {
|
2011-10-28 15:52:50 -03:00
|
|
|
if (deg)
|
|
|
|
deg *= 10;
|
|
|
|
deg += DIGIT_TO_VAL(*q++);
|
|
|
|
}
|
|
|
|
|
|
|
|
// convert minutes
|
2014-11-15 23:08:20 -04:00
|
|
|
while (p > q && *q) {
|
2011-10-28 15:52:50 -03:00
|
|
|
if (min)
|
|
|
|
min *= 10;
|
|
|
|
min += DIGIT_TO_VAL(*q++);
|
|
|
|
}
|
|
|
|
|
|
|
|
// convert fractional minutes
|
|
|
|
if (*p == '.') {
|
|
|
|
q = p + 1;
|
2013-08-14 01:28:34 -03:00
|
|
|
float frac_scale = 0.1f;
|
2014-11-15 23:08:20 -04:00
|
|
|
while (*q && isdigit(*q)) {
|
2014-11-15 23:12:14 -04:00
|
|
|
frac_min += DIGIT_TO_VAL(*q) * frac_scale;
|
|
|
|
q++;
|
2013-08-14 01:28:34 -03:00
|
|
|
frac_scale *= 0.1f;
|
2011-10-28 15:52:50 -03:00
|
|
|
}
|
|
|
|
}
|
2013-08-14 01:28:34 -03:00
|
|
|
ret = (deg * (int32_t)10000000UL);
|
|
|
|
ret += (min * (int32_t)10000000UL / 60);
|
2014-07-08 07:27:03 -03:00
|
|
|
ret += (int32_t) (frac_min * (1.0e7f / 60.0f));
|
2012-06-12 08:27:50 -03:00
|
|
|
return ret;
|
2010-09-06 17:16:50 -03:00
|
|
|
}
|
|
|
|
|
2015-07-03 09:08:05 -03:00
|
|
|
/*
|
|
|
|
see if we have a new set of NMEA messages
|
|
|
|
*/
|
|
|
|
bool AP_GPS_NMEA::_have_new_message()
|
|
|
|
{
|
2016-04-18 02:30:17 -03:00
|
|
|
if (_last_RMC_ms == 0 ||
|
|
|
|
_last_GGA_ms == 0) {
|
2015-07-03 09:08:05 -03:00
|
|
|
return false;
|
|
|
|
}
|
2015-11-19 23:10:22 -04:00
|
|
|
uint32_t now = AP_HAL::millis();
|
2016-04-18 02:30:17 -03:00
|
|
|
if (now - _last_RMC_ms > 150 ||
|
|
|
|
now - _last_GGA_ms > 150) {
|
2015-07-03 09:08:05 -03:00
|
|
|
return false;
|
|
|
|
}
|
2016-04-18 02:30:17 -03:00
|
|
|
if (_last_VTG_ms != 0 &&
|
|
|
|
now - _last_VTG_ms > 150) {
|
2015-07-03 09:08:05 -03:00
|
|
|
return false;
|
|
|
|
}
|
|
|
|
// prevent these messages being used again
|
2016-04-18 02:30:17 -03:00
|
|
|
if (_last_VTG_ms != 0) {
|
|
|
|
_last_VTG_ms = 1;
|
2015-07-03 09:08:05 -03:00
|
|
|
}
|
2017-05-28 01:11:31 -03:00
|
|
|
|
|
|
|
if (now - _last_HDT_ms > 300) {
|
|
|
|
// we have lost GPS yaw
|
|
|
|
state.have_gps_yaw = false;
|
|
|
|
}
|
|
|
|
|
2016-04-18 02:30:17 -03:00
|
|
|
_last_GGA_ms = 1;
|
|
|
|
_last_RMC_ms = 1;
|
2015-07-03 09:08:05 -03:00
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
2011-01-09 21:55:45 -04:00
|
|
|
// Processes a just-completed term
|
|
|
|
// Returns true if new sentence has just passed checksum test and is validated
|
|
|
|
bool AP_GPS_NMEA::_term_complete()
|
|
|
|
{
|
2011-10-28 15:52:50 -03:00
|
|
|
// handle the last term in a message
|
|
|
|
if (_is_checksum_term) {
|
2019-07-12 05:52:38 -03:00
|
|
|
uint8_t nibble_high = 0;
|
|
|
|
uint8_t nibble_low = 0;
|
|
|
|
if (!hex_to_uint8(_term[0], nibble_high) || !hex_to_uint8(_term[1], nibble_low)) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
const uint8_t checksum = (nibble_high << 4u) | nibble_low;
|
2011-10-28 15:52:50 -03:00
|
|
|
if (checksum == _parity) {
|
|
|
|
if (_gps_data_good) {
|
2016-02-09 18:39:32 -04:00
|
|
|
uint32_t now = AP_HAL::millis();
|
2011-10-28 15:52:50 -03:00
|
|
|
switch (_sentence_type) {
|
2016-04-18 02:30:17 -03:00
|
|
|
case _GPS_SENTENCE_RMC:
|
|
|
|
_last_RMC_ms = now;
|
2013-10-23 08:13:48 -03:00
|
|
|
//time = _new_time;
|
|
|
|
//date = _new_date;
|
2014-03-28 16:52:27 -03:00
|
|
|
state.location.lat = _new_latitude;
|
|
|
|
state.location.lng = _new_longitude;
|
|
|
|
state.ground_speed = _new_speed*0.01f;
|
2016-05-04 22:28:35 -03:00
|
|
|
state.ground_course = wrap_360(_new_course*0.01f);
|
2014-03-28 16:52:27 -03:00
|
|
|
make_gps_time(_new_date, _new_time * 10);
|
2018-05-15 22:16:01 -03:00
|
|
|
set_uart_timestamp(_sentence_length);
|
2016-02-09 18:39:32 -04:00
|
|
|
state.last_gps_time_ms = now;
|
2014-03-28 16:52:27 -03:00
|
|
|
fill_3d_velocity();
|
2011-10-28 15:52:50 -03:00
|
|
|
break;
|
2016-04-18 02:30:17 -03:00
|
|
|
case _GPS_SENTENCE_GGA:
|
|
|
|
_last_GGA_ms = now;
|
2014-03-28 16:52:27 -03:00
|
|
|
state.location.alt = _new_altitude;
|
|
|
|
state.location.lat = _new_latitude;
|
|
|
|
state.location.lng = _new_longitude;
|
|
|
|
state.num_sats = _new_satellite_count;
|
|
|
|
state.hdop = _new_hdop;
|
2017-09-14 11:59:23 -03:00
|
|
|
switch(_new_quality_indicator) {
|
|
|
|
case 0: // Fix not available or invalid
|
|
|
|
state.status = AP_GPS::NO_FIX;
|
|
|
|
break;
|
|
|
|
case 1: // GPS SPS Mode, fix valid
|
|
|
|
state.status = AP_GPS::GPS_OK_FIX_3D;
|
|
|
|
break;
|
|
|
|
case 2: // Differential GPS, SPS Mode, fix valid
|
|
|
|
state.status = AP_GPS::GPS_OK_FIX_3D_DGPS;
|
|
|
|
break;
|
|
|
|
case 3: // GPS PPS Mode, fix valid
|
|
|
|
state.status = AP_GPS::GPS_OK_FIX_3D;
|
|
|
|
break;
|
|
|
|
case 4: // Real Time Kinematic. System used in RTK mode with fixed integers
|
|
|
|
state.status = AP_GPS::GPS_OK_FIX_3D_RTK_FIXED;
|
|
|
|
break;
|
|
|
|
case 5: // Float RTK. Satellite system used in RTK mode, floating integers
|
|
|
|
state.status = AP_GPS::GPS_OK_FIX_3D_RTK_FLOAT;
|
|
|
|
break;
|
|
|
|
case 6: // Estimated (dead reckoning) Mode
|
|
|
|
state.status = AP_GPS::NO_FIX;
|
|
|
|
break;
|
|
|
|
default://to maintain compatibility with MAV_GPS_INPUT and others
|
|
|
|
state.status = AP_GPS::GPS_OK_FIX_3D;
|
|
|
|
break;
|
|
|
|
}
|
2011-10-28 15:52:50 -03:00
|
|
|
break;
|
2016-04-18 02:30:17 -03:00
|
|
|
case _GPS_SENTENCE_VTG:
|
|
|
|
_last_VTG_ms = now;
|
2016-05-04 22:28:35 -03:00
|
|
|
state.ground_speed = _new_speed*0.01f;
|
|
|
|
state.ground_course = wrap_360(_new_course*0.01f);
|
2016-02-09 18:41:42 -04:00
|
|
|
fill_3d_velocity();
|
2011-10-28 15:52:50 -03:00
|
|
|
// VTG has no fix indicator, can't change fix status
|
|
|
|
break;
|
2017-05-28 01:11:31 -03:00
|
|
|
case _GPS_SENTENCE_HDT:
|
|
|
|
_last_HDT_ms = now;
|
|
|
|
state.gps_yaw = wrap_360(_new_gps_yaw*0.01f);
|
|
|
|
state.have_gps_yaw = true;
|
2019-12-22 19:03:58 -04:00
|
|
|
// remember that we are setup to provide yaw. With
|
|
|
|
// a NMEA GPS we can only tell if the GPS is
|
|
|
|
// configured to provide yaw when it first sends a
|
|
|
|
// HDT sentence.
|
|
|
|
state.gps_yaw_configured = true;
|
2017-05-28 01:11:31 -03:00
|
|
|
break;
|
2011-10-28 15:52:50 -03:00
|
|
|
}
|
|
|
|
} else {
|
|
|
|
switch (_sentence_type) {
|
2016-04-18 02:30:17 -03:00
|
|
|
case _GPS_SENTENCE_RMC:
|
|
|
|
case _GPS_SENTENCE_GGA:
|
2011-10-28 15:52:50 -03:00
|
|
|
// Only these sentences give us information about
|
|
|
|
// fix status.
|
2014-03-28 16:52:27 -03:00
|
|
|
state.status = AP_GPS::NO_FIX;
|
2011-10-28 15:52:50 -03:00
|
|
|
}
|
|
|
|
}
|
2015-07-03 09:08:05 -03:00
|
|
|
// see if we got a good message
|
|
|
|
return _have_new_message();
|
2011-10-28 15:52:50 -03:00
|
|
|
}
|
|
|
|
// we got a bad message, ignore it
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
// the first term determines the sentence type
|
|
|
|
if (_term_number == 0) {
|
2016-04-18 02:30:17 -03:00
|
|
|
/*
|
|
|
|
The first two letters of the NMEA term are the talker
|
|
|
|
ID. The most common is 'GP' but there are a bunch of others
|
|
|
|
that are valid. We accept any two characters here.
|
|
|
|
*/
|
|
|
|
if (_term[0] < 'A' || _term[0] > 'Z' ||
|
|
|
|
_term[1] < 'A' || _term[1] > 'Z') {
|
|
|
|
_sentence_type = _GPS_SENTENCE_OTHER;
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
const char *term_type = &_term[2];
|
|
|
|
if (strcmp(term_type, "RMC") == 0) {
|
|
|
|
_sentence_type = _GPS_SENTENCE_RMC;
|
|
|
|
} else if (strcmp(term_type, "GGA") == 0) {
|
|
|
|
_sentence_type = _GPS_SENTENCE_GGA;
|
2017-05-28 01:11:31 -03:00
|
|
|
} else if (strcmp(term_type, "HDT") == 0) {
|
|
|
|
_sentence_type = _GPS_SENTENCE_HDT;
|
|
|
|
// HDT doesn't have a data qualifier
|
|
|
|
_gps_data_good = true;
|
2016-04-18 02:30:17 -03:00
|
|
|
} else if (strcmp(term_type, "VTG") == 0) {
|
|
|
|
_sentence_type = _GPS_SENTENCE_VTG;
|
2011-10-28 15:52:50 -03:00
|
|
|
// VTG may not contain a data qualifier, presume the solution is good
|
|
|
|
// unless it tells us otherwise.
|
|
|
|
_gps_data_good = true;
|
|
|
|
} else {
|
|
|
|
_sentence_type = _GPS_SENTENCE_OTHER;
|
|
|
|
}
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
2017-05-28 01:11:31 -03:00
|
|
|
// 32 = RMC, 64 = GGA, 96 = VTG, 128 = HDT
|
2011-10-28 15:52:50 -03:00
|
|
|
if (_sentence_type != _GPS_SENTENCE_OTHER && _term[0]) {
|
|
|
|
switch (_sentence_type + _term_number) {
|
2012-08-21 23:19:51 -03:00
|
|
|
// operational status
|
|
|
|
//
|
2016-04-18 02:30:17 -03:00
|
|
|
case _GPS_SENTENCE_RMC + 2: // validity (RMC)
|
2011-10-28 15:52:50 -03:00
|
|
|
_gps_data_good = _term[0] == 'A';
|
|
|
|
break;
|
2016-04-18 02:30:17 -03:00
|
|
|
case _GPS_SENTENCE_GGA + 6: // Fix data (GGA)
|
2011-10-28 15:52:50 -03:00
|
|
|
_gps_data_good = _term[0] > '0';
|
2017-09-14 11:59:23 -03:00
|
|
|
_new_quality_indicator = _term[0] - '0';
|
2011-10-28 15:52:50 -03:00
|
|
|
break;
|
2016-04-18 02:30:17 -03:00
|
|
|
case _GPS_SENTENCE_VTG + 9: // validity (VTG) (we may not see this field)
|
2011-10-28 15:52:50 -03:00
|
|
|
_gps_data_good = _term[0] != 'N';
|
|
|
|
break;
|
2016-04-18 02:30:17 -03:00
|
|
|
case _GPS_SENTENCE_GGA + 7: // satellite count (GGA)
|
2011-10-28 15:52:50 -03:00
|
|
|
_new_satellite_count = atol(_term);
|
|
|
|
break;
|
2016-04-18 02:30:17 -03:00
|
|
|
case _GPS_SENTENCE_GGA + 8: // HDOP (GGA)
|
2016-05-19 10:10:49 -03:00
|
|
|
_new_hdop = (uint16_t)_parse_decimal_100(_term);
|
2011-10-28 15:52:50 -03:00
|
|
|
break;
|
|
|
|
|
2012-08-21 23:19:51 -03:00
|
|
|
// time and date
|
|
|
|
//
|
2016-04-18 02:30:17 -03:00
|
|
|
case _GPS_SENTENCE_RMC + 1: // Time (RMC)
|
|
|
|
case _GPS_SENTENCE_GGA + 1: // Time (GGA)
|
2016-05-19 10:10:49 -03:00
|
|
|
_new_time = _parse_decimal_100(_term);
|
2011-10-28 15:52:50 -03:00
|
|
|
break;
|
2016-04-18 02:30:17 -03:00
|
|
|
case _GPS_SENTENCE_RMC + 9: // Date (GPRMC)
|
2011-10-28 15:52:50 -03:00
|
|
|
_new_date = atol(_term);
|
|
|
|
break;
|
|
|
|
|
2012-08-21 23:19:51 -03:00
|
|
|
// location
|
|
|
|
//
|
2016-04-18 02:30:17 -03:00
|
|
|
case _GPS_SENTENCE_RMC + 3: // Latitude
|
|
|
|
case _GPS_SENTENCE_GGA + 2:
|
2011-10-28 15:52:50 -03:00
|
|
|
_new_latitude = _parse_degrees();
|
|
|
|
break;
|
2016-04-18 02:30:17 -03:00
|
|
|
case _GPS_SENTENCE_RMC + 4: // N/S
|
|
|
|
case _GPS_SENTENCE_GGA + 3:
|
2011-10-28 15:52:50 -03:00
|
|
|
if (_term[0] == 'S')
|
|
|
|
_new_latitude = -_new_latitude;
|
|
|
|
break;
|
2016-04-18 02:30:17 -03:00
|
|
|
case _GPS_SENTENCE_RMC + 5: // Longitude
|
|
|
|
case _GPS_SENTENCE_GGA + 4:
|
2011-10-28 15:52:50 -03:00
|
|
|
_new_longitude = _parse_degrees();
|
|
|
|
break;
|
2016-04-18 02:30:17 -03:00
|
|
|
case _GPS_SENTENCE_RMC + 6: // E/W
|
|
|
|
case _GPS_SENTENCE_GGA + 5:
|
2011-10-28 15:52:50 -03:00
|
|
|
if (_term[0] == 'W')
|
|
|
|
_new_longitude = -_new_longitude;
|
|
|
|
break;
|
2016-04-18 02:30:17 -03:00
|
|
|
case _GPS_SENTENCE_GGA + 9: // Altitude (GPGGA)
|
2016-05-19 10:10:49 -03:00
|
|
|
_new_altitude = _parse_decimal_100(_term);
|
2011-10-28 15:52:50 -03:00
|
|
|
break;
|
|
|
|
|
2012-08-21 23:19:51 -03:00
|
|
|
// course and speed
|
|
|
|
//
|
2016-04-18 02:30:17 -03:00
|
|
|
case _GPS_SENTENCE_RMC + 7: // Speed (GPRMC)
|
|
|
|
case _GPS_SENTENCE_VTG + 5: // Speed (VTG)
|
2016-05-19 10:10:49 -03:00
|
|
|
_new_speed = (_parse_decimal_100(_term) * 514) / 1000; // knots-> m/sec, approximiates * 0.514
|
2011-10-28 15:52:50 -03:00
|
|
|
break;
|
2017-05-28 01:11:31 -03:00
|
|
|
case _GPS_SENTENCE_HDT + 1: // Course (HDT)
|
|
|
|
_new_gps_yaw = _parse_decimal_100(_term);
|
|
|
|
break;
|
2016-04-18 02:30:17 -03:00
|
|
|
case _GPS_SENTENCE_RMC + 8: // Course (GPRMC)
|
|
|
|
case _GPS_SENTENCE_VTG + 1: // Course (VTG)
|
2016-05-19 10:10:49 -03:00
|
|
|
_new_course = _parse_decimal_100(_term);
|
2011-10-28 15:52:50 -03:00
|
|
|
break;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
return false;
|
2010-09-06 17:16:50 -03:00
|
|
|
}
|
2012-09-17 01:43:07 -03:00
|
|
|
|
|
|
|
/*
|
|
|
|
detect a NMEA GPS. Adds one byte, and returns true if the stream
|
|
|
|
matches a NMEA string
|
|
|
|
*/
|
|
|
|
bool
|
2014-03-28 16:52:27 -03:00
|
|
|
AP_GPS_NMEA::_detect(struct NMEA_detect_state &state, uint8_t data)
|
2012-09-17 01:43:07 -03:00
|
|
|
{
|
2014-03-28 00:50:44 -03:00
|
|
|
switch (state.step) {
|
2012-09-17 01:43:07 -03:00
|
|
|
case 0:
|
2014-03-28 00:50:44 -03:00
|
|
|
state.ck = 0;
|
2012-09-17 01:43:07 -03:00
|
|
|
if ('$' == data) {
|
2014-03-28 00:50:44 -03:00
|
|
|
state.step++;
|
2012-09-17 01:43:07 -03:00
|
|
|
}
|
|
|
|
break;
|
|
|
|
case 1:
|
|
|
|
if ('*' == data) {
|
2014-03-28 00:50:44 -03:00
|
|
|
state.step++;
|
2012-09-17 01:43:07 -03:00
|
|
|
} else {
|
2014-03-28 00:50:44 -03:00
|
|
|
state.ck ^= data;
|
2012-09-17 01:43:07 -03:00
|
|
|
}
|
|
|
|
break;
|
|
|
|
case 2:
|
2014-03-28 00:50:44 -03:00
|
|
|
if (hexdigit(state.ck>>4) == data) {
|
|
|
|
state.step++;
|
2012-09-17 01:43:07 -03:00
|
|
|
} else {
|
2014-03-28 00:50:44 -03:00
|
|
|
state.step = 0;
|
2012-09-17 01:43:07 -03:00
|
|
|
}
|
|
|
|
break;
|
|
|
|
case 3:
|
2014-03-28 00:50:44 -03:00
|
|
|
if (hexdigit(state.ck&0xF) == data) {
|
2016-06-05 18:36:31 -03:00
|
|
|
state.step = 0;
|
2012-09-17 01:43:07 -03:00
|
|
|
return true;
|
|
|
|
}
|
2014-03-28 00:50:44 -03:00
|
|
|
state.step = 0;
|
2012-09-17 01:43:07 -03:00
|
|
|
break;
|
|
|
|
}
|
|
|
|
return false;
|
|
|
|
}
|