diff --git a/ArduCopter/mode_guided.cpp b/ArduCopter/mode_guided.cpp index e52bfdae310128..04af579f8f3082 100644 --- a/ArduCopter/mode_guided.cpp +++ b/ArduCopter/mode_guided.cpp @@ -961,7 +961,7 @@ void ModeGuided::angle_control_run() // TODO: use get_alt_hold_state // landed with positive desired climb rate, takeoff - if (copter.ap.land_complete && (guided_angle_state.climb_rate_cms > 0.0f)) { + if (copter.ap.land_complete && positive_thrust_or_climbrate) { 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) {