From de3c9340cb7a1c7dac9c03f41d51932e1746fff3 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 19 Sep 2019 18:58:23 +1000 Subject: [PATCH] Tools: autotest: correct timeout on heli spline mission --- Tools/autotest/arducopter.py | 7 +++---- 1 file changed, 3 insertions(+), 4 deletions(-) diff --git a/Tools/autotest/arducopter.py b/Tools/autotest/arducopter.py index d4d36cc0ea..2c618adee8 100644 --- a/Tools/autotest/arducopter.py +++ b/Tools/autotest/arducopter.py @@ -3909,7 +3909,7 @@ class AutoTestHeli(AutoTestCopter): if ex is not None: raise ex - def fly_spline_waypoint(self): + def fly_spline_waypoint(self, timeout=600): """ensure basic spline functionality works""" self.load_mission("copter_spline_mission.txt") self.change_mode("LOITER") @@ -3922,11 +3922,10 @@ class AutoTestHeli(AutoTestCopter): self.set_rc(3, 1500) tstart = self.get_sim_time() while True: + if self.get_sim_time() - tstart > timeout: + raise AutoTestTimeoutException("Vehicle did not disarm after mission") if not self.armed(): break - remaining = self.get_sim_time() - tstart - if remaining <= 0: - raise AutoTestTimeoutException("Vehicle did not disarm after mission") self.delay_sim_time(1) self.progress("Lowering rotor speed") self.set_rc(8, 1000)