From 19f6b2d6d644fadafcbb87dd6490d62c6d956047 Mon Sep 17 00:00:00 2001 From: Paul Riseborough Date: Thu, 28 Sep 2023 09:26:10 +1000 Subject: [PATCH] Tools: relax req accuracy for plane dead reckoning when not using airspeed --- Tools/autotest/arduplane.py | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/Tools/autotest/arduplane.py b/Tools/autotest/arduplane.py index adce4c66d8..8601f6b171 100644 --- a/Tools/autotest/arduplane.py +++ b/Tools/autotest/arduplane.py @@ -2155,7 +2155,10 @@ class AutoTestPlane(vehicle_test_suite.TestSuite): if self.simstate is None: return divergence = self.get_distance_int(self.gpi, self.simstate) - max_allowed_divergence = 200 + if disable_airspeed_sensor: + max_allowed_divergence = 300 + else: + max_allowed_divergence = 150 if (time.time() - self.last_print > 1 or divergence > self.max_divergence): self.progress("position-estimate-divergence=%fm" % (divergence,))