mirror of https://github.com/ArduPilot/ardupilot
AP_GPS: backport to copter 4.5 the correct satellite count for NrSv do-not-use value
This commit is contained in:
parent
b43c139752
commit
eff242a7c7
|
@ -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);
|
||||||
|
|
Loading…
Reference in New Issue