From b24a6fe15f642bd12db08120a2968ee22b7fe5c1 Mon Sep 17 00:00:00 2001 From: Bill Geyer Date: Sat, 21 Jan 2023 22:33:21 -0500 Subject: [PATCH] Copter: fix landing detector for autorotation --- ArduCopter/land_detector.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/ArduCopter/land_detector.cpp b/ArduCopter/land_detector.cpp index 69b65b88dc..c6b038c4a7 100644 --- a/ArduCopter/land_detector.cpp +++ b/ArduCopter/land_detector.cpp @@ -73,6 +73,9 @@ void Copter::update_land_detector() // 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) +#if MODE_AUTOROTATE_ENABLED == ENABLED + || (flightmode->mode_number() == Mode::Number::AUTOROTATE && motors->get_below_land_min_coll()) +#endif || ((!force_flying || landing) && motors->limit.throttle_lower && pos_control->get_vel_desired_cms().z < 0.0f); bool throttle_mix_at_min = true; #else