mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-23 09:08:30 -04:00
AC_AttitudeControl: fixed one usage of zero accel limits
in other places zero accel limit means no limit
This commit is contained in:
parent
7479bc5734
commit
58f0abaf4c
@ -549,7 +549,7 @@ void AC_AttitudeControl::update_rate_bf_targets()
|
||||
|
||||
// stab roll calculation
|
||||
// constrain roll rate request
|
||||
if (_flags.limit_angle_to_rate_request) {
|
||||
if (_flags.limit_angle_to_rate_request && _accel_roll_max > 0.0f) {
|
||||
_rate_bf_target.x = sqrt_controller(_angle_bf_error.x, _p_angle_roll.kP(), constrain_float(_accel_roll_max/2.0f, AC_ATTITUDE_ACCEL_RP_CONTROLLER_MIN, AC_ATTITUDE_ACCEL_RP_CONTROLLER_MAX));
|
||||
}else{
|
||||
_rate_bf_target.x = _p_angle_roll.kP() * _angle_bf_error.x;
|
||||
@ -557,7 +557,7 @@ void AC_AttitudeControl::update_rate_bf_targets()
|
||||
|
||||
// stab pitch calculation
|
||||
// constrain pitch rate request
|
||||
if (_flags.limit_angle_to_rate_request) {
|
||||
if (_flags.limit_angle_to_rate_request && _accel_pitch_max > 0.0f) {
|
||||
_rate_bf_target.y = sqrt_controller(_angle_bf_error.y, _p_angle_pitch.kP(), constrain_float(_accel_pitch_max/2.0f, AC_ATTITUDE_ACCEL_RP_CONTROLLER_MIN, AC_ATTITUDE_ACCEL_RP_CONTROLLER_MAX));
|
||||
}else{
|
||||
_rate_bf_target.y = _p_angle_pitch.kP() * _angle_bf_error.y;
|
||||
@ -565,7 +565,7 @@ void AC_AttitudeControl::update_rate_bf_targets()
|
||||
|
||||
// stab yaw calculation
|
||||
// constrain yaw rate request
|
||||
if (_flags.limit_angle_to_rate_request) {
|
||||
if (_flags.limit_angle_to_rate_request && _accel_yaw_max > 0.0f) {
|
||||
_rate_bf_target.z = sqrt_controller(_angle_bf_error.z, _p_angle_yaw.kP(), constrain_float(_accel_yaw_max/2.0f, AC_ATTITUDE_ACCEL_Y_CONTROLLER_MIN, AC_ATTITUDE_ACCEL_Y_CONTROLLER_MAX));
|
||||
}else{
|
||||
_rate_bf_target.z = _p_angle_yaw.kP() * _angle_bf_error.z;
|
||||
|
Loading…
Reference in New Issue
Block a user