mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-08 17:03:57 -04:00
autotest: do no drain mav (i.e. pause sitl) while delaying for sim time
This commit is contained in:
parent
aeb24d4978
commit
f57e3668e3
@ -3223,8 +3223,9 @@ class AutoTest(ABC):
|
|||||||
#################################################
|
#################################################
|
||||||
# SIM UTILITIES
|
# SIM UTILITIES
|
||||||
#################################################
|
#################################################
|
||||||
def get_sim_time(self, timeout=60):
|
def get_sim_time(self, timeout=60, drain_mav=True):
|
||||||
"""Get SITL time in seconds."""
|
"""Get SITL time in seconds."""
|
||||||
|
if drain_mav:
|
||||||
self.drain_mav()
|
self.drain_mav()
|
||||||
tstart = time.time()
|
tstart = time.time()
|
||||||
while True:
|
while True:
|
||||||
@ -5626,7 +5627,7 @@ class AutoTest(ABC):
|
|||||||
r += " for %s" % reason
|
r += " for %s" % reason
|
||||||
self.progress(r % (seconds_to_wait,))
|
self.progress(r % (seconds_to_wait,))
|
||||||
while tstart + seconds_to_wait > tnow:
|
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):
|
def get_altitude(self, relative=False, timeout=30):
|
||||||
'''returns vehicles altitude in metres, possibly relative-to-home'''
|
'''returns vehicles altitude in metres, possibly relative-to-home'''
|
||||||
|
Loading…
Reference in New Issue
Block a user