mirror of https://github.com/ArduPilot/ardupilot
Sub: remove angle_boost logic
Most subs are neutrally buoyant, which means this code makes more harm than it is actually useful
This commit is contained in:
parent
830c1a4a3e
commit
e1ec24f25d
|
@ -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)));
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue