AP_Control: apply pitch rate limit to turn coordination

At high bank angles, for example when rolling to/from inverted, a large turn
coordination pitch rate offset is requested. Before this patch, this offset was
not subject to the configured pitch rate limit, which could result in pitch
controller integrator windup.
This commit is contained in:
Ben Wolsieffer 2021-03-20 16:37:07 -04:00 committed by Andrew Tridgell
parent 9c8648d99c
commit 1d634cc2be
1 changed files with 4 additions and 7 deletions

View File

@ -301,20 +301,17 @@ int32_t AP_PitchController::get_servo_out(int32_t angle_err, float scaler, bool
// as the rates will be tuned when upright, and it is common that // as the rates will be tuned when upright, and it is common that
// much higher rates are needed inverted // much higher rates are needed inverted
if (!inverted) { if (!inverted) {
desired_rate += rate_offset;
if (gains.rmax_neg && desired_rate < -gains.rmax_neg) { if (gains.rmax_neg && desired_rate < -gains.rmax_neg) {
desired_rate = -gains.rmax_neg; desired_rate = -gains.rmax_neg;
} else if (gains.rmax_pos && desired_rate > gains.rmax_pos) { } else if (gains.rmax_pos && desired_rate > gains.rmax_pos) {
desired_rate = gains.rmax_pos; desired_rate = gains.rmax_pos;
} }
} else {
// Make sure not to invert the turn coordination offset
desired_rate = -desired_rate + rate_offset;
} }
if (inverted) {
desired_rate = -desired_rate;
}
// Apply the turn correction offset
desired_rate = desired_rate + rate_offset;
/* /*
when we are past the users defined roll limit for the aircraft when we are past the users defined roll limit for the aircraft
our priority should be to bring the aircraft back within the our priority should be to bring the aircraft back within the