Sub: remove angle_boost logic

This gets in the way of the vectored thrust implemented,
and is just not useful for Sub.
This commit is contained in:
Willian Galvani 2019-09-11 10:57:48 -03:00
parent 5e21690335
commit 89a7089b6f
1 changed files with 0 additions and 7 deletions

View File

@ -297,13 +297,6 @@ void AC_AttitudeControl_Sub::set_throttle_out(float throttle_in, bool apply_angl
_throttle_in = throttle_in;
update_althold_lean_angle_max(throttle_in);
_motors.set_throttle_filter_cutoff(filter_cutoff);
if (apply_angle_boost) {
// Apply angle boost
throttle_in = get_throttle_boosted(throttle_in);
}else{
// Clear angle_boost for logging purposes
_angle_boost = 0.0f;
}
_motors.set_throttle(throttle_in);
_motors.set_throttle_avg_max(get_throttle_avg_max(MAX(throttle_in, _throttle_in)));
}