autotest: do no drain mav (i.e. pause sitl) while delaying for sim time

This commit is contained in:
Peter Barker 2022-07-23 11:45:38 +10:00 committed by Peter Barker
parent aeb24d4978
commit f57e3668e3

View File

@ -3223,9 +3223,10 @@ class AutoTest(ABC):
#################################################
# SIM UTILITIES
#################################################
def get_sim_time(self, timeout=60):
def get_sim_time(self, timeout=60, drain_mav=True):
"""Get SITL time in seconds."""
self.drain_mav()
if drain_mav:
self.drain_mav()
tstart = time.time()
while True:
self.drain_all_pexpects()
@ -5626,7 +5627,7 @@ class AutoTest(ABC):
r += " for %s" % reason
self.progress(r % (seconds_to_wait,))
while tstart + seconds_to_wait > tnow:
tnow = self.get_sim_time()
tnow = self.get_sim_time(drain_mav=False)
def get_altitude(self, relative=False, timeout=30):
'''returns vehicles altitude in metres, possibly relative-to-home'''