From 5b765ef0d9eace32a94a1b4a66a022655f647dae Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Fri, 8 Jan 2016 10:47:20 +0900 Subject: [PATCH] AC_AttControl: bug fix to angle_boost reporting Thanks to OXINARF for finding this --- 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 a7f23210c9..9ac616ead8 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.cpp +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.cpp @@ -9,8 +9,8 @@ float AC_AttitudeControl_Multi::get_boosted_throttle(float throttle_in) { if (!_angle_boost_enabled) { - return throttle_in; _angle_boost = 0; + return throttle_in; } // inverted_factor is 1 for tilt angles below 60 degrees // reduces as a function of angle beyond 60 degrees