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!
This commit is contained in:
Peter Barker 2022-08-22 18:00:07 +10:00 committed by Peter Barker
parent 8a13fb0f6d
commit 8b5afb4a24
1 changed files with 6 additions and 3 deletions

View File

@ -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):