diff --git a/ArduCopter/mode_guided.cpp b/ArduCopter/mode_guided.cpp index 04b010f262..7ee4b2b671 100644 --- a/ArduCopter/mode_guided.cpp +++ b/ArduCopter/mode_guided.cpp @@ -606,17 +606,6 @@ void ModeGuided::accel_control_run() } } - // landed with positive desired climb rate, initiate takeoff - if (motors->armed() && copter.ap.auto_armed && copter.ap.land_complete && is_positive(guided_vel_target_cms.z)) { - zero_throttle_and_relax_ac(); - motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED); - if (motors->get_spool_state() == AP_Motors::SpoolState::THROTTLE_UNLIMITED) { - set_land_complete(false); - set_throttle_takeoff(); - } - return; - } - // if not armed set throttle to zero and exit immediately if (is_disarmed_or_landed()) { make_safe_spool_down(); @@ -677,17 +666,6 @@ void ModeGuided::velaccel_control_run() } } - // landed with positive desired climb rate, initiate takeoff - if (motors->armed() && copter.ap.auto_armed && copter.ap.land_complete && is_positive(guided_vel_target_cms.z)) { - zero_throttle_and_relax_ac(); - motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED); - if (motors->get_spool_state() == AP_Motors::SpoolState::THROTTLE_UNLIMITED) { - set_land_complete(false); - set_throttle_takeoff(); - } - return; - } - // if not armed set throttle to zero and exit immediately if (is_disarmed_or_landed()) { make_safe_spool_down();