mirror of https://github.com/ArduPilot/ardupilot
Plane: decay fw rate integrators when at low airspeed
this prevents large fixed wing control surface integrators from causing issues when we have wind from behind in hover
This commit is contained in:
parent
05bd0cb9f4
commit
aa18c75689
|
@ -28,6 +28,12 @@ float Plane::get_speed_scaler(void)
|
|||
if (aspeed < threshold) {
|
||||
float new_scaler = linear_interpolate(0, g.scaling_speed / threshold, aspeed, 0, threshold);
|
||||
speed_scaler = MIN(speed_scaler, new_scaler);
|
||||
|
||||
// we also decay the integrator to prevent an integrator from before
|
||||
// we were at low speed persistint at high speed
|
||||
rollController.decay_I();
|
||||
pitchController.decay_I();
|
||||
yawController.decay_I();
|
||||
}
|
||||
}
|
||||
} else if (hal.util->get_soft_armed()) {
|
||||
|
|
Loading…
Reference in New Issue