From c76969365a655ffdaeea9b67347e72c46fc3a291 Mon Sep 17 00:00:00 2001 From: Chiara de Saint Giniez Date: Fri, 9 Aug 2024 10:54:36 +0200 Subject: [PATCH] AP_GPS: backport to copter 4.5 the correct satellite count for NrSv do-not-use value --- libraries/AP_GPS/AP_GPS_SBF.cpp | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/libraries/AP_GPS/AP_GPS_SBF.cpp b/libraries/AP_GPS/AP_GPS_SBF.cpp index 569d5b6910ec4..7cb792b6b94e6 100644 --- a/libraries/AP_GPS/AP_GPS_SBF.cpp +++ b/libraries/AP_GPS/AP_GPS_SBF.cpp @@ -453,8 +453,10 @@ AP_GPS_SBF::process_message(void) set_alt_amsl_cm(state, ((float)temp.Height - temp.Undulation) * 1e2f); } - if (temp.NrSV != 255) { - state.num_sats = temp.NrSV; + state.num_sats = temp.NrSV; + if (temp.NrSV == 255) { + //Do-Not-Use value for NrSv field in PVTGeodetic message + state.num_sats = 0; } Debug("temp.Mode=0x%02x\n", (unsigned)temp.Mode);