From 6fc40867261a26e3858d0df77400384ad82d39f4 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 25 Feb 2019 14:05:09 +1100 Subject: [PATCH] Tools: autotest: accept home position before or after ack autopilot may be out of space or time to send home position packet after we have requested it --- Tools/autotest/common.py | 12 ++++++++---- 1 file changed, 8 insertions(+), 4 deletions(-) diff --git a/Tools/autotest/common.py b/Tools/autotest/common.py index da78ea2e7e..fe19f4545d 100644 --- a/Tools/autotest/common.py +++ b/Tools/autotest/common.py @@ -1689,6 +1689,7 @@ class AutoTest(ABC): while True: if self.get_sim_time() - tstart > 30: raise NotAchievedException("Failed to poll home position") + self.progress("Sending MAV_CMD_GET_HOME_POSITION") try: self.run_cmd( mavutil.mavlink.MAV_CMD_GET_HOME_POSITION, @@ -1701,10 +1702,13 @@ class AutoTest(ABC): 0) except ValueError as e: continue - break - m = self.mav.messages.get("HOME_POSITION", None) - if old is not None and m._timestamp == old._timestamp: - raise NotAchievedException("home position not updated") + m = self.mav.messages.get("HOME_POSITION", None) + if m is None: + continue + if old is None: + break + if m._timestamp != old._timestamp: + break return m def distance_to_home(self):