diff --git a/ArduCopter/precision_landing.cpp b/ArduCopter/precision_landing.cpp index ea184522c0..0761776678 100644 --- a/ArduCopter/precision_landing.cpp +++ b/ArduCopter/precision_landing.cpp @@ -13,13 +13,8 @@ void Copter::init_precland() void Copter::update_precland() { - int32_t height_above_ground_cm = current_loc.alt; - - // use range finder altitude if it is valid, otherwise use home alt - if (rangefinder_alt_ok()) { - height_above_ground_cm = rangefinder_state.alt_cm_glitch_protected; - } - - precland.update(height_above_ground_cm, rangefinder_alt_ok()); + // alt will be unused if we pass false through as the second parameter: + return precland.update(rangefinder_state.alt_cm_glitch_protected, + rangefinder_alt_ok()); } #endif