mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 08:38:36 -04:00
AC_AttitudeControlHeli: fix update_althold_lean_angle_max use of throttle_in
This commit is contained in:
parent
3c8aa955d5
commit
84e6c59fdd
@ -325,7 +325,7 @@ void AC_AttitudeControl_Heli::rate_controller_run()
|
|||||||
// Update Alt_Hold angle maximum
|
// Update Alt_Hold angle maximum
|
||||||
void AC_AttitudeControl_Heli::update_althold_lean_angle_max(float throttle_in)
|
void AC_AttitudeControl_Heli::update_althold_lean_angle_max(float throttle_in)
|
||||||
{
|
{
|
||||||
float althold_lean_angle_max = acosf(constrain_float(_throttle_in / AC_ATTITUDE_HELI_ANGLE_LIMIT_THROTTLE_MAX, 0.0f, 1.0f));
|
float althold_lean_angle_max = acosf(constrain_float(throttle_in / AC_ATTITUDE_HELI_ANGLE_LIMIT_THROTTLE_MAX, 0.0f, 1.0f));
|
||||||
_althold_lean_angle_max = _althold_lean_angle_max + (_dt / (_dt + _angle_limit_tc)) * (althold_lean_angle_max - _althold_lean_angle_max);
|
_althold_lean_angle_max = _althold_lean_angle_max + (_dt / (_dt + _angle_limit_tc)) * (althold_lean_angle_max - _althold_lean_angle_max);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user