From 8b5afb4a24afba85bcbb5dd8801b50683c875efd Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 22 Aug 2022 18:00:07 +1000 Subject: [PATCH] autotest: loop across recv_match in assert_receive_message pymavlink sleeps for half the passed-in timeout which is no good if we are willing to wait for 30 seconds for a message! --- Tools/autotest/common.py | 9 ++++++--- 1 file changed, 6 insertions(+), 3 deletions(-) diff --git a/Tools/autotest/common.py b/Tools/autotest/common.py index f81890ea36..4d434fc427 100644 --- a/Tools/autotest/common.py +++ b/Tools/autotest/common.py @@ -3791,13 +3791,16 @@ class AutoTest(ABC): def assert_receive_message(self, type, timeout=1, verbose=False, very_verbose=False, mav=None): if mav is None: mav = self.mav - m = mav.recv_match(type=type, blocking=True, timeout=timeout) + m = None + tstart = time.time() # timeout in wallclock + while m is None: + m = mav.recv_match(type=type, blocking=True, timeout=0.05) + if time.time() - tstart > timeout: + raise NotAchievedException("Did not get %s" % type) if verbose: self.progress("Received (%s)" % str(m)) if very_verbose: self.progress(self.dump_message_verbose(m)) - if m is None: - raise NotAchievedException("Did not get %s" % type) return m def assert_receive_named_value_float(self, name, timeout=10):