From 4cc92c6b3ed8686d2eaad7c324dd9199aee52701 Mon Sep 17 00:00:00 2001 From: Samuel Tabor Date: Tue, 13 Apr 2021 21:53:07 +0100 Subject: [PATCH] Plane: Constrain target_airspeed_cm by min as well as max airspeed. --- ArduPlane/navigation.cpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/ArduPlane/navigation.cpp b/ArduPlane/navigation.cpp index 9d37d7f8dc..45b8a5914d 100644 --- a/ArduPlane/navigation.cpp +++ b/ArduPlane/navigation.cpp @@ -238,8 +238,7 @@ void Plane::calc_airspeed_errors() } // Apply airspeed limit - if (target_airspeed_cm > (aparm.airspeed_max * 100)) - target_airspeed_cm = (aparm.airspeed_max * 100); + target_airspeed_cm = constrain_int32(target_airspeed_cm, aparm.airspeed_min*100, aparm.airspeed_max*100); // use the TECS view of the target airspeed for reporting, to take // account of the landing speed