From 570c12215dd01c84e1f647b5a5ca6db13fcb351b Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Thu, 9 Sep 2021 10:33:46 +0900 Subject: [PATCH] AR_AttitudeControl: fix get_throttle_out_speed use of passed in limits --- libraries/APM_Control/AR_AttitudeControl.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/APM_Control/AR_AttitudeControl.cpp b/libraries/APM_Control/AR_AttitudeControl.cpp index 8e146bdca6..13ed8d8457 100644 --- a/libraries/APM_Control/AR_AttitudeControl.cpp +++ b/libraries/APM_Control/AR_AttitudeControl.cpp @@ -594,7 +594,7 @@ float AR_AttitudeControl::get_throttle_out_speed(float desired_speed, bool motor } // calculate final output - float throttle_out = _throttle_speed_pid.update_all(desired_speed, speed, (_throttle_limit_low || _throttle_limit_high)); + float throttle_out = _throttle_speed_pid.update_all(desired_speed, speed, (motor_limit_low || motor_limit_high || _throttle_limit_low || _throttle_limit_high)); throttle_out += _throttle_speed_pid.get_ff(); throttle_out += throttle_base;