From 0cd5bdebfbdd0fa826978d590d60b53164fd2dab Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Tue, 15 Feb 2022 09:15:07 +1100 Subject: [PATCH] autotest: reduce Copter speed requirement in DO_CHANGE_SPEED --- Tools/autotest/ArduCopter_Tests/DO_CHANGE_SPEED/mission.txt | 2 +- Tools/autotest/arducopter.py | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Tools/autotest/ArduCopter_Tests/DO_CHANGE_SPEED/mission.txt b/Tools/autotest/ArduCopter_Tests/DO_CHANGE_SPEED/mission.txt index a5cf57476d..f4ef0ef2a1 100644 --- a/Tools/autotest/ArduCopter_Tests/DO_CHANGE_SPEED/mission.txt +++ b/Tools/autotest/ArduCopter_Tests/DO_CHANGE_SPEED/mission.txt @@ -6,6 +6,6 @@ QGC WPL 110 4 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.360174 149.167908 14.000000 1 5 0 0 178 1.000000 10.000000 0.000000 0.000000 0.000000 0.000000 0.000000 1 6 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.363296 149.169244 18.000000 1 -7 0 0 178 1.000000 17.000000 0.000000 0.000000 0.000000 0.000000 0.000000 1 +7 0 0 178 1.000000 16.000000 0.000000 0.000000 0.000000 0.000000 0.000000 1 8 0 3 16 0.000000 0.000000 0.000000 0.000000 -35.364115 149.165747 20.000000 1 9 0 0 20 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 0.000000 1 diff --git a/Tools/autotest/arducopter.py b/Tools/autotest/arducopter.py index e7828b4552..f30972e1d3 100644 --- a/Tools/autotest/arducopter.py +++ b/Tools/autotest/arducopter.py @@ -7773,7 +7773,7 @@ class AutoTestCopter(AutoTest): self.set_parameter("ANGLE_MAX", 6000) self.wait_current_waypoint(6) self.wait_groundspeed( - 16.5, 18.5, + 15.5, 16.5, minimum_duration=10, timeout=60, )