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