diff --git a/ArduCopter/precision_landing.cpp b/ArduCopter/precision_landing.cpp index 10fb230635..769bf69bc0 100644 --- a/ArduCopter/precision_landing.cpp +++ b/ArduCopter/precision_landing.cpp @@ -15,13 +15,15 @@ void Copter::init_precland() void Copter::update_precland() { - float final_alt = current_loc.alt; + int32_t height_above_ground_cm = current_loc.alt; - // use range finder altitude if it is valid + // use range finder altitude if it is valid, else try to get terrain alt if (rangefinder_alt_ok()) { - final_alt = rangefinder_state.alt_cm; + height_above_ground_cm = rangefinder_state.alt_cm; + } else if (terrain_use()) { + current_loc.get_alt_cm(Location_Class::ALT_FRAME_ABOVE_TERRAIN, height_above_ground_cm); } - copter.precland.update(final_alt); + copter.precland.update(height_above_ground_cm); } #endif