From 7571ef67af389a17b5f0738d85dfe92a00104791 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 29 Aug 2022 09:55:41 +1000 Subject: [PATCH] autotest: fix airspeed driver test mismatch at end of mission ground interactions cause fluctuations --- Tools/autotest/arduplane.py | 7 +++++-- 1 file changed, 5 insertions(+), 2 deletions(-) diff --git a/Tools/autotest/arduplane.py b/Tools/autotest/arduplane.py index d3c6b3da79..00ab7550de 100644 --- a/Tools/autotest/arduplane.py +++ b/Tools/autotest/arduplane.py @@ -2587,9 +2587,12 @@ function''' return if airspeed[0] is None or airspeed[1] is None: return + if airspeed[0] < 2 or airspeed[1] < 2: + # this mismatch can occur on takeoff, or when we + # smack into the ground at the end of the mission + return if not initial_airspeed_threshold_reached: - if (airspeed[0] < 2 or airspeed[1] < 2 and - not (airspeed[0] > 10 or airspeed[1] > 10)): + if not (airspeed[0] > 10 or airspeed[1] > 10): return initial_airspeed_threshold_reached = True delta = abs(airspeed[0] - airspeed[1])