mirror of https://github.com/ArduPilot/ardupilot
AC_AttControl: reduce max_rate_step based on hover throttle
This changes reduces AutoTune's twitch size based on the hover throttle This method is only used by AutoTune
This commit is contained in:
parent
0051ecb288
commit
29d4790fc7
|
@ -738,7 +738,7 @@ float AC_AttitudeControl::max_rate_step_bf_roll()
|
|||
{
|
||||
float alpha = get_rate_roll_pid().get_filt_alpha();
|
||||
float alpha_remaining = 1-alpha;
|
||||
return AC_ATTITUDE_RATE_RP_CONTROLLER_OUT_MAX/((alpha_remaining*alpha_remaining*alpha_remaining*alpha*get_rate_roll_pid().kD())/_dt + get_rate_roll_pid().kP());
|
||||
return 2.0f*_motors.get_throttle_hover()*AC_ATTITUDE_RATE_RP_CONTROLLER_OUT_MAX/((alpha_remaining*alpha_remaining*alpha_remaining*alpha*get_rate_roll_pid().kD())/_dt + get_rate_roll_pid().kP());
|
||||
}
|
||||
|
||||
// Return pitch rate step size in centidegrees/s that results in maximum output after 4 time steps
|
||||
|
@ -746,7 +746,7 @@ float AC_AttitudeControl::max_rate_step_bf_pitch()
|
|||
{
|
||||
float alpha = get_rate_pitch_pid().get_filt_alpha();
|
||||
float alpha_remaining = 1-alpha;
|
||||
return AC_ATTITUDE_RATE_RP_CONTROLLER_OUT_MAX/((alpha_remaining*alpha_remaining*alpha_remaining*alpha*get_rate_pitch_pid().kD())/_dt + get_rate_pitch_pid().kP());
|
||||
return 2.0f*_motors.get_throttle_hover()*AC_ATTITUDE_RATE_RP_CONTROLLER_OUT_MAX/((alpha_remaining*alpha_remaining*alpha_remaining*alpha*get_rate_pitch_pid().kD())/_dt + get_rate_pitch_pid().kP());
|
||||
}
|
||||
|
||||
// Return yaw rate step size in centidegrees/s that results in maximum output after 4 time steps
|
||||
|
@ -754,5 +754,5 @@ float AC_AttitudeControl::max_rate_step_bf_yaw()
|
|||
{
|
||||
float alpha = get_rate_yaw_pid().get_filt_alpha();
|
||||
float alpha_remaining = 1-alpha;
|
||||
return AC_ATTITUDE_RATE_RP_CONTROLLER_OUT_MAX/((alpha_remaining*alpha_remaining*alpha_remaining*alpha*get_rate_yaw_pid().kD())/_dt + get_rate_yaw_pid().kP());
|
||||
return 2.0f*_motors.get_throttle_hover()*AC_ATTITUDE_RATE_RP_CONTROLLER_OUT_MAX/((alpha_remaining*alpha_remaining*alpha_remaining*alpha*get_rate_yaw_pid().kD())/_dt + get_rate_yaw_pid().kP());
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue