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

This reverts commit 62fe90bb64.
This commit is contained in:
Randy Mackay 2024-10-07 16:28:51 +09:00
parent 22e8f1e84e
commit 82799a9206
1 changed files with 2 additions and 4 deletions

View File

@ -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);