Browse Source

autotest: fix airspeed driver test mismatch at end of mission

ground interactions cause fluctuations
master_rangefinder
Peter Barker 2 years ago committed by Peter Barker
parent
commit
7571ef67af
  1. 7
      Tools/autotest/arduplane.py

7
Tools/autotest/arduplane.py

@ -2587,9 +2587,12 @@ function'''
return return
if airspeed[0] is None or airspeed[1] is None: if airspeed[0] is None or airspeed[1] is None:
return 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 not initial_airspeed_threshold_reached:
if (airspeed[0] < 2 or airspeed[1] < 2 and if not (airspeed[0] > 10 or airspeed[1] > 10):
not (airspeed[0] > 10 or airspeed[1] > 10)):
return return
initial_airspeed_threshold_reached = True initial_airspeed_threshold_reached = True
delta = abs(airspeed[0] - airspeed[1]) delta = abs(airspeed[0] - airspeed[1])

Loading…
Cancel
Save