From b9a4902aa6f81dd8cf60e824bc035f241e3b4cb7 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sun, 17 Oct 2021 22:51:15 +1100 Subject: [PATCH] autotest: let system settle before annoying Also fly in circles to avoid long flight home --- Tools/autotest/arduplane.py | 7 +++++-- 1 file changed, 5 insertions(+), 2 deletions(-) diff --git a/Tools/autotest/arduplane.py b/Tools/autotest/arduplane.py index bd812f0915..0a3312acca 100644 --- a/Tools/autotest/arduplane.py +++ b/Tools/autotest/arduplane.py @@ -3143,14 +3143,17 @@ class AutoTestPlane(AutoTest): self.fly_mission("ap-circuit.txt", mission_timeout=1200) def DCMFallback(self): + self.reboot_sitl() + self.delay_sim_time(30) self.wait_ready_to_arm() self.arm_vehicle() self.takeoff(50) + self.change_mode('CIRCLE') self.context_collect('STATUSTEXT') - self.set_parameter("EK3_POS_I_GATE", 25) + self.set_parameter("EK3_POS_I_GATE", 0) self.set_parameter("SIM_GPS_HZ", 1) - self.wait_statustext("DCM Active", check_context=True) + self.wait_statustext("DCM Active", check_context=True, timeout=60) self.wait_statustext("EKF3 Active", check_context=True) self.wait_statustext("DCM Active", check_context=True) self.wait_statustext("EKF3 Active", check_context=True)