mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 16:48:29 -04:00
AC_AttitudeControlHeli: fix update_althold_lean_angle_max
This commit is contained in:
parent
096bdd67f8
commit
9bd8878c8b
@ -236,7 +236,7 @@ void AC_AttitudeControl_Heli::rate_controller_run()
|
||||
void AC_AttitudeControl_Heli::update_althold_lean_angle_max(float throttle_in)
|
||||
{
|
||||
float althold_lean_angle_max = acos(constrain_float(_throttle_in/AC_ATTITUDE_CONTROL_ANGLE_LIMIT_THROTTLE_MAX, 0.0f, 1.0f));
|
||||
_althold_lean_angle_max = _althold_lean_angle_max + (_dt/(_dt+_angle_limit_tc))*(_throttle_in-_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