From e569f3878dbc306fe92954e4c3c12324e62df0b2 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Mon, 7 Oct 2024 16:28:51 +0900 Subject: [PATCH] AP_GPS: revert backport to copter 4.5 the correct satellite count for NrSv do-not-use value This reverts commit 62fe90bb64f4a28b9ad180e7dc25d7c92a93d7ad. --- libraries/AP_GPS/AP_GPS_SBF.cpp | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/libraries/AP_GPS/AP_GPS_SBF.cpp b/libraries/AP_GPS/AP_GPS_SBF.cpp index 7cb792b6b9..569d5b6910 100644 --- a/libraries/AP_GPS/AP_GPS_SBF.cpp +++ b/libraries/AP_GPS/AP_GPS_SBF.cpp @@ -453,10 +453,8 @@ AP_GPS_SBF::process_message(void) set_alt_amsl_cm(state, ((float)temp.Height - temp.Undulation) * 1e2f); } - state.num_sats = temp.NrSV; - if (temp.NrSV == 255) { - //Do-Not-Use value for NrSv field in PVTGeodetic message - state.num_sats = 0; + if (temp.NrSV != 255) { + state.num_sats = temp.NrSV; } Debug("temp.Mode=0x%02x\n", (unsigned)temp.Mode);