mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 09:28:31 -04:00
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:
parent
0f1d3c4fc4
commit
2dd392ec4b
@ -2761,9 +2761,16 @@ class AutoTest(ABC):
|
|||||||
def get_sim_time(self, timeout=60):
|
def get_sim_time(self, timeout=60):
|
||||||
"""Get SITL time in seconds."""
|
"""Get SITL time in seconds."""
|
||||||
self.drain_mav()
|
self.drain_mav()
|
||||||
m = self.mav.recv_match(type='SYSTEM_TIME', blocking=True, timeout=timeout)
|
tstart = time.time()
|
||||||
if m is None:
|
while True:
|
||||||
|
self.drain_all_pexpects()
|
||||||
|
if time.time() - tstart > timeout:
|
||||||
raise AutoTestTimeoutException("Did not get SYSTEM_TIME message after %f seconds" % 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
|
return m.time_boot_ms * 1.0e-3
|
||||||
|
|
||||||
def get_sim_time_cached(self):
|
def get_sim_time_cached(self):
|
||||||
|
Loading…
Reference in New Issue
Block a user