From 9cc494bdc2052a452d424425724af649ced4d159 Mon Sep 17 00:00:00 2001 From: Bill Geyer Date: Wed, 20 Mar 2024 11:37:24 -0400 Subject: [PATCH] AC_AttitudeControl: only allow angle boost when not autorotating --- libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.cpp b/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.cpp index e1c276d2b2af77..1881f6f2d1ac98 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.cpp +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.cpp @@ -540,7 +540,7 @@ void AC_AttitudeControl_Heli::set_throttle_out(float throttle_in, bool apply_ang update_althold_lean_angle_max(throttle_in); _motors.set_throttle_filter_cutoff(filter_cutoff); - if (apply_angle_boost) { + if (apply_angle_boost && !((AP_MotorsHeli&)_motors).get_in_autorotation()) { // Apply angle boost throttle_in = get_throttle_boosted(throttle_in); } else {