mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 13:38:38 -04:00
autotest: fix airspeed driver test mismatch at end of mission
ground interactions cause fluctuations
This commit is contained in:
parent
a7aa5b6897
commit
7571ef67af
@ -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])
|
||||
|
Loading…
Reference in New Issue
Block a user