mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 01:18:29 -04:00
AC_AttitudeControl: constrain _angle_boost to avoid overflow
This commit is contained in:
parent
fdf226ebc1
commit
ab2532a609
@ -734,7 +734,7 @@ float AC_AttitudeControl::get_boosted_throttle(float throttle_in)
|
||||
float boost_factor = 1.0f/constrain_float(cos_tilt, 0.5f, 1.0f);
|
||||
|
||||
float throttle_out = (throttle_in-min_throttle)*inverted_factor*boost_factor + min_throttle;
|
||||
_angle_boost = throttle_out - throttle_in;
|
||||
_angle_boost = constrain_float(throttle_out - throttle_in,-32000,32000);
|
||||
return throttle_out;
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user