From a1bde16abdf840581fadea8c7d238a5cde394b69 Mon Sep 17 00:00:00 2001 From: Paul Riseborough Date: Sun, 13 Dec 2020 13:14:27 +1100 Subject: [PATCH] Plane: Fix failure to disarm after landing in strong winds --- ArduPlane/is_flying.cpp | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/ArduPlane/is_flying.cpp b/ArduPlane/is_flying.cpp index 5fe09e2e2c..2ddad79c5d 100644 --- a/ArduPlane/is_flying.cpp +++ b/ArduPlane/is_flying.cpp @@ -48,8 +48,9 @@ void Plane::update_is_flying_5Hz(void) // we've flown before, remove GPS constraints temporarily and only use airspeed is_flying_bool = airspeed_movement; // moving through the air } else { - // we've never flown yet, require good GPS movement - is_flying_bool = airspeed_movement || // moving through the air + // Because ahrs.airspeed_estimate can return a continued high value after landing if flying in + // strong winds above stall speed it is necessary to include the IMU based movement check. + is_flying_bool = (airspeed_movement && !AP::ins().is_still()) || // moving through the air gps_confirmed_movement; // locked and we're moving }