AC_AttControl: bug fix to angle_boost reporting

Thanks to OXINARF for finding this
This commit is contained in:
Randy Mackay 2016-01-08 10:47:20 +09:00
parent a42b286c01
commit 8c7f36563c

View File

@ -17,8 +17,8 @@ float AC_AttitudeControl_Multi::get_althold_lean_angle_max() const
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