mirror of https://github.com/ArduPilot/ardupilot
autotest: loosen constrain on proximity distance message
the floating/double changes appear to have cause this to start to flap
This commit is contained in:
parent
fc924857d3
commit
909401b15f
|
@ -7137,6 +7137,7 @@ class AutoTestCopter(AutoTest):
|
||||||
failed = False
|
failed = False
|
||||||
wants = []
|
wants = []
|
||||||
gots = []
|
gots = []
|
||||||
|
epsilon = 20
|
||||||
while True:
|
while True:
|
||||||
if self.get_sim_time_cached() - tstart > 30:
|
if self.get_sim_time_cached() - tstart > 30:
|
||||||
raise AutoTestTimeoutException("Failed to get distances")
|
raise AutoTestTimeoutException("Failed to get distances")
|
||||||
|
@ -7149,7 +7150,7 @@ class AutoTestCopter(AutoTest):
|
||||||
want = expected_distances_copy[m.orientation]
|
want = expected_distances_copy[m.orientation]
|
||||||
wants.append(want)
|
wants.append(want)
|
||||||
gots.append(got)
|
gots.append(got)
|
||||||
if abs(want - got) > 5:
|
if abs(want - got) > epsilon:
|
||||||
failed = True
|
failed = True
|
||||||
del expected_distances_copy[m.orientation]
|
del expected_distances_copy[m.orientation]
|
||||||
if failed:
|
if failed:
|
||||||
|
|
Loading…
Reference in New Issue