From ca2977decfdf4225b1e84f67731742c9ddaf6a70 Mon Sep 17 00:00:00 2001 From: Leonard Hall Date: Sun, 22 May 2016 20:54:04 +0930 Subject: [PATCH] AC_AttitudeControl: set throttle vs attitude priority for flipped state When performing a flip we want to allow throttle to go high to provide maximum attitude control --- libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.cpp b/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.cpp index e5e13ac11f..d7afb1c3a4 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.cpp +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.cpp @@ -174,7 +174,7 @@ void AC_AttitudeControl_Multi::set_throttle_out(float throttle_in, bool apply_an _angle_boost = 0.0f; } _motors.set_throttle(throttle_in); - _motors.set_throttle_ave_max(get_throttle_ave_max(throttle_in)); + _motors.set_throttle_ave_max(get_throttle_ave_max(MAX(throttle_in, _throttle_in))); } // returns a throttle including compensation for roll/pitch angle