autotest: bump default speedups for several vehicles

These tests seem to run stabley on my box with essentially no speedup
limit
This commit is contained in:
Peter Barker 2021-03-17 11:17:02 +11:00 committed by Peter Barker
parent 6f2de67ead
commit fdbbcaa506
5 changed files with 22 additions and 1 deletions

View File

@ -29,6 +29,10 @@ class AutoTestTracker(AutoTest):
def log_name(self): def log_name(self):
return "AntennaTracker" return "AntennaTracker"
def default_speedup(self):
'''Tracker seems to be race-free'''
return 100
def test_filepath(self): def test_filepath(self):
return os.path.realpath(__file__) return os.path.realpath(__file__)

View File

@ -6936,6 +6936,10 @@ class AutoTestHeli(AutoTestCopter):
def sitl_start_location(self): def sitl_start_location(self):
return SITL_START_LOCATION_AVC return SITL_START_LOCATION_AVC
def default_speedup(self):
'''Heli seems to be race-free'''
return 100
def is_heli(self): def is_heli(self):
return True return True

View File

@ -59,6 +59,10 @@ class AutoTestSub(AutoTest):
def log_name(self): def log_name(self):
return "ArduSub" return "ArduSub"
def default_speedup(self):
'''Sub seems to be race-free'''
return 100
def test_filepath(self): def test_filepath(self):
return os.path.realpath(__file__) return os.path.realpath(__file__)

View File

@ -1199,7 +1199,7 @@ class AutoTest(ABC):
binary, binary,
valgrind=False, valgrind=False,
gdb=False, gdb=False,
speedup=8, speedup=None,
frame=None, frame=None,
params=None, params=None,
gdbserver=False, gdbserver=False,
@ -1230,6 +1230,8 @@ class AutoTest(ABC):
self.breakpoints = breakpoints self.breakpoints = breakpoints
self.disable_breakpoints = disable_breakpoints self.disable_breakpoints = disable_breakpoints
self.speedup = speedup self.speedup = speedup
if self.speedup is None:
self.speedup = self.default_speedup()
self.sup_binaries = sup_binaries self.sup_binaries = sup_binaries
self.mavproxy = None self.mavproxy = None
@ -1277,6 +1279,9 @@ class AutoTest(ABC):
self.rc_thread.join() self.rc_thread.join()
self.rc_thread = None self.rc_thread = None
def default_speedup(self):
return 8
def progress(self, text, send_statustext=True): def progress(self, text, send_statustext=True):
"""Display autotest progress text.""" """Display autotest progress text."""
global __autotest__ global __autotest__

View File

@ -55,6 +55,10 @@ class AutoTestQuadPlane(AutoTest):
def sitl_start_location(self): def sitl_start_location(self):
return SITL_START_LOCATION return SITL_START_LOCATION
def default_speedup(self):
'''QuadPlane seems to be race-free'''
return 100
def log_name(self): def log_name(self):
return "QuadPlane" return "QuadPlane"