mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
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:
parent
7b5ef6df77
commit
131e04e6a9
@ -453,10 +453,8 @@ 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);
|
||||||
|
Loading…
Reference in New Issue
Block a user