Copter: precland: don't use altitude from bad location

This commit is contained in:
Peter Barker 2019-12-02 15:53:59 +11:00 committed by Randy Mackay
parent d332118b05
commit a58813c828
1 changed files with 1 additions and 1 deletions

View File

@ -18,7 +18,7 @@ void Copter::update_precland()
// use range finder altitude if it is valid, else try to get terrain alt
if (rangefinder_alt_ok()) {
height_above_ground_cm = rangefinder_state.alt_cm;
} else if (terrain_use()) {
} else if (terrain_use() && !current_loc.is_zero()) {
if (!current_loc.get_alt_cm(Location::AltFrame::ABOVE_TERRAIN, height_above_ground_cm)) {
height_above_ground_cm = current_loc.alt;
}