mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
AP_GPS:Comform to ardupilot undulation definition
This commit is contained in:
parent
eb5e86ecf0
commit
6f38788575
@ -417,7 +417,7 @@ AP_GPS_SBF::process_message(void)
|
||||
state.location.lng = (int32_t)(temp.Longitude * RAD_TO_DEG_DOUBLE * (double)1e7);
|
||||
state.location.alt = (int32_t)(((float)temp.Height - temp.Undulation) * 1e2f);
|
||||
state.have_undulation = true;
|
||||
state.undulation = temp.Undulation;
|
||||
state.undulation = -temp.Undulation;
|
||||
}
|
||||
|
||||
if (temp.NrSV != 255) {
|
||||
|
Loading…
Reference in New Issue
Block a user