Skip to content

Commit

Permalink
autotest: loosen constrain on proximity distance message
Browse files Browse the repository at this point in the history
the floating/double changes appear to have cause this to start to flap
  • Loading branch information
peterbarker committed Sep 13, 2023
1 parent fc92485 commit 909401b
Showing 1 changed file with 2 additions and 1 deletion.
3 changes: 2 additions & 1 deletion Tools/autotest/arducopter.py
Original file line number Diff line number Diff line change
Expand Up @@ -7137,6 +7137,7 @@ def ProximitySensors(self):
failed = False
wants = []
gots = []
epsilon = 20
while True:
if self.get_sim_time_cached() - tstart > 30:
raise AutoTestTimeoutException("Failed to get distances")
Expand All @@ -7149,7 +7150,7 @@ def ProximitySensors(self):
want = expected_distances_copy[m.orientation]
wants.append(want)
gots.append(got)
if abs(want - got) > 5:
if abs(want - got) > epsilon:
failed = True
del expected_distances_copy[m.orientation]
if failed:
Expand Down

0 comments on commit 909401b

Please sign in to comment.