diff --git a/ArduCopter/land_detector.cpp b/ArduCopter/land_detector.cpp index 4a4a672031..e8690b6c70 100644 --- a/ArduCopter/land_detector.cpp +++ b/ArduCopter/land_detector.cpp @@ -65,8 +65,11 @@ void Copter::update_land_detector() // because multi's use throttle), check that collective pitch is below land min collective position or throttle stick is zero. // Including the throttle zero check will ensure the conditions where stabilize stick zero position was not below collective min. For modes // that use altitude hold, check that the pilot is commanding a descent and collective is at min allowed for altitude hold modes. - bool motor_at_lower_limit = ((flightmode->has_manual_throttle() && (motors->get_below_land_min_coll() || heli_flags.coll_stk_low) && - fabsf(ahrs.get_roll()) < M_PI/2.0f) || (motors->limit.throttle_lower && pos_control->get_vel_desired_cms().z < 0.0f)); + + // check if landing + const bool landing = flightmode->is_landing(); + bool motor_at_lower_limit = (flightmode->has_manual_throttle() && (motors->get_below_land_min_coll() || heli_flags.coll_stk_low) && fabsf(ahrs.get_roll()) < M_PI/2.0f) + || ((!force_flying || landing) && motors->limit.throttle_lower && pos_control->get_vel_desired_cms().z < 0.0f); #else // check that the average throttle output is near minimum (less than 12.5% hover throttle) bool motor_at_lower_limit = motors->limit.throttle_lower && attitude_control->is_throttle_mix_min();