From 64360f263cc5dad5a3f992943d5b605fcadc7f40 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Tue, 28 Apr 2020 17:34:32 +0900 Subject: [PATCH] Copter: land detector allows larger lean angle request in land mode --- ArduCopter/land_detector.cpp | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/ArduCopter/land_detector.cpp b/ArduCopter/land_detector.cpp index faf05de5b1..af8cfb5d67 100644 --- a/ArduCopter/land_detector.cpp +++ b/ArduCopter/land_detector.cpp @@ -173,7 +173,10 @@ void Copter::update_throttle_mix() // check for requested decent bool descent_not_demanded = pos_control->get_desired_velocity().z >= 0.0f; - if (large_angle_request || large_angle_error || accel_moving || descent_not_demanded) { + // check if landing + const bool landing = flightmode->is_landing(); + + if ((large_angle_request && !landing) || large_angle_error || accel_moving || descent_not_demanded) { attitude_control->set_throttle_mix_max(pos_control->get_vel_z_control_ratio()); } else { attitude_control->set_throttle_mix_min();