mirror of https://github.com/ArduPilot/ardupilot
autotest: allow a test to override speedup
This is a crutch for poorly-behaving tests.
This commit is contained in:
parent
e92d4c6fc5
commit
d555c49230
|
@ -1434,11 +1434,12 @@ class LocationInt(object):
|
|||
|
||||
class Test(object):
|
||||
'''a test definition - information about a test'''
|
||||
def __init__(self, name, description, function, attempts=1):
|
||||
def __init__(self, name, description, function, attempts=1, speedup=None):
|
||||
self.name = name
|
||||
self.description = description
|
||||
self.function = function
|
||||
self.attempts = attempts
|
||||
self.speedup = speedup
|
||||
|
||||
|
||||
class AutoTest(ABC):
|
||||
|
@ -7120,6 +7121,8 @@ Also, ignores heartbeats not from our target system'''
|
|||
|
||||
start_time = time.time()
|
||||
|
||||
orig_speedup = None
|
||||
|
||||
ex = None
|
||||
try:
|
||||
self.check_rc_defaults()
|
||||
|
@ -7129,6 +7132,10 @@ Also, ignores heartbeats not from our target system'''
|
|||
self.set_current_waypoint(0, check_afterwards=False)
|
||||
self.drain_mav()
|
||||
self.drain_all_pexpects()
|
||||
if test.speedup is not None:
|
||||
self.progress("Overriding speedup to %u" % test.speedup)
|
||||
orig_speedup = self.get_parameter("SIM_SPEEDUP")
|
||||
self.set_parameter("SIM_SPEEDUP", test.speedup)
|
||||
|
||||
test_function()
|
||||
except Exception as e:
|
||||
|
@ -7142,6 +7149,9 @@ Also, ignores heartbeats not from our target system'''
|
|||
self.test_timings[desc] = time.time() - start_time
|
||||
reset_needed = self.contexts[-1].sitl_commandline_customised
|
||||
|
||||
if orig_speedup is not None:
|
||||
self.set_parameter("SIM_SPEEDUP", orig_speedup)
|
||||
|
||||
passed = True
|
||||
if ex is not None:
|
||||
passed = False
|
||||
|
|
Loading…
Reference in New Issue