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.cpp
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//2223/// @file AP_GPS_NMEA.cpp24/// @brief NMEA protocol parser25///26/// This is a lightweight NMEA parser, derived originally from the27/// TinyGPS parser by Mikal Hart.28///2930#include <AP_Common/AP_Common.h>31#include <AP_Common/NMEA.h>32#include <GCS_MAVLink/GCS.h>33#include <AP_Logger/AP_Logger.h>3435#include <ctype.h>36#include <stdint.h>37#include <stdlib.h>38#include <stdio.h>3940#include "AP_GPS_NMEA.h"4142#if AP_GPS_NMEA_ENABLED43extern const AP_HAL::HAL& hal;4445#ifndef AP_GPS_NMEA_CONFIG_PERIOD_MS46// how often we send board specific config commands47#define AP_GPS_NMEA_CONFIG_PERIOD_MS 15000U48#endif4950// a quiet nan for invalid values51#define QNAN nanf("GPS")5253// Convenience macros //////////////////////////////////////////////////////////54//55#define DIGIT_TO_VAL(_x) (_x - '0')56#define hexdigit(x) ((x)>9?'A'+((x)-10):'0'+(x))5758bool AP_GPS_NMEA::read(void)59{60int16_t numc;61bool parsed = false;6263send_config();6465numc = port->available();66while (numc--) {67char c = port->read();68#if AP_GPS_DEBUG_LOGGING_ENABLED69log_data((const uint8_t *)&c, 1);70#endif71if (_decode(c)) {72parsed = true;73}74}75return parsed;76}7778/*79decode one character, return true if we have successfully completed a sentence, false otherwise80*/81bool AP_GPS_NMEA::_decode(char c)82{83_sentence_length++;8485switch (c) {86case ';':87// header separator for unicore88if (!_is_unicore) {89return false;90}91FALLTHROUGH;92case ',': // term terminators93_parity ^= c;94if (_is_unicore) {95_crc32 = crc_crc32(_crc32, (const uint8_t *)&c, 1);96}97FALLTHROUGH;98case '\r':99case '\n':100case '*': {101if (_sentence_done) {102return false;103}104bool valid_sentence = false;105if (_term_offset < sizeof(_term)) {106_term[_term_offset] = 0;107valid_sentence = _term_complete();108}109++_term_number;110_term_offset = 0;111_is_checksum_term = c == '*';112return valid_sentence;113}114115case '$': // sentence begin116case '#': // unicore message begin117_is_unicore = (c == '#');118_term_number = _term_offset = 0;119_parity = 0;120_crc32 = 0;121_sentence_type = _GPS_SENTENCE_OTHER;122_is_checksum_term = false;123_sentence_length = 1;124_sentence_done = false;125_new_gps_yaw = QNAN;126return false;127}128129// ordinary characters130if (_term_offset < sizeof(_term) - 1)131_term[_term_offset++] = c;132if (!_is_checksum_term) {133_parity ^= c;134if (_is_unicore) {135_crc32 = crc_crc32(_crc32, (const uint8_t *)&c, 1);136}137}138139return false;140}141142int32_t AP_GPS_NMEA::_parse_decimal_100(const char *p)143{144char *endptr = nullptr;145long ret = 100 * strtol(p, &endptr, 10);146int sign = ret < 0 ? -1 : 1;147148if (ret >= (long)INT32_MAX) {149return INT32_MAX;150}151if (ret <= (long)INT32_MIN) {152return INT32_MIN;153}154if (endptr == nullptr || *endptr != '.') {155return ret;156}157158if (isdigit(endptr[1])) {159ret += sign * 10 * DIGIT_TO_VAL(endptr[1]);160if (isdigit(endptr[2])) {161ret += sign * DIGIT_TO_VAL(endptr[2]);162if (isdigit(endptr[3])) {163ret += sign * (DIGIT_TO_VAL(endptr[3]) >= 5);164}165}166}167return ret;168}169170/*171parse a NMEA latitude/longitude degree value. The result is in degrees*1e7172*/173uint32_t AP_GPS_NMEA::_parse_degrees()174{175char *p, *q;176uint8_t deg = 0, min = 0;177float frac_min = 0;178int32_t ret = 0;179180// scan for decimal point or end of field181for (p = _term; *p && isdigit(*p); p++)182;183q = _term;184185// convert degrees186while ((p - q) > 2 && *q) {187if (deg)188deg *= 10;189deg += DIGIT_TO_VAL(*q++);190}191192// convert minutes193while (p > q && *q) {194if (min)195min *= 10;196min += DIGIT_TO_VAL(*q++);197}198199// convert fractional minutes200if (*p == '.') {201q = p + 1;202float frac_scale = 0.1f;203while (*q && isdigit(*q)) {204frac_min += DIGIT_TO_VAL(*q) * frac_scale;205q++;206frac_scale *= 0.1f;207}208}209ret = (deg * (int32_t)10000000UL);210ret += (min * (int32_t)10000000UL / 60);211ret += (int32_t) (frac_min * (1.0e7f / 60.0f));212return ret;213}214215/*216see if we have a new set of NMEA messages217*/218bool AP_GPS_NMEA::_have_new_message()219{220if (_last_RMC_ms == 0 ||221_last_GGA_ms == 0) {222return false;223}224uint32_t now = AP_HAL::millis();225if (now - _last_RMC_ms > 150 ||226now - _last_GGA_ms > 150) {227return false;228}229if (_last_VTG_ms != 0 &&230now - _last_VTG_ms > 150) {231return false;232}233234/*235if we have seen a message with 3D velocity data messages then236wait for them again. This is important as the237have_vertical_velocity field will be overwritten by238fill_3d_velocity()239*/240if (_last_vvelocity_ms != 0 &&241now - _last_vvelocity_ms > 150 &&242now - _last_vvelocity_ms < 1000) {243// waiting on a message with velocity244return false;245}246if (_last_vaccuracy_ms != 0 &&247now - _last_vaccuracy_ms > 150 &&248now - _last_vaccuracy_ms < 1000) {249// waiting on a message with velocity accuracy250return false;251}252253// prevent these messages being used again254if (_last_VTG_ms != 0) {255_last_VTG_ms = 1;256}257258if (now - _last_yaw_ms > 300) {259// we have lost GPS yaw260state.have_gps_yaw = false;261}262263if (now - _last_KSXT_pos_ms > 500) {264// we have lost KSXT265_last_KSXT_pos_ms = 0;266}267268#if AP_GPS_NMEA_UNICORE_ENABLED269if (now - _last_AGRICA_ms > 500) {270if (_last_AGRICA_ms != 0) {271// we have lost AGRICA272state.have_gps_yaw = false;273state.have_vertical_velocity = false;274state.have_speed_accuracy = false;275state.have_horizontal_accuracy = false;276state.have_vertical_accuracy = false;277state.have_undulation = false;278_last_AGRICA_ms = 0;279}280}281#endif // AP_GPS_NMEA_UNICORE_ENABLED282283_last_fix_ms = now;284285_last_GGA_ms = 1;286_last_RMC_ms = 1;287return true;288}289290// Processes a just-completed term291// Returns true if new sentence has just passed checksum test and is validated292bool AP_GPS_NMEA::_term_complete()293{294// handle the last term in a message295if (_is_checksum_term) {296_sentence_done = true;297const uint32_t crc = strtoul(_term, nullptr, 16);298const bool crc_ok = _is_unicore? (_crc32 == crc) : (_parity == crc);299if (crc_ok) {300uint32_t now = AP_HAL::millis();301switch (_sentence_type) {302case _GPS_SENTENCE_RMC:303_last_RMC_ms = now;304//time = _new_time;305//date = _new_date;306if (_last_KSXT_pos_ms == 0 && _last_AGRICA_ms == 0) {307state.location.lat = _new_latitude;308state.location.lng = _new_longitude;309}310if (_last_3D_velocity_ms == 0 ||311now - _last_3D_velocity_ms > 1000) {312state.ground_speed = _new_speed*0.01f;313state.ground_course = wrap_360(_new_course*0.01f);314}315if (state.status >= AP_GPS::GPS_OK_FIX_3D) {316make_gps_time(_new_date, _new_time * 10);317if (_last_AGRICA_ms != 0) {318state.time_week_ms = _last_itow_ms;319}320}321set_uart_timestamp(_sentence_length);322state.last_gps_time_ms = now;323if (_last_vvelocity_ms == 0 ||324now - _last_vvelocity_ms > 1000) {325fill_3d_velocity();326}327break;328case _GPS_SENTENCE_GGA:329_last_GGA_ms = now;330if (_last_KSXT_pos_ms == 0 && _last_AGRICA_ms == 0) {331set_alt_amsl_cm(state, _new_altitude);332state.location.lat = _new_latitude;333state.location.lng = _new_longitude;334}335state.num_sats = _new_satellite_count;336state.hdop = _new_hdop;337switch(_new_quality_indicator) {338case 0: // Fix not available or invalid339state.status = AP_GPS::NO_FIX;340break;341case 1: // GPS SPS Mode, fix valid342state.status = AP_GPS::GPS_OK_FIX_3D;343break;344case 2: // Differential GPS, SPS Mode, fix valid345state.status = AP_GPS::GPS_OK_FIX_3D_DGPS;346break;347case 3: // GPS PPS Mode, fix valid348state.status = AP_GPS::GPS_OK_FIX_3D;349break;350case 4: // Real Time Kinematic. System used in RTK mode with fixed integers351state.status = AP_GPS::GPS_OK_FIX_3D_RTK_FIXED;352break;353case 5: // Float RTK. Satellite system used in RTK mode, floating integers354state.status = AP_GPS::GPS_OK_FIX_3D_RTK_FLOAT;355break;356case 6: // Estimated (dead reckoning) Mode357state.status = AP_GPS::NO_FIX;358break;359default://to maintain compatibility with MAV_GPS_INPUT and others360state.status = AP_GPS::GPS_OK_FIX_3D;361break;362}363break;364case _GPS_SENTENCE_VTG:365_last_VTG_ms = now;366if (_last_3D_velocity_ms == 0 ||367now - _last_3D_velocity_ms > 1000) {368state.ground_speed = _new_speed*0.01f;369state.ground_course = wrap_360(_new_course*0.01f);370if (_last_vvelocity_ms == 0 ||371now - _last_vvelocity_ms > 1000) {372fill_3d_velocity();373}374}375// VTG has no fix indicator, can't change fix status376break;377case _GPS_SENTENCE_HDT:378case _GPS_SENTENCE_THS:379if (_last_AGRICA_ms != 0 || _expect_agrica) {380// use AGRICA381break;382}383if (isnan(_new_gps_yaw)) {384// empty sentence385break;386}387_last_yaw_ms = now;388state.gps_yaw = wrap_360(_new_gps_yaw*0.01f);389state.have_gps_yaw = true;390state.gps_yaw_time_ms = now;391// remember that we are setup to provide yaw. With392// a NMEA GPS we can only tell if the GPS is393// configured to provide yaw when it first sends a394// HDT sentence.395state.gps_yaw_configured = true;396break;397case _GPS_SENTENCE_PHD:398if (_last_AGRICA_ms != 0) {399// prefer AGRICA400break;401}402if (_phd.msg_id == 12) {403state.velocity.x = _phd.fields[0] * 0.01;404state.velocity.y = _phd.fields[1] * 0.01;405state.velocity.z = _phd.fields[2] * 0.01;406state.have_vertical_velocity = true;407_last_vvelocity_ms = now;408// we prefer a true 3D velocity when available409velocity_to_speed_course(state);410_last_3D_velocity_ms = now;411} else if (_phd.msg_id == 26) {412state.horizontal_accuracy = MAX(_phd.fields[0],_phd.fields[1]) * 0.001;413state.have_horizontal_accuracy = true;414state.vertical_accuracy = _phd.fields[2] * 0.001;415state.have_vertical_accuracy = true;416state.speed_accuracy = MAX(_phd.fields[3],_phd.fields[4]) * 0.001;417state.have_speed_accuracy = true;418_last_vaccuracy_ms = now;419}420break;421case _GPS_SENTENCE_KSXT:422if (_last_AGRICA_ms != 0 || _expect_agrica) {423// prefer AGRICA424break;425}426state.location.lat = _ksxt.fields[2]*1.0e7;427state.location.lng = _ksxt.fields[1]*1.0e7;428set_alt_amsl_cm(state, _ksxt.fields[3]*1.0e2);429_last_KSXT_pos_ms = now;430if (_ksxt.fields[9] >= 1) {431// we have 3D fix432constexpr float kmh_to_mps = 1.0 / 3.6;433state.velocity.y = _ksxt.fields[16] * kmh_to_mps;434state.velocity.x = _ksxt.fields[17] * kmh_to_mps;435state.velocity.z = _ksxt.fields[18] * -kmh_to_mps;436state.have_vertical_velocity = true;437_last_vvelocity_ms = now;438// we prefer a true 3D velocity when available439velocity_to_speed_course(state);440_last_3D_velocity_ms = now;441}442if (is_equal(3.0f, float(_ksxt.fields[10]))) {443// have good yaw (from RTK fixed moving baseline solution)444_last_yaw_ms = now;445state.gps_yaw = _ksxt.fields[4];446state.have_gps_yaw = true;447state.gps_yaw_time_ms = now;448state.gps_yaw_configured = true;449}450break;451#if AP_GPS_NMEA_UNICORE_ENABLED452case _GPS_SENTENCE_AGRICA: {453const auto &ag = _agrica;454_last_AGRICA_ms = now;455_last_vvelocity_ms = now;456_last_vaccuracy_ms = now;457_last_3D_velocity_ms = now;458state.location.lat = ag.lat*1.0e7;459state.location.lng = ag.lng*1.0e7;460state.undulation = -ag.undulation;461state.have_undulation = true;462set_alt_amsl_cm(state, ag.alt*1.0e2);463state.velocity = ag.vel_NED;464velocity_to_speed_course(state);465state.speed_accuracy = ag.vel_stddev.length();466state.horizontal_accuracy = ag.pos_stddev.xy().length();467state.vertical_accuracy = ag.pos_stddev.z;468state.have_vertical_velocity = true;469state.have_speed_accuracy = true;470state.have_horizontal_accuracy = true;471state.have_vertical_accuracy = true;472check_new_itow(ag.itow, _sentence_length);473break;474}475case _GPS_SENTENCE_VERSIONA: {476_have_unicore_versiona = true;477GCS_SEND_TEXT(MAV_SEVERITY_INFO,478"NMEA %s %s %s",479_versiona.type,480_versiona.version,481_versiona.build_date);482break;483}484case _GPS_SENTENCE_UNIHEADINGA: {485#if GPS_MOVING_BASELINE486const auto &ag = _agrica;487const auto &uh = _uniheadinga;488if (now - _last_AGRICA_ms > 500 || ag.heading_status != 4) {489// we need heading_status from AGRICA490state.have_gps_yaw = false;491break;492}493const float dist = uh.baseline_length;494const float bearing = uh.heading;495const float alt_diff = dist*tanf(radians(-uh.pitch));496state.relPosHeading = bearing;497state.relPosLength = dist;498state.relPosD = alt_diff;499state.relposheading_ts = now;500if (calculate_moving_base_yaw(bearing, dist, alt_diff)) {501state.have_gps_yaw_accuracy = true;502state.gps_yaw_accuracy = uh.heading_sd;503_last_yaw_ms = now;504}505state.gps_yaw_configured = true;506#endif // GPS_MOVING_BASELINE507break;508}509#endif // AP_GPS_NMEA_UNICORE_ENABLED510}511// see if we got a good message512return _have_new_message();513}514// we got a bad message, ignore it515return false;516}517518// the first term determines the sentence type519if (_term_number == 0) {520/*521special case for $PHD message522*/523if (strcmp(_term, "PHD") == 0) {524_sentence_type = _GPS_SENTENCE_PHD;525return false;526}527if (strcmp(_term, "KSXT") == 0) {528_sentence_type = _GPS_SENTENCE_KSXT;529return false;530}531#if AP_GPS_NMEA_UNICORE_ENABLED532if (strcmp(_term, "AGRICA") == 0 && _expect_agrica) {533_sentence_type = _GPS_SENTENCE_AGRICA;534return false;535}536if (strcmp(_term, "VERSIONA") == 0) {537_sentence_type = _GPS_SENTENCE_VERSIONA;538return false;539}540if (strcmp(_term, "UNIHEADINGA") == 0 && _expect_agrica) {541_sentence_type = _GPS_SENTENCE_UNIHEADINGA;542return false;543}544#endif545/*546The first two letters of the NMEA term are the talker547ID. The most common is 'GP' but there are a bunch of others548that are valid. We accept any two characters here.549*/550if (_term[0] < 'A' || _term[0] > 'Z' ||551_term[1] < 'A' || _term[1] > 'Z') {552_sentence_type = _GPS_SENTENCE_OTHER;553return false;554}555const char *term_type = &_term[2];556if (strcmp(term_type, "RMC") == 0) {557_sentence_type = _GPS_SENTENCE_RMC;558} else if (strcmp(term_type, "GGA") == 0) {559_sentence_type = _GPS_SENTENCE_GGA;560} else if (strcmp(term_type, "HDT") == 0) {561_sentence_type = _GPS_SENTENCE_HDT;562} else if (strcmp(term_type, "THS") == 0) {563_sentence_type = _GPS_SENTENCE_THS;564} else if (strcmp(term_type, "VTG") == 0) {565_sentence_type = _GPS_SENTENCE_VTG;566} else {567_sentence_type = _GPS_SENTENCE_OTHER;568}569return false;570}571572// 32 = RMC, 64 = GGA, 96 = VTG, 128 = HDT, 160 = THS573if (_sentence_type != _GPS_SENTENCE_OTHER && _term[0]) {574switch (_sentence_type + _term_number) {575// operational status576//577case _GPS_SENTENCE_RMC + 2: // validity (RMC)578break;579case _GPS_SENTENCE_GGA + 6: // Fix data (GGA)580if (_term[0] > '0') {581_new_quality_indicator = _term[0] - '0';582} else {583_new_quality_indicator = 0;584}585break;586case _GPS_SENTENCE_GGA + 7: // satellite count (GGA)587_new_satellite_count = atol(_term);588break;589case _GPS_SENTENCE_GGA + 8: // HDOP (GGA)590_new_hdop = (uint16_t)_parse_decimal_100(_term);591break;592593// time and date594//595case _GPS_SENTENCE_RMC + 1: // Time (RMC)596case _GPS_SENTENCE_GGA + 1: // Time (GGA)597_new_time = _parse_decimal_100(_term);598break;599case _GPS_SENTENCE_RMC + 9: // Date (GPRMC)600_new_date = atol(_term);601break;602603// location604//605case _GPS_SENTENCE_RMC + 3: // Latitude606case _GPS_SENTENCE_GGA + 2:607_new_latitude = _parse_degrees();608break;609case _GPS_SENTENCE_RMC + 4: // N/S610case _GPS_SENTENCE_GGA + 3:611if (_term[0] == 'S')612_new_latitude = -_new_latitude;613break;614case _GPS_SENTENCE_RMC + 5: // Longitude615case _GPS_SENTENCE_GGA + 4:616_new_longitude = _parse_degrees();617break;618case _GPS_SENTENCE_RMC + 6: // E/W619case _GPS_SENTENCE_GGA + 5:620if (_term[0] == 'W')621_new_longitude = -_new_longitude;622break;623case _GPS_SENTENCE_GGA + 9: // Altitude (GPGGA)624_new_altitude = _parse_decimal_100(_term);625break;626627// course and speed628//629case _GPS_SENTENCE_RMC + 7: // Speed (GPRMC)630case _GPS_SENTENCE_VTG + 5: // Speed (VTG)631_new_speed = (_parse_decimal_100(_term) * 514) / 1000; // knots-> m/sec, approximates * 0.514632break;633case _GPS_SENTENCE_HDT + 1: // Course (HDT)634_new_gps_yaw = _parse_decimal_100(_term);635break;636case _GPS_SENTENCE_THS + 1: // Course (THS)637_new_gps_yaw = _parse_decimal_100(_term);638break;639case _GPS_SENTENCE_RMC + 8: // Course (GPRMC)640case _GPS_SENTENCE_VTG + 1: // Course (VTG)641_new_course = _parse_decimal_100(_term);642break;643644case _GPS_SENTENCE_PHD + 1: // PHD class645_phd.msg_class = atol(_term);646break;647case _GPS_SENTENCE_PHD + 2: // PHD message648_phd.msg_id = atol(_term);649break;650case _GPS_SENTENCE_PHD + 5: // PHD message, itow651_phd.itow = strtoul(_term, nullptr, 10);652break;653case _GPS_SENTENCE_PHD + 6 ... _GPS_SENTENCE_PHD + 11: // PHD message, fields654_phd.fields[_term_number-6] = atol(_term);655break;656case _GPS_SENTENCE_KSXT + 1 ... _GPS_SENTENCE_KSXT + 22: // KSXT message, fields657_ksxt.fields[_term_number-1] = atof(_term);658break;659#if AP_GPS_NMEA_UNICORE_ENABLED660case _GPS_SENTENCE_AGRICA + 1 ... _GPS_SENTENCE_AGRICA + 65: // AGRICA message661parse_agrica_field(_term_number, _term);662break;663case _GPS_SENTENCE_VERSIONA + 1 ... _GPS_SENTENCE_VERSIONA + 20:664parse_versiona_field(_term_number, _term);665break;666#if GPS_MOVING_BASELINE667case _GPS_SENTENCE_UNIHEADINGA + 1 ... _GPS_SENTENCE_UNIHEADINGA + 28: // UNIHEADINGA message668parse_uniheadinga_field(_term_number, _term);669break;670#endif671#endif672}673}674675return false;676}677678#if AP_GPS_NMEA_UNICORE_ENABLED679/*680parse an AGRICA message term681682Example:683#AGRICA,82,GPS,FINE,2237,176366400,0,0,18,15;GNSS,232,22,11,22,0,59,8,1,5,8,12,0,0.0000,0.0000,0.0000,0.0000,0.0000,0.0000,296.4656,-26.5685,0.0000,0.005,0.000,0.000,-0.005,0.044,0.032,0.038,-35.33142715815,149.13181842030,609.1494,-4471799.0368,2672944.7758,-3668288.9857,1.3923,1.5128,3.2272,2.3026,2.1633,2.1586,0.00000000000,0.00000000000,0.0000,0.00000000000,0.00000000000,0.0000,176366400,0.000,66.175285,18.972784,0.000000,0.000000,5,0,0,0*9f704dad684*/685void AP_GPS_NMEA::parse_agrica_field(uint16_t term_number, const char *term)686{687auto &ag = _agrica;688// subtract 8 to align term numbers with reference manual689// look for "Unicore Reference Command Manual" to find the specification690const uint8_t hdr_align = 8;691if (term_number < hdr_align) {692// discard header;693return;694}695term_number -= hdr_align;696// useful for debugging697//::printf("AGRICA[%u]=%s\n", unsigned(term_number), term);698switch (term_number) {699case 10:700ag.rtk_status = atol(term);701break;702case 11:703ag.heading_status = atol(term);704break;705case 25 ... 26:706ag.vel_NED[term_number-25] = atof(term);707break;708case 27:709// AGRIC gives velocity up710ag.vel_NED.z = -atof(term);711break;712case 28 ... 30:713ag.vel_stddev[term_number-28] = atof(term);714break;715case 31:716ag.lat = atof(term);717break;718case 32:719ag.lng = atof(term);720break;721case 33:722ag.alt = atof(term);723break;724case 49:725ag.itow = atol(term);726break;727case 37 ... 39:728ag.pos_stddev[term_number-37] = atof(term);729break;730case 52:731ag.undulation = atof(term);732break;733}734}735736#if GPS_MOVING_BASELINE737/*738parse a UNIHEADINGA message term739740Example:741#UNIHEADINGA,79,GPS,FINE,2242,167498200,0,0,18,22;SOL_COMPUTED,L1_INT,2.7889,296.7233,-25.7710,0.0000,0.1127,0.1812,"999",49,37,37,0,3,00,1,51*d50af0ea742*/743void AP_GPS_NMEA::parse_uniheadinga_field(uint16_t term_number, const char *term)744{745const uint8_t hdr_align = 8;746if (term_number < hdr_align) {747// discard header;748return;749}750term_number -= hdr_align;751// useful for debugging752// ::printf("UNIHEADINGA[%u]=%s\n", unsigned(term_number), term);753auto &uh = _uniheadinga;754switch (term_number) {755case 4:756uh.baseline_length = atof(term);757break;758case 5:759uh.heading = atof(term);760break;761case 6:762uh.pitch = atof(term);763break;764case 8:765uh.heading_sd = atof(term);766break;767}768}769#endif // GPS_MOVING_BASELINE770771// parse VERSIONA fields772void AP_GPS_NMEA::parse_versiona_field(uint16_t term_number, const char *term)773{774// printf useful for debugging775// ::printf("VERSIONA[%u]='%s'\n", term_number, term);776auto &v = _versiona;777#pragma GCC diagnostic push778#if defined(__GNUC__) && __GNUC__ >= 9779#pragma GCC diagnostic ignored "-Wstringop-truncation"780#endif781switch (term_number) {782case 10:783strncpy(v.type, _term, sizeof(v.type)-1);784break;785case 11:786strncpy(v.version, _term, sizeof(v.version)-1);787break;788case 15:789strncpy(v.build_date, _term, sizeof(v.build_date)-1);790break;791}792#pragma GCC diagnostic pop793}794#endif // AP_GPS_NMEA_UNICORE_ENABLED795796/*797detect a NMEA GPS. Adds one byte, and returns true if the stream798matches a NMEA string799*/800bool801AP_GPS_NMEA::_detect(struct NMEA_detect_state &state, uint8_t data)802{803switch (state.step) {804case 0:805state.ck = 0;806if ('$' == data) {807state.step++;808}809break;810case 1:811if ('*' == data) {812state.step++;813} else {814state.ck ^= data;815}816break;817case 2:818if (hexdigit(state.ck>>4) == data) {819state.step++;820} else {821state.step = 0;822}823break;824case 3:825if (hexdigit(state.ck&0xF) == data) {826state.step = 0;827return true;828}829state.step = 0;830break;831}832return false;833}834835/*836send type specific config strings837*/838void AP_GPS_NMEA::send_config(void)839{840const auto type = get_type();841_expect_agrica = (type == AP_GPS::GPS_TYPE_UNICORE_NMEA ||842type == AP_GPS::GPS_TYPE_UNICORE_MOVINGBASE_NMEA);843if (gps._auto_config == AP_GPS::GPS_AUTO_CONFIG_DISABLE) {844// not doing auto-config845return;846}847uint32_t now_ms = AP_HAL::millis();848if (now_ms - last_config_ms < AP_GPS_NMEA_CONFIG_PERIOD_MS) {849return;850}851last_config_ms = now_ms;852const uint16_t rate_ms = params.rate_ms;853#if AP_GPS_NMEA_UNICORE_ENABLED854const float rate_s = rate_ms * 0.001;855#endif856const uint8_t rate_hz = 1000U / rate_ms;857858switch (get_type()) {859#if AP_GPS_NMEA_UNICORE_ENABLED860case AP_GPS::GPS_TYPE_UNICORE_MOVINGBASE_NMEA:861port->printf("\r\nCONFIG HEADING FIXLENGTH\r\n" \862"CONFIG UNDULATION AUTO\r\n" \863"CONFIG\r\n" \864"UNIHEADINGA %.3f\r\n",865rate_s);866state.gps_yaw_configured = true;867FALLTHROUGH;868869case AP_GPS::GPS_TYPE_UNICORE_NMEA: {870port->printf("\r\nAGRICA %.3f\r\n" \871"MODE MOVINGBASE\r\n" \872"GNGGA %.3f\r\n" \873"GNRMC %.3f\r\n",874rate_s, rate_s, rate_s);875if (!_have_unicore_versiona) {876// get version information for logging if we don't have it yet877port->printf("VERSIONA\r\n");878if (gps._save_config) {879// save config changes for fast startup880port->printf("SAVECONFIG\r\n");881}882}883break;884}885#endif // AP_GPS_NMEA_UNICORE_ENABLED886887case AP_GPS::GPS_TYPE_HEMI: {888port->printf(889"$JATT,NMEAHE,0\r\n" /* Prefix of GP on the HDT message */ \890"$JASC,GPGGA,%u\r\n" /* GGA at 5Hz */ \891"$JASC,GPRMC,%u\r\n" /* RMC at 5Hz */ \892"$JASC,GPVTG,%u\r\n" /* VTG at 5Hz */ \893"$JASC,GPHDT,%u\r\n" /* HDT at 5Hz */ \894"$JMODE,SBASR,YES\r\n" /* Enable SBAS */,895rate_hz, rate_hz, rate_hz, rate_hz);896break;897}898899case AP_GPS::GPS_TYPE_ALLYSTAR:900nmea_printf(port, "$PHD,06,42,UUUUTTTT,BB,0,%u,55,0,%u,0,0,0",901unsigned(rate_hz), unsigned(rate_ms));902break;903904default:905break;906}907908#ifdef AP_GPS_NMEA_CUSTOM_CONFIG_STRING909// allow for custom config strings, useful for peripherals910port->printf("%s\r\n", AP_GPS_NMEA_CUSTOM_CONFIG_STRING);911#endif912}913914/*915return health status916*/917bool AP_GPS_NMEA::is_healthy(void) const918{919switch (get_type()) {920#if AP_GPS_NMEA_UNICORE_ENABLED921case AP_GPS::GPS_TYPE_UNICORE_MOVINGBASE_NMEA:922case AP_GPS::GPS_TYPE_UNICORE_NMEA:923// we should be getting AGRICA messages924return _last_AGRICA_ms != 0;925#endif // AP_GPS_NMEA_UNICORE_ENABLED926927case AP_GPS::GPS_TYPE_HEMI:928// we should be getting HDR for yaw929return _last_yaw_ms != 0;930931case AP_GPS::GPS_TYPE_ALLYSTAR:932// we should get vertical velocity and accuracy from PHD933return _last_vvelocity_ms != 0 && _last_vaccuracy_ms != 0;934935default:936break;937}938return true;939}940941// get the velocity lag942bool AP_GPS_NMEA::get_lag(float &lag_sec) const943{944switch (get_type()) {945#if AP_GPS_NMEA_UNICORE_ENABLED946case AP_GPS::GPS_TYPE_UNICORE_MOVINGBASE_NMEA:947case AP_GPS::GPS_TYPE_UNICORE_NMEA:948lag_sec = 0.14;949break;950#endif // AP_GPS_NMEA_UNICORE_ENABLED951952default:953lag_sec = 0.2;954break;955}956return true;957}958959#if HAL_LOGGING_ENABLED960void AP_GPS_NMEA::Write_AP_Logger_Log_Startup_messages() const961{962AP_GPS_Backend::Write_AP_Logger_Log_Startup_messages();963#if AP_GPS_NMEA_UNICORE_ENABLED964if (_have_unicore_versiona) {965AP::logger().Write_MessageF("NMEA %u %s %s %s",966state.instance+1,967_versiona.type,968_versiona.version,969_versiona.build_date);970}971#endif972}973#endif974975#endif // AP_GPS_NMEA_ENABLED976977978