Plane: don't allow a zero speed_scaler

this fixes an issue with yaw damper on quadplanes when at zero
airspeed

Thanks to Vladi Portnoy for reporting this
This commit is contained in:
Andrew Tridgell 2020-06-22 14:45:50 +10:00 committed by Peter Barker
parent edba1cca4a
commit d9358b4ac2
1 changed files with 1 additions and 1 deletions

View File

@ -26,7 +26,7 @@ float Plane::get_speed_scaler(void)
// when in VTOL modes limit surface movement at low speed to prevent instability
float threshold = aparm.airspeed_min * 0.5;
if (aspeed < threshold) {
float new_scaler = linear_interpolate(0, g.scaling_speed / threshold, aspeed, 0, threshold);
float new_scaler = linear_interpolate(0.001, 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