From d2d6dc8ce44a3a687b7167c3ddfd544eecad9a45 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 24 Nov 2022 08:45:28 +1100 Subject: [PATCH] AP_GPS: only give time if we have a 3D fix and ensure we configure rate for GGA and RMC for Unicore --- libraries/AP_GPS/AP_GPS_NMEA.cpp | 9 +++++++-- 1 file changed, 7 insertions(+), 2 deletions(-) diff --git a/libraries/AP_GPS/AP_GPS_NMEA.cpp b/libraries/AP_GPS/AP_GPS_NMEA.cpp index 156dcb35c8..80469c0b7b 100644 --- a/libraries/AP_GPS/AP_GPS_NMEA.cpp +++ b/libraries/AP_GPS/AP_GPS_NMEA.cpp @@ -309,7 +309,9 @@ bool AP_GPS_NMEA::_term_complete() state.ground_speed = _new_speed*0.01f; state.ground_course = wrap_360(_new_course*0.01f); } - make_gps_time(_new_date, _new_time * 10); + if (state.status >= AP_GPS::GPS_OK_FIX_3D) { + make_gps_time(_new_date, _new_time * 10); + } set_uart_timestamp(_sentence_length); state.last_gps_time_ms = now; if (_last_vvelocity_ms == 0 || @@ -759,7 +761,10 @@ void AP_GPS_NMEA::send_config(void) FALLTHROUGH; case AP_GPS::GPS_TYPE_UNICORE_NMEA: { - port->printf("\r\nAGRICA %.3f\r\n", rate_s); + port->printf("\r\nAGRICA %.3f\r\n" \ + "GNGGA %.3f\r\n" \ + "GNRMC %.3f\r\n", + rate_s, rate_s, rate_s); _expect_agrica = true; break; }