mirror of https://github.com/ArduPilot/ardupilot
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:
parent
6f2de67ead
commit
fdbbcaa506
|
@ -29,6 +29,10 @@ class AutoTestTracker(AutoTest):
|
|||
def log_name(self):
|
||||
return "AntennaTracker"
|
||||
|
||||
def default_speedup(self):
|
||||
'''Tracker seems to be race-free'''
|
||||
return 100
|
||||
|
||||
def test_filepath(self):
|
||||
return os.path.realpath(__file__)
|
||||
|
||||
|
|
|
@ -6936,6 +6936,10 @@ class AutoTestHeli(AutoTestCopter):
|
|||
def sitl_start_location(self):
|
||||
return SITL_START_LOCATION_AVC
|
||||
|
||||
def default_speedup(self):
|
||||
'''Heli seems to be race-free'''
|
||||
return 100
|
||||
|
||||
def is_heli(self):
|
||||
return True
|
||||
|
||||
|
|
|
@ -59,6 +59,10 @@ class AutoTestSub(AutoTest):
|
|||
def log_name(self):
|
||||
return "ArduSub"
|
||||
|
||||
def default_speedup(self):
|
||||
'''Sub seems to be race-free'''
|
||||
return 100
|
||||
|
||||
def test_filepath(self):
|
||||
return os.path.realpath(__file__)
|
||||
|
||||
|
|
|
@ -1199,7 +1199,7 @@ class AutoTest(ABC):
|
|||
binary,
|
||||
valgrind=False,
|
||||
gdb=False,
|
||||
speedup=8,
|
||||
speedup=None,
|
||||
frame=None,
|
||||
params=None,
|
||||
gdbserver=False,
|
||||
|
@ -1230,6 +1230,8 @@ class AutoTest(ABC):
|
|||
self.breakpoints = breakpoints
|
||||
self.disable_breakpoints = disable_breakpoints
|
||||
self.speedup = speedup
|
||||
if self.speedup is None:
|
||||
self.speedup = self.default_speedup()
|
||||
self.sup_binaries = sup_binaries
|
||||
|
||||
self.mavproxy = None
|
||||
|
@ -1277,6 +1279,9 @@ class AutoTest(ABC):
|
|||
self.rc_thread.join()
|
||||
self.rc_thread = None
|
||||
|
||||
def default_speedup(self):
|
||||
return 8
|
||||
|
||||
def progress(self, text, send_statustext=True):
|
||||
"""Display autotest progress text."""
|
||||
global __autotest__
|
||||
|
|
|
@ -55,6 +55,10 @@ class AutoTestQuadPlane(AutoTest):
|
|||
def sitl_start_location(self):
|
||||
return SITL_START_LOCATION
|
||||
|
||||
def default_speedup(self):
|
||||
'''QuadPlane seems to be race-free'''
|
||||
return 100
|
||||
|
||||
def log_name(self):
|
||||
return "QuadPlane"
|
||||
|
||||
|
|
Loading…
Reference in New Issue