From cafc5b01f472f2e392f61b71f4036af913b53936 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 28 Aug 2020 22:10:09 +1000 Subject: [PATCH] autotest: fix race condition in Rover RTL test --- Tools/autotest/rover.py | 15 +++++++++++++-- 1 file changed, 13 insertions(+), 2 deletions(-) diff --git a/Tools/autotest/rover.py b/Tools/autotest/rover.py index 3d7f5c8909..8ef5990473 100644 --- a/Tools/autotest/rover.py +++ b/Tools/autotest/rover.py @@ -467,13 +467,24 @@ Brakes have negligible effect (with=%0.2fm without=%0.2fm delta=%0.2fm) '''maximum distance allowed from home at end''' return 6.5 - def drive_rtl_mission(self): + def drive_rtl_mission(self, timeout=120): self.wait_ready_to_arm() self.arm_vehicle() self.load_mission("rtl.txt") self.change_mode("AUTO") - self.mavproxy.expect('Mission: 3 RTL') + + tstart = self.get_sim_time() + while True: + now = self.get_sim_time_cached() + if now - tstart > timeout: + raise AutoTestTimeoutException("Didn't see wp 3") + m = self.mav.recv_match(type='MISSION_CURRENT', + blocking=True, + timeout=1) + self.progress("MISSION_CURRENT: %s" % str(m)) + if m.seq == 3: + break self.drain_mav();