From d9358b4ac26b90d9ceef749708b747c1b3b1f3a0 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 22 Jun 2020 14:45:50 +1000 Subject: [PATCH] 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 --- ArduPlane/Attitude.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduPlane/Attitude.cpp b/ArduPlane/Attitude.cpp index 09dcb0b11e..0c0dd458e9 100644 --- a/ArduPlane/Attitude.cpp +++ b/ArduPlane/Attitude.cpp @@ -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