mirror of https://github.com/ArduPilot/ardupilot
AP_GPS_SBF: change reported altitude from geoid to MSL
This commit is contained in:
parent
04c76843fc
commit
5e63abf431
|
@ -237,7 +237,7 @@ AP_GPS_SBF::process_message(void)
|
|||
if (temp.Latitude > -200000) {
|
||||
state.location.lat = (int32_t)(temp.Latitude * RAD_TO_DEG_DOUBLE * 1e7);
|
||||
state.location.lng = (int32_t)(temp.Longitude * RAD_TO_DEG_DOUBLE * 1e7);
|
||||
state.location.alt = (int32_t)((float)temp.Height * 1e2f);
|
||||
state.location.alt = (int32_t)(((float)temp.Height - temp.Undulation) * 1e2f );
|
||||
}
|
||||
|
||||
if (temp.NrSV != 255) {
|
||||
|
|
Loading…
Reference in New Issue