mirror of https://github.com/ArduPilot/ardupilot
AC_AttitudeControlHeli: fix althold lean angle max
This commit is contained in:
parent
75c4367cfc
commit
a1548405c1
|
@ -404,6 +404,7 @@ float AC_AttitudeControl_Heli::rate_bf_to_motor_yaw(float rate_target_rads)
|
|||
void AC_AttitudeControl_Heli::set_throttle_out(float throttle_in, bool apply_angle_boost, float filter_cutoff)
|
||||
{
|
||||
_throttle_in = throttle_in;
|
||||
update_althold_lean_angle_max(throttle_in);
|
||||
_motors.set_throttle_filter_cutoff(filter_cutoff);
|
||||
_motors.set_throttle(throttle_in);
|
||||
// Clear angle_boost for logging purposes
|
||||
|
|
Loading…
Reference in New Issue