mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 15:23:57 -04:00
AP_Terrain: avoid direct use of Location alt field
This commit is contained in:
parent
d24612b4ac
commit
5fe91f16af
@ -247,11 +247,9 @@ void AP_Terrain::send_terrain_report(mavlink_channel_t chan, const Location &loc
|
||||
if (spacing == 0 && !(extrapolate && have_current_loc_height)) {
|
||||
current_height = 0;
|
||||
} else {
|
||||
if (current_loc.relative_alt) {
|
||||
current_height = current_loc.alt*0.01f;
|
||||
} else {
|
||||
current_height = (current_loc.alt - ahrs.get_home().alt)*0.01f;
|
||||
}
|
||||
int32_t height_above_home_cm = 0;
|
||||
UNUSED_RESULT(current_loc.get_alt_cm(Location::AltFrame::ABOVE_HOME, height_above_home_cm));
|
||||
current_height = height_above_home_cm * 0.01f; // cm -> m
|
||||
}
|
||||
current_height += home_terrain_height - terrain_height;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user