AP_GPS: backport to copter 4.5 the correct satellite count for NrSv do-not-use value

This commit is contained in:
Chiara de Saint Giniez 2024-08-09 10:54:36 +02:00 committed by Randy Mackay
parent b43c139752
commit eff242a7c7
1 changed files with 4 additions and 2 deletions

View File

@ -453,8 +453,10 @@ AP_GPS_SBF::process_message(void)
set_alt_amsl_cm(state, ((float)temp.Height - temp.Undulation) * 1e2f); 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); Debug("temp.Mode=0x%02x\n", (unsigned)temp.Mode);