autotest: read pexpects while waiting for sim time

If we do not drain pexpects regularly the ardupilot process can become blocked on terminal IO
This commit is contained in:
Peter Barker 2021-11-06 23:57:31 +11:00 committed by Peter Barker
parent 0f1d3c4fc4
commit 2dd392ec4b
1 changed files with 11 additions and 4 deletions

View File

@ -2761,10 +2761,17 @@ class AutoTest(ABC):
def get_sim_time(self, timeout=60):
"""Get SITL time in seconds."""
self.drain_mav()
m = self.mav.recv_match(type='SYSTEM_TIME', blocking=True, timeout=timeout)
if m is None:
raise AutoTestTimeoutException("Did not get SYSTEM_TIME message after %f seconds" % timeout)
return m.time_boot_ms * 1.0e-3
tstart = time.time()
while True:
self.drain_all_pexpects()
if time.time() - tstart > timeout:
raise AutoTestTimeoutException("Did not get SYSTEM_TIME message after %f seconds" % timeout)
m = self.mav.recv_match(type='SYSTEM_TIME', blocking=True, timeout=0.1)
if m is None:
continue
return m.time_boot_ms * 1.0e-3
def get_sim_time_cached(self):
"""Get SITL time in seconds."""